diff --git a/LICENSE.txt b/LICENSE.txt index 40ee251..4da8180 100644 --- a/LICENSE.txt +++ b/LICENSE.txt @@ -310,36 +310,19 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in │   │   │   │   ├── hal_uart.h │   │   │   │   ├── hal_usb_bulk.c │   │   │   │   └── hal_usb_bulk.h -│   │   │   ├── nvidia_jetson -│   │   │   │   ├── application -│   │   │   │   │   ├── dji_sdk_app_info.h -│   │   │   │   │   ├── dji_sdk_config.h -│   │   │   │   │   └── main.c -│   │   │   │   ├── CMakeLists.txt -│   │   │   │   └── hal -│   │   │   │   ├── hal_i2c.c -│   │   │   │   ├── hal_i2c.h -│   │   │   │   ├── hal_network.c -│   │   │   │   ├── hal_network.h -│   │   │   │   ├── hal_uart.c -│   │   │   │   ├── hal_uart.h -│   │   │   │   ├── hal_usb_bulk.c -│   │   │   │   └── hal_usb_bulk.h -│   │   │   ├── raspberry_pi -│   │   │   │   ├── application -│   │   │   │   │   ├── dji_sdk_app_info.h -│   │   │   │   │   ├── dji_sdk_config.h -│   │   │   │   │   └── main.c -│   │   │   │   ├── CMakeLists.txt -│   │   │   │   └── hal -│   │   │   │   ├── hal_i2c.c -│   │   │   │   ├── hal_i2c.h -│   │   │   │   ├── hal_network.c -│   │   │   │   ├── hal_network.h -│   │   │   │   ├── hal_uart.c -│   │   │   │   ├── hal_uart.h -│   │   │   │   ├── hal_usb_bulk.c -│   │   │   │   └── hal_usb_bulk.h +│   │   │   └── nvidia_jetson +│   │   │   ├── application +│   │   │   │   ├── dji_sdk_app_info.h +│   │   │   │   ├── dji_sdk_config.h +│   │   │   │   └── main.c +│   │   │   ├── CMakeLists.txt +│   │   │   └── hal +│   │   │   ├── hal_network.c +│   │   │   ├── hal_network.h +│   │   │   ├── hal_uart.c +│   │   │   ├── hal_uart.h +│   │   │   ├── hal_usb_bulk.c +│   │   │   └── hal_usb_bulk.h │   │   └── rtos_freertos │   │   ├── common │   │   │   └── osal diff --git a/README.md b/README.md index 4b65f43..1bcb988 100644 --- a/README.md +++ b/README.md @@ -1,8 +1,8 @@ # DJI Payload SDK (PSDK) -![](https://img.shields.io/badge/version-V3.11.1-yellow.svg) -![](https://img.shields.io/badge/platform-linux_|_rtos-pink.svg) -![](https://img.shields.io/badge/license-MIT-red.svg) +![](https://img.shields.io/badge/version-V3.12.0-green.svg) +![](https://img.shields.io/badge/platform-linux_|_rtos-blue.svg) +![](https://img.shields.io/badge/license-MIT-orange.svg) ## What is the DJI Payload SDK? @@ -23,12 +23,48 @@ to get the latest version information. ## Latest Release -The latest release version of PSDK is 3.11.1. This version of Payload SDK mainly add some new features support and fixed some +The latest release version of PSDK is 3.12.0. This version of Payload SDK mainly add some new features support and fixed some bugs. Please refer to the release notes for detailed changes list. -* Fixed the issue where the Matrice 4D or Matrice 4TD E-Port Lite interface was not recognized on FlightHub 2. -* Fixed the crash issue when using the DjiCore_Delnit interface. -* Fixed the occasional crash issue when transmitting video streams through the USB bulk channel on Matrice 350 RTK. +### 1. Matrice 400 Feature Support +- **Added point cloud data subscription for LiDAR/millimeter-wave radar on aircraft.** +- **Added custom widget management.** +- **Added Expanded payload device support.** + Supports up to 7 payload devices simultaneously, compatible with: + - Skyport-V2 + - XPort + +### 2. Manifold 3 Now Supports: +- **Added AR image drawing function.** +- **Added Enhanced warning functionality.** +- **Added H30 camera image processing capabilities.** + - Together with Matrice 400, Manifold 3 can: + - Obtain decoded images from the H30 camera. + - Encode using a hardware encoder. + - Display AI recognition results in real time. +- **Added PSDK application development** + - Supports developing and packaging applications based on PSDK. + - Supports installing and running applications on Manifold 3. + +### 3. Matrice 4TD/4D Series Feature Optimization +- **Added cloud API firmware upgrade** + +### 4. E-PORT V2 Hardware Port Support +- **Adapter compatibility:** + - E-Port V2 coaxial cable + - Skyport V3 +- **Power management:** + - Supports voltage requests for 13.6V, 17V, and 24V. +- **Link models:** + - Added: ONLY_USB_BULK, ONLY_NETWORK. + - Not supported: UART_AND_NETWORK, UART_AND_USB_BULK. +- **Development support:** + - Released DJI E-Port V2 development kit. + - Documentation: Refer to the Quick Start > E-Port Quick Start section. + +### 5. Upgrade and Compatibility +#### SkyPort V2 and X-Port Software Upgrade +The software versions of Skyport V2 and X-Port have been upgraded. Devices need to be mounted on the Matrice 300 or Matrice 350 to be upgraded to the latest software version before they can be used on the Matrice 400 model. Subsequent software upgrades can be performed on the Matrice 400. ## License diff --git a/psdk_lib/include/dji_cloud_api_by_websockt.h b/psdk_lib/include/dji_cloud_api_by_websockt.h new file mode 100644 index 0000000..c0f187c --- /dev/null +++ b/psdk_lib/include/dji_cloud_api_by_websockt.h @@ -0,0 +1,60 @@ +/** + ******************************************************************** + * @file dji_cloud_api_by_websockt.h + * @brief This is the header file for "dji_cloud_api_by_websockt.h", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_CLOUD_API_BY_WEEBSOCKET_H +#define DJI_CLOUD_API_BY_WEEBSOCKET_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + +/** + * @brief Send data into cloud api channel over pilot2 websocket. + * @note This interface should be called only on manifold3 application. It is recommended + * to send more bytes of data at a time to improve read and write efficiency. Need to determine whether the send is + * successful according to the return code and the actual sent data length. + * @param data: pointer to data to be sent. + * @param len: length of data to be sented to pilot2, unit: byte. + * @param realLen: pointer to real length of data that already sent. + * @return Execution result. + */ +T_DjiReturnCode DjiCloudApi_SendDataByWebSocket(uint8_t *data, uint32_t len, uint32_t *realLen); +#ifdef __cplusplus +} +#endif + +#endif + +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ + diff --git a/psdk_lib/include/dji_fc_subscription.h b/psdk_lib/include/dji_fc_subscription.h index c687c2f..525f4fe 100644 --- a/psdk_lib/include/dji_fc_subscription.h +++ b/psdk_lib/include/dji_fc_subscription.h @@ -526,6 +526,153 @@ typedef enum { */ DJI_FC_SUBSCRIPTION_TOPIC_IMU_ATTI_NAVI_DATA_WITH_TIMESTAMP = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 48), + /*! + * @brief Provides postion NO.1 gimbal pitch, roll, yaw @ up to 50Hz + * @details + * The reference frame for gimbal angles is a NED frame attached to the gimbal. + * This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is : + * |Data Structure Element| Meaning| + * |----------------------|--------| + * |Vector3f.x |pitch | + * |Vector3f.y |roll | + * |Vector3f.z |yaw | + * + * @perf + * 0.1 deg accuracy in all axes + * + * @sensors Gimbal Encoder, IMU, Magnetometer + * @units deg + * @datastruct \ref T_DjiFcSubscriptionGimbalAngles + * @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE + */ + DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO1 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 48), + + /*! + * @brief Provides postion NO.2 gimbal pitch, roll, yaw @ up to 50Hz + * @details + * The reference frame for gimbal angles is a NED frame attached to the gimbal. + * This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is : + * |Data Structure Element| Meaning| + * |----------------------|--------| + * |Vector3f.x |pitch | + * |Vector3f.y |roll | + * |Vector3f.z |yaw | + * + * @perf + * 0.1 deg accuracy in all axes + * + * @sensors Gimbal Encoder, IMU, Magnetometer + * @units deg + * @datastruct \ref T_DjiFcSubscriptionGimbalAngles + * @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE + */ + DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO2 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 49), + + /*! + * @brief Provides postion NO.3 gimbal pitch, roll, yaw @ up to 50Hz + * @details + * The reference frame for gimbal angles is a NED frame attached to the gimbal. + * This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is : + * |Data Structure Element| Meaning| + * |----------------------|--------| + * |Vector3f.x |pitch | + * |Vector3f.y |roll | + * |Vector3f.z |yaw | + * + * @perf + * 0.1 deg accuracy in all axes + * + * @sensors Gimbal Encoder, IMU, Magnetometer + * @units deg + * @datastruct \ref T_DjiFcSubscriptionGimbalAngles + * @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE + */ + DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO3 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 50), + + /*! + * @brief Provides postion NO.4 gimbal pitch, roll, yaw @ up to 50Hz + * @details + * The reference frame for gimbal angles is a NED frame attached to the gimbal. + * This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is : + * |Data Structure Element| Meaning| + * |----------------------|--------| + * |Vector3f.x |pitch | + * |Vector3f.y |roll | + * |Vector3f.z |yaw | + * + * @perf + * 0.1 deg accuracy in all axes + * + * @sensors Gimbal Encoder, IMU, Magnetometer + * @units deg + * @datastruct \ref T_DjiFcSubscriptionGimbalAngles + * @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE + */ + DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO4 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 51), + + /*! + * @brief Provides postion NO.5 gimbal pitch, roll, yaw @ up to 50Hz + * @details + * The reference frame for gimbal angles is a NED frame attached to the gimbal. + * This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is : + * |Data Structure Element| Meaning| + * |----------------------|--------| + * |Vector3f.x |pitch | + * |Vector3f.y |roll | + * |Vector3f.z |yaw | + * + * @perf + * 0.1 deg accuracy in all axes + * + * @sensors Gimbal Encoder, IMU, Magnetometer + * @units deg + * @datastruct \ref T_DjiFcSubscriptionGimbalAngles + * @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE + */ + DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO5 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 52), + + /*! + * @brief Provides postion NO.6 gimbal pitch, roll, yaw @ up to 50Hz + * @details + * The reference frame for gimbal angles is a NED frame attached to the gimbal. + * This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is : + * |Data Structure Element| Meaning| + * |----------------------|--------| + * |Vector3f.x |pitch | + * |Vector3f.y |roll | + * |Vector3f.z |yaw | + * + * @perf + * 0.1 deg accuracy in all axes + * + * @sensors Gimbal Encoder, IMU, Magnetometer + * @units deg + * @datastruct \ref T_DjiFcSubscriptionGimbalAngles + * @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE + */ + DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO6 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 53), + + /*! + * @brief Provides postion NO.7 gimbal pitch, roll, yaw @ up to 50Hz + * @details + * The reference frame for gimbal angles is a NED frame attached to the gimbal. + * This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is : + * |Data Structure Element| Meaning| + * |----------------------|--------| + * |Vector3f.x |pitch | + * |Vector3f.y |roll | + * |Vector3f.z |yaw | + * + * @perf + * 0.1 deg accuracy in all axes + * + * @sensors Gimbal Encoder, IMU, Magnetometer + * @units deg + * @datastruct \ref T_DjiFcSubscriptionGimbalAngles + * @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE + */ + DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO7 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 54), + /*! Total number of topics that can be subscribed. */ DJI_FC_SUBSCRIPTION_TOPIC_TOTAL_NUMBER, } E_DjiFcSubscriptionTopic; diff --git a/psdk_lib/include/dji_flight_controller.h b/psdk_lib/include/dji_flight_controller.h index 3df46c1..36dc970 100644 --- a/psdk_lib/include/dji_flight_controller.h +++ b/psdk_lib/include/dji_flight_controller.h @@ -237,6 +237,17 @@ typedef enum { DJI_FLIGHT_CONTROLLER_DISABLE_RC_LOST_ACTION = 1, } E_DjiFlightControllerRCLostActionEnableStatus; +typedef enum { + DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE = 0, + DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE = 1, + DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE = 2, +} E_DjiFlightControllerElectronicSpeedControllerStatus; + +typedef enum { + DJI_FLIGHT_CONTROLLER_FTS_NOT_TRIGGERD = 0, + DJI_FLIGHT_CONTROLLER_FTS_TRIGGERD = 1, +} E_DjiFlightControllerFtsStatus; + /** * @brief Joystick mode. * @note You need to set joystick mode first before start to send joystick command to aircraft. @@ -274,6 +285,16 @@ typedef struct { #pragma pack() +typedef struct { + E_DjiMountPosition fts_select; + E_DjiFlightControllerFtsStatus fts_status; + uint8_t fts_pwm_cnt; /* correct number of PWM signals received */ +} T_DjiFtsPwmTriggerStatus; + +typedef struct { + T_DjiFtsPwmTriggerStatus ESC[2]; /* trigger status of the two ESCs */ +} T_DjiFtsPwmEscTriggerStatus; + /* Exported functions --------------------------------------------------------*/ /** * @brief Initialise flight controller module @@ -649,6 +670,38 @@ DjiFlightController_GetEnableRCLostActionStatus(E_DjiFlightControllerRCLostActio */ T_DjiReturnCode DjiFlightController_RegTriggerFtsEventCallback(TriggerFtsEventCallback callback); +/** + * @brief Start to rotate motors slowly. + * @return Execution result. + */ +T_DjiReturnCode DjiFlightController_StartSlowRotateMotor(void); + +/** + * @brief Stop to rotate motors slowly. + * @return Execution result. + */ +T_DjiReturnCode DjiFlightController_StopSlowRotateMotor(void); + +/** + * @brief Get the status of the ESC. + * @param status: The status of the motor on aircraft. + * @return Execution result. + */ +T_DjiReturnCode DjiFlightController_GetElectronicSpeedControllerStatus(E_DjiFlightControllerElectronicSpeedControllerStatus *status); + +/** + * @brief Select Fts pwm trigger. + * @param position: Pwm trigger source position. + * @return Execution result. + */ +T_DjiReturnCode DjiFlightController_SelectFtsPwmTrigger(E_DjiMountPosition position); + +/** + * @brief Get Fts pwm trigger status. + * @return Execution result. + */ +T_DjiReturnCode DjiFlightController_GetFtsPwmTriggerStatus(T_DjiFtsPwmEscTriggerStatus* trigger_status); + #ifdef __cplusplus } #endif diff --git a/psdk_lib/include/dji_hms_customization.h b/psdk_lib/include/dji_hms_customization.h index ec63c6f..0d0eb78 100644 --- a/psdk_lib/include/dji_hms_customization.h +++ b/psdk_lib/include/dji_hms_customization.h @@ -44,6 +44,18 @@ typedef enum { DJI_HMS_ERROR_LEVEL_FATAL, } E_DjiHmsErrorLevel; +typedef enum { + DJI_HMS_ALARM_ENHANCED_TYPE_SHAKE_MOTOR = 1, /*!< Alarm triggered by shaking the motor on the pilot; alerts the user with vibrations indicating a warning or fault. */ + DJI_HMS_ALARM_ENHANCED_PLAY_SOUND = 2, /*!< Alarm triggered by playing sound */ + DJI_HMS_ALARM_ENHANCED_PLAY_SOUND_AND_SHAKE_MOTOR =3, /*!< Alarm that alerts the user on the PILOT app with both sound and vibrations */ +} E_DjiHmsAlarmEnhancedType; + +typedef enum { + DJI_HMS_ALARM_ENHANCED_ACTION_STOP = 0, /*!< Action to stop a specific enhanced alarm, shake motor or play sound */ + DJI_HMS_ALARM_ENHANCED_ACTION_START = 1, /*!< Action to stop a specific enhanced alarm */ + DJI_HMS_ALARM_ENHANCED_ACTION_EXIT_ALL =2,/*!< Action to exit all enhanced alarms, both shake motor and play sound; */ +} E_DjiHmsAlarmEnhancedAction; + typedef struct { char *fileName; /*!< The file name of the hms text config file */ uint32_t fileSize; /*!< The file size of the hms text config file, uint : byte */ @@ -55,6 +67,12 @@ typedef struct { T_DjiHmsFileBinaryArray *fileBinaryArrayList; /*!< Pointer to binary array list */ } T_DjiHmsBinaryArrayConfig; +typedef struct { + E_DjiHmsAlarmEnhancedType type; /*!< The type is used to specify which enhanced alarm to ACTION_STOP or ACTION_START. It is ignored when EXIT_ALL alarms.*/ + int8_t times; /* !< Specifies the number of consecutive times the alarm is to be activated.*/ + int16_t interval; /* !< Indicates the interval (in milliseconds) between consecutive activations of the alarm.*/ +} T_DjiHmsAlarmEnhancedSetting; + /* Exported functions --------------------------------------------------------*/ /** * @brief Initialise hms customization module, and user should call this function @@ -124,6 +142,15 @@ T_DjiReturnCode DjiHmsCustomization_RegDefaultHmsTextConfigByBinaryArray(const T T_DjiReturnCode DjiHmsCustomization_RegHmsTextConfigByBinaryArray(E_DjiMobileAppLanguage appLanguage, const T_DjiHmsBinaryArrayConfig *binaryArrayConfig); +/** + * @brief Contrl the app alram. + * @note This interface support on DJI manifold3. + * @param action: The action to start or stop alarm. + * @param setting: The alarm information. + * @return Execution result. + */ +T_DjiReturnCode DjiHmsCustomization_AlarmEnhancedCtrl(E_DjiHmsAlarmEnhancedAction action, T_DjiHmsAlarmEnhancedSetting setting); + #ifdef __cplusplus } #endif diff --git a/psdk_lib/include/dji_interest_point.h b/psdk_lib/include/dji_interest_point.h index 00f3d9c..0b33a52 100644 --- a/psdk_lib/include/dji_interest_point.h +++ b/psdk_lib/include/dji_interest_point.h @@ -39,16 +39,23 @@ extern "C" { /* Exported constants --------------------------------------------------------*/ /* Exported types ------------------------------------------------------------*/ +typedef enum { + DJI_INTEREST_POINT_MISSION_ACTION_STATE_NOT_STARTED = 0, + DJI_INTEREST_POINT_MISSION_ACTION_STATE_PAUSE = 1, + DJI_INTEREST_POINT_MISSION_ACTION_STATE_RUNNING = 2, +} E_DjiInterestPointActionState; + typedef struct { dji_f32_t curSpeed; dji_f32_t radius; - uint8_t state; + uint8_t state; /*!< Refer to E_DjiInterestPointActionState.*/ } T_DjiInterestPointMissionState; typedef struct { dji_f64_t latitude; dji_f64_t longitude; dji_f32_t speed; + int8_t payloadCameraIndex; /*!< Used by which aircraft that can mount payload cameras. Range starts from 1.*/ } T_DjiInterestPointSettings; typedef T_DjiReturnCode (*InterestPointMissionStateCallback)(T_DjiInterestPointMissionState missionState); diff --git a/psdk_lib/include/dji_liveview.h b/psdk_lib/include/dji_liveview.h index 4f43d3f..d6764d7 100644 --- a/psdk_lib/include/dji_liveview.h +++ b/psdk_lib/include/dji_liveview.h @@ -47,6 +47,15 @@ typedef enum { DJI_LIVEVIEW_CAMERA_POSITION_FPV = 7 } E_DjiLiveViewCameraPosition; +/** + * @brief Image format. + */ +typedef enum { + PIXFMT_NV12 = 3, + PIXFMT_RGB_PLANAR = 4, + PIXFMT_RGB_PACKED = 5 +} E_DjiLiveViewPixFormate; + /** * @brief Liveview camera stream source. */ @@ -71,6 +80,8 @@ typedef enum { DJI_LIVEVIEW_CAMERA_SOURCE_M3D_VIS = 1, DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_VIS = 1, DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_IR = 2, + DJI_LIVEVIEW_CAMERA_SOURCE_H30_ZOOM = 1, + DJI_LIVEVIEW_CAMERA_SOURCE_H30_4K = 7, DJI_LIVEVIEW_CAMERA_SOURCE_M4E_VIS = 1, DJI_LIVEVIEW_CAMERA_SOURCE_M4T_VIS = 1, DJI_LIVEVIEW_CAMERA_SOURCE_M4T_IR = 2, @@ -79,11 +90,91 @@ typedef enum { DJI_LIVEVIEW_CAMERA_SOURCE_M4TD_IR = 2, } E_DjiLiveViewCameraSource; +/** + * @brief DJI standard types of target recognition. + */ +typedef enum { + DJI_LIVEVIEW_OBJ_TYPE_INVALID = 0, + DJI_LIVEVIEW_OBJ_TYPE_UNKNOWN = 1, + DJI_LIVEVIEW_OBJ_TYPE_PERSON = 2, + DJI_LIVEVIEW_OBJ_TYPE_CAR = 3, + DJI_LIVEVIEW_OBJ_TYPE_BOAT = 4, + DJI_LIVEVIEW_OBJ_TYPE_HUMAN_FACE = 5, + DJI_LIVEVIEW_OBJ_TYPE_BIRD = 10, + DJI_LIVEVIEW_OBJ_TYPE_BEACON = 20, + DJI_LIVEVIEW_OBJ_TYPE_GPS = 30, + DJI_LIVEVIEW_OBJ_TYPE_MOVING_TARGET = 34, +} E_DjiLiveViewTargetObjectType; + +/** + * @brief Target Recognition Status. + */ +typedef enum { + DJI_LIVEVIEW_OBJ_STATE_INVALID = 0, /*!< invalid state */ + DJI_LIVEVIEW_OBJ_STATE_TRACKED = 1, /*!< steady state following */ + DJI_LIVEVIEW_OBJ_STATE_VISION_BEACON_FUSIONED = 2, /*!< Vision beacon fusion state */ + DJI_LIVEVIEW_OBJ_STATE_AUXILIARY_TRACKED = 3, /*!< Loss of trigger source, auxiliary observation following state */ + DJI_LIVEVIEW_OBJ_STATE_NOT_CONFIDENT = 4, /*!< unstable following state */ + DJI_LIVEVIEW_OBJ_STATE_LOST_WITH_PREDICT = 5, /*!< Target lost, forecast status maintained */ + DJI_LIVEVIEW_OBJ_STATE_LOST = 6, /*!< Target Loss Status */ + DJI_LIVEVIEW_OBJ_STATE_REDETECTED = 7, /*!< Target Loss Retrieval Status */ +} E_DjiLiveViewTargetObjectState; + +/** + * @brief Picture frame information for target recognition results + */ +typedef struct +{ + uint16_t cx; /*!< X-coordinate of the center of the frame, unit: 1/10000 * screen width */ + uint16_t cy; /*!< Y-coordinate of the center of the frame, unit: 1/10000 * screen height */ + uint16_t w; /*!< Frame width, unit: 1/10000 * screen width */ + uint16_t h; /*!< Frame height, unit: 1/10000 * screen height */ + uint32_t distance; /*!< Distance in mm */ +} __attribute__((packed)) T_DjiLiveViewTarget2dBox; + +/** + * @brief BoundingBox information for target recognition. + */ +typedef struct { + uint16_t id; + uint8_t type; /*!< type can be an enumerated value of E_DjiLiveViewTargetObjectType or a user-defined value. */ + uint8_t state; /*!< state should be of type E_DjiLiveViewTargetObjectState enumeration */ + T_DjiLiveViewTarget2dBox box; +} __attribute__((packed)) T_DjiLiveViewBoundingBox; + +/** + * @brief List of boundingBox information. + */ +typedef struct { + uint8_t boxCount; + T_DjiLiveViewBoundingBox boxData[1]; +} __attribute__((packed)) T_DjiLiveViewStandardMetaData; + +/** + * @brief Image information. + */ +typedef struct { + E_DjiLiveViewPixFormate pixFmt; + uint16_t width; + uint16_t height; + uint32_t frameId; +} T_DjiLiveviewImageInfo; + /** * @brief Liveview camera h264 stream callback. */ typedef void (*DjiLiveview_H264Callback)(E_DjiLiveViewCameraPosition position, const uint8_t *buf, uint32_t len); +/** + * @brief Liveview camera image data callback. + */ +typedef void (*DjiLiveview_ImageCallback)(E_DjiLiveViewCameraPosition position, const uint8_t *buf, + uint32_t len , T_DjiLiveviewImageInfo ImageInfo); + +/** + * @brief Callback for handling encoded output data + */ +typedef void (*DjiLiveview_EncoderCallback)(const uint8_t *buf, uint32_t len); /* Exported functions --------------------------------------------------------*/ /** * @brief Initialize the liveview module. @@ -125,6 +216,81 @@ T_DjiReturnCode DjiLiveview_StopH264Stream(E_DjiLiveViewCameraPosition position, T_DjiReturnCode DjiLiveview_RequestIntraframeFrameData(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source); +/** + * @brief Request to get the decoded image data from the specified position. + * @param position: Camera position for the H264 stream. + * @param source: sub-camera source for the H264 stream. + * @param pixFmt: Requested Image Format. + * @param callback: Callback for handling image data. + * @return Execution result. + * @note This interface support on DJI manifold3. + */ +T_DjiReturnCode DjiLiveview_StartImageStream(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source, + E_DjiLiveViewPixFormate pixFmt, DjiLiveview_ImageCallback callback); + +/** + * @brief Stop the decoded image data from the specified position. + * @param position: Camera position for the H264 stream. + * @param source: sub-camera source for the H264 stream. + * @return Execution result. + * @note This interface support on DJI manifold3. + */ +T_DjiReturnCode DjiLiveview_StopImageStream(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source); + +/** + * @brief Registering encoder callback handlers. + * @return Execution result. + * @note This interface support on DJI manifold3. + */ +T_DjiReturnCode DjiLiveview_RegEncoderCallback(DjiLiveview_EncoderCallback callback); + +/** + * @brief Unregistering encoder callback handlers. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_UnregEncoderCallback(); + +/** + * @brief Encoding image into h264 streams. + * @param buf: raw data of image. + * @param len: length of image data. + * @param imageInfo: information of image. + * @param metaData: Resulting information obtained from images for target recognition. + * @return Execution result. + * @note If there is no need for information related to target identification, fill in NULL for metaData. + * @note This interface needs to be used after DjiLiveview_RegEncoderCallback. + * @note This interface support on DJI manifold3. + */ +T_DjiReturnCode DjiLiveview_EncodeAFrameToH264(const uint8_t *buf, uint32_t len, T_DjiLiveviewImageInfo imageInfo, + T_DjiLiveViewStandardMetaData *metaData); + +/** + * @brief Register user-defined target Lables + * @param lableCount: Number of lable. + * @param labels: lable String Array + * @note The key-value pairs of lable and index will be recorded on the Pilot after registration + * and will be used to parse the metaData and display the lable when rendering the boundingbox. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_RegUserAiTargetLableList(uint8_t lableCount,const char *labels[]); + +/** + * @brief Unregister user-defined target Lables + * @return Execution result. + * @note This interface support on DJI manifold3. + */ +T_DjiReturnCode DjiLiveview_UnregUserAiTargetLableList(); + +/** + * @brief Transmits the result information of the target recognition to the pilot for display. + * @param metaData: Resulting information obtained from images for target recognition. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_SendAiMetaToPilot(T_DjiLiveViewStandardMetaData *metaData); + + #ifdef __cplusplus } #endif diff --git a/psdk_lib/include/dji_logger.h b/psdk_lib/include/dji_logger.h index 0ee2142..128d753 100644 --- a/psdk_lib/include/dji_logger.h +++ b/psdk_lib/include/dji_logger.h @@ -102,14 +102,24 @@ T_DjiReturnCode DjiLogger_RemoveConsole(T_DjiLoggerConsole *console); void DjiLogger_UserLogOutput(E_DjiLoggerConsoleLogLevel level, const char *fmt, ...); /* Exported constants --------------------------------------------------------*/ +#define __FILENAME__ (strrchr("/" __FILE__, '/') + 1) + +#define USER_LOG_PREFIX_FMT "%25s:%-4d " + +#ifndef SYSTEM_ARCH_RTOS +#define USER_LOG_PREFIX_ARG __FILENAME__, __LINE__ +#else +#define USER_LOG_PREFIX_ARG __FUNCTION__, __LINE__ +#endif + #define USER_LOG_DEBUG(fmt, ...) \ - DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__) + DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__) #define USER_LOG_INFO(fmt, ...) \ - DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__) + DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__) #define USER_LOG_WARN(fmt, ...) \ - DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_WARN, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__) + DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_WARN, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__) #define USER_LOG_ERROR(fmt, ...) \ - DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_ERROR, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__) + DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_ERROR, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__) #ifdef __cplusplus } diff --git a/psdk_lib/include/dji_open_ar.h b/psdk_lib/include/dji_open_ar.h new file mode 100644 index 0000000..a04c64a --- /dev/null +++ b/psdk_lib/include/dji_open_ar.h @@ -0,0 +1,389 @@ +/** + ******************************************************************** + * @file dji_open_ar.h + * @brief This is the header file for "dji_open_ar.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_OPEN_AR_H +#define DJI_OPEN_AR_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +typedef struct +{ + float longitude; + float latitude; + float altitude; +} T_DjiOpenArCoordinate; + +/** + * @brief Text information definition + */ +typedef struct +{ + uint8_t is_show:1; /*!< Whether to display, 0: not display, 1: display */ + uint8_t text[30]; /*!< Text information, with '\0' as the terminator */ +} T_DjiOpenArTextAttribute; + +typedef struct +{ + uint8_t selected:1; /*!< Whether selected, 0: not selected, 1: selected */ + uint8_t visible :1; /*!< Whether to display, 0: not display, 1: display */ + uint32_t color; /*!< Contains alpha channel */ +} T_DjiOpenArIconAttribute; + +/** +* @brief Click action for a point +*/ +typedef struct +{ + uint8_t action; /*!< 0: click; 1: drag along the line; 2: drag from a distance */ + T_DjiOpenArCoordinate normal_vector; /*!< Dragging direction: normal vector */ +} T_DjiOpenArTouchAttribute; + +/** + * @brief Represents the unique identifier for AR elements + */ +typedef struct +{ + uint32_t uuid; /*!< uuid used for updating and deleting */ + uint32_t style_id; /*!< used to index resources config, corresponding resource is configured in widget.json */ +} T_DjiOpenArIds; + +/** + * @brief AR face drawing attributes + */ +typedef struct +{ + uint8_t dist_alpha_enable :1; /*!< Enable distance-based alpha blending (1) or not (0) */ + uint8_t face_bottom_enable:1; /*!< Enable drawing bottom face (1) or not (0) */ + uint8_t face_side_enable :1; /*!< Enable drawing side face (1) or not (0) */ + uint8_t face_top_enable :1; /*!< Enable drawing top face (1) or not (0) */ +} T_DjiOpenArPolygonFaceAttribute; + +/** + * @brief AR border drawing attributes + */ +typedef struct +{ + uint8_t top_show :1; + uint8_t top_dist_alpha_enable :1; + uint8_t side_show :1; + uint8_t side_dist_alpha_enable :1; + uint8_t bottom_show :1; + uint8_t bottom_dist_alpha_enable:1; +} T_DjiOpenArPolygonStrokeAttribute; + +/** + * @brief AR pint drawing attibutes + */ +typedef struct +{ + uint32_t uuid; /*!< uuid for point , used to updating and delting */ + uint32_t style_id; /*!< dentifier for the style associated with the point, define with widget.json */ + uint32_t resource_id; /*!< Identifier for the resource associated with the point */ + uint8_t is_always_in_edge; /*!< Whether the point is always on the edge */ + T_DjiOpenArCoordinate coordinate; /*!< Physical position in the world coordinate system */ + T_DjiOpenArTextAttribute text_attr; /*!< Attributes related to the text associated with the point */ + T_DjiOpenArIconAttribute icon_attr; /*!< Attributes related to the icon associated with the point */ + T_DjiOpenArTouchAttribute touch_attr; /*!< Attributes related to touch interactions with the point */ +} T_DjiOpenArPoint; + +/** + * @brief Array of points + */ +typedef struct +{ + uint32_t len; /*!< Length of the array (number of points) */ + T_DjiOpenArPoint points[0]; /*!< 0 length implies dynamic allocation */ +} T_DjiOpenArPointArray; + +/** + * @biref AR Drawing Line + */ +typedef struct +{ + T_DjiOpenArIds ids; /*!< uuids for the AR line */ + T_DjiOpenArPointArray point_array; /*!< Array of points defining the line */ +} T_DjiOpenArLine; + +/** + * @brief AR Drawing Polygon + */ +typedef struct +{ + T_DjiOpenArIds ids; /*!< Unique identifiers for the AR polygon */ + T_DjiOpenArCoordinate normal_vector; /*!< Normal vector of the polygon surface */ + T_DjiOpenArPolygonFaceAttribute face; /*!< Face attributes of the polygon */ + T_DjiOpenArPolygonStrokeAttribute stroke; /*!< Stroke attributes of the polygon */ + T_DjiOpenArPointArray point_array; /*!< Array of points defining the polygon */ +} T_DjiOpenArPolygon; + +/** + * @brief AR Drawing Circle + */ +typedef struct +{ + T_DjiOpenArIds ids; /*!< Unique identifiers for the AR circle */ + float radius; /*!< Radius of the circle */ + T_DjiOpenArCoordinate center; /*!< Center coordinates of the circle */ + T_DjiOpenArCoordinate normal_vector; /*!< Normal vector of the circle's surface */ + T_DjiOpenArPolygonFaceAttribute face; /*!< Face attributes of the circle */ + T_DjiOpenArPolygonStrokeAttribute stroke; /*!< Stroke attributes of the circle */ +} T_DjiOpenArCircle; + +/** + * @brief AR Drawing 3D Cone Pivot Axis + */ +typedef struct +{ + T_DjiOpenArIds ids; /*!< Unique identifiers for the 3D cone */ + uint8_t show_enable; /*!< Flag indicating if the cone should be displayed (1) or not (0) */ + T_DjiOpenArCoordinate pivot; /*!< Center point of the cone */ + T_DjiOpenArCoordinate normal_vector; /*!< Normal vector for the cone's surface */ +} T_DjiOpenArPivotAxis; + +/** + * @brief eletion Entry for Specified Point, Face, Line, etc. + */ +typedef struct +{ + uint32_t resource_id; /*!< Resource ID for the element to be deleted */ + uint32_t uuid_len; /*!< Length of the UUID array */ + uint32_t uuid_array[0]; /*!< Array of UUIDs to identify the elements to be deleted */ +} T_DjiOpenArDeletePointEntry; + +typedef struct +{ + uint32_t uuid; +} T_DjiOpenArDeleteCommonEntry; + +/** + * @brief Typedef for deletion of line entries + */ +typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeleteLineEntry; + +/** + * @brief Typedef for deletion of polygon entries + */ +typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeletePolygonEntry; + +/** + * @brief Typedef for deletion of circle entries + */ +typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeleteCircleEntry; + +/** + * @brief Typedef for deletion of pivot axis entries + */ +typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeletePovixAxisEntry; + +/** + * @brief Set the ar point. + * @param metaData: the information for Ar point. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArSetPoint(const T_DjiOpenArPointArray* entry); + +/** + * @brief Update the ar point. + * @param metaData: the information for Ar point. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArUpdatePoint(const T_DjiOpenArPointArray* entry); + +/** + * @brief Delete the ar point + * @param metaData: the information for Ar point. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArDeletePoint(const T_DjiOpenArDeletePointEntry* entry); + +/** + * @brief Clear the ar point + * @param metaData: the resource id for Ar point. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArClearPoint(uint32_t resource_id); + +/** + * @brief Set the ar line + * @param metaData: the ar line information for setting. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArSetLine(const T_DjiOpenArLine* entry); + +/** + * @brief Update the ar line + * @param metaData: The ar line information + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArUpdateLine(const T_DjiOpenArLine* entry); + +/** + * @brief Delete the ar line + * @param metaData: The ar line entry for delete + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArDeleteLine(const T_DjiOpenArDeleteLineEntry* entry, uint32_t entry_len); + +/** + * @brief Clear the ar line. + * @param metaData: The ar line information for clear. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArClearLine(); + +/** + * @brief Set the ar polygon. + * @param metaData: The ar polygon information for setting. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArSetPolygon(const T_DjiOpenArPolygon* entry); + +/** + * @brief Update the ar polygon. + * @param metaData: The ar polygon information for update. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArUpdatePolygon(const T_DjiOpenArPolygon* entry); + +/** + * @brief Delete the ar polygon. + * @param metaData: The polygon entry information for delete. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArDeletePolygon(const T_DjiOpenArDeletePolygonEntry* entry, uint32_t entry_len); + +/** + * @brief Clear the ar polygon. + * @param metaData: none + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArClearPolygon(); + +/** + * @brief Set the ar circle. + * @param metaData: The ar circle information for setting. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArSetCircle(const T_DjiOpenArCircle* entry); + +/** + * @brief Update the ar circle. + * @param metaData: The ar circle information for update. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArUpdateCircle(const T_DjiOpenArCircle* entry); + +/** + * @brief Delete the ar circle. + * @param metaData: The ar circle information for delete. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArDeleteCircle(const T_DjiOpenArDeleteCircleEntry* entry, uint32_t entry_len); + +/** + * @brief Clear the ar circle. + * @param metaData: The ar circle information for clear. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArClearCircle(); + +/** + * @brief Set the pivot axis. + * @param metaData: The pivot axis information for setting. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArSetPivotAxis(const T_DjiOpenArPivotAxis* entry); + +/** + * @brief Update the pivot axis. + * @param metaData: The pivot axis information for update. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArUpdatePivotAxis(const T_DjiOpenArPivotAxis* entry); + +/** + * @brief Delete the pivot axis. + * @param metaData: The pivot axis information for delete. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArDeletePivotAxis(const T_DjiOpenArDeletePovixAxisEntry* entry, uint32_t entry_len); + +/** + * @brief Clear the pivot axis. + * @param metaData: none + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArClearPivotAxis(); + +/** + * @brief Once entering this callback it is necessary to reflesh all AR drawings. + * @param metaData: none + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +typedef void (*DjiLiveview_ArRefleshAllCallback)(void); + +/** + * @brief Register the ar refresh function. + * @param metaData: The ar reflesh callback function. + * @note This interface support on DJI manifold3. + * @return Execution result. + */ +T_DjiReturnCode DjiLiveview_ArRegRefleshAllCallback(DjiLiveview_ArRefleshAllCallback callback); + +#ifdef __cplusplus +} +#endif + +#endif // DJI_OPEN_AR_H diff --git a/psdk_lib/include/dji_payload_camera.h b/psdk_lib/include/dji_payload_camera.h index 6bec055..8a2e701 100644 --- a/psdk_lib/include/dji_payload_camera.h +++ b/psdk_lib/include/dji_payload_camera.h @@ -173,6 +173,8 @@ typedef struct { bool isShootingIntervalStart; /*!< Specifies if the camera is in interval shooting start status. This parameter is boolean type. */ uint16_t currentPhotoShootingIntervalTimeInSeconds; /*!< Specifies the current interval shoot countdown time, the value is decreasing, * when the value equals to zero trigger the interval take photo, uint:s. */ + uint16_t currentPhotoShootingIntervalTimeInMs; /*!< Specifies the current interval shoot countdown time of millisecond part, the value is decreasing, + * when the value equals to zero trigger the interval take photo, uint:ms. */ uint16_t currentPhotoShootingIntervalCount; /*!< Specifies the current interval photo count, the value is decreasing step by one from * the setted count when interval taking photo */ bool isRecording; /*!< Specifies if the camera is in recording status. This parameter is boolean type. */ @@ -841,7 +843,7 @@ T_DjiReturnCode DjiPayloadCamera_RegMediaDownloadPlaybackHandler(const T_DjiCame * @param len: length of data to be sent via data stream, and it must be less than or equal to 65000, unit: byte. * @return Execution result. */ -T_DjiReturnCode DjiPayloadCamera_SendVideoStream(const uint8_t *data, uint16_t len); +T_DjiReturnCode DjiPayloadCamera_SendVideoStream(const uint8_t *data, uint32_t len); /** * @brief Get data transmission state of "videoStream" channel. User can use the state as base for controlling data diff --git a/psdk_lib/include/dji_perception.h b/psdk_lib/include/dji_perception.h index 3dfd258..ee2e4d1 100644 --- a/psdk_lib/include/dji_perception.h +++ b/psdk_lib/include/dji_perception.h @@ -39,6 +39,8 @@ extern "C" { #define DJI_PERCEPTION_INTRINSICS_PARAM_ARRAY_NUM 9 #define DJI_PERCEPTION_ROTATION_PARAM_ARRAY_NUM 9 #define DJI_PERCEPTION_TRANSLATION_PARAM_ARRAY_NUM 3 +#define DJI_PTS_NUM_PER_PKG 96 +#define DJI_LIDAR_PKG_BUFFER_NUM 564 /* Exported types ------------------------------------------------------------*/ /** @@ -71,6 +73,19 @@ typedef enum { RECTIFY_RIGHT_RIGHT = 26 } E_DjiPerceptionCameraPosition; +/** + * @bref Perception radar design location + */ +typedef enum { + RADAR_POSITION_LEFT = 0, + RADAR_POSITION_RIGHT = 1, + RADAR_POSITION_DOWN =2, + RADAR_POSITION_UP = 3, + RADAR_POSITION_FRONT = 4, + RADAR_POSITION_BACK =5, + MAX_RADAR_NUM = 6, +}E_DjiPerceptionRadarPosition; + #pragma pack(1) /** * @bref Perception camera ram image info @@ -114,14 +129,217 @@ typedef struct { uint32_t directionNum; T_DjiPerceptionCameraParameters cameraParameters[IMAGE_MAX_DIRECTION_NUM]; } T_DjiPerceptionCameraParametersPacket; + +/** + * @bref Perception Lidar data point info + */ +typedef struct{ + float x; /*!< unit: meters */ + float y; /*!< unit: meters */ + float z; /*!< unit: meters */ + uint8_t intensity; + uint8_t label; /*!< Noise filtering results (0: obj; 1: noise; 2: unknow; 3: not_retuen ) */ +} T_DJIPerceptionLidarPoint; + +/** + * @bref Perception Lidar data header of each pkg + */ +typedef struct{ + uint16_t timeInterval; /*!< The point cloud sampling time (in 0.1us) */ + uint16_t dotNum; /*!< Current packet data field contains the number of points This field is not valid for non-repeat scans*/ + uint8_t dataType; /** dataType + * + * Bit Position (7-4) | Field Name | Description | Remarks + * ------------------ | ------------ | -------------------- | ------------------------------------------------- + * 4-7 | echo_mode | Echo Mode | 0: Single echo mode + * | | | 1: Dual echo mode + * | | | 2: Triple echo mode + * | | | 3: Quadruple echo mode + * | | | 4: Quintuple echo mode + * + * Bit Position (3-0) | Field Name | Description | Remarks + * ------------------ | ------------ | -------------------- | ------------------------------------------------- + * 0-3 | data_type | Data Type | 40: IMU Data + * | | | 1: Point cloud data (rectangular, 32-bit) + * | | | 2: Point cloud data (rectangular, 16-bit default) + * | | | 3: Point cloud data (spherical) + * | | | 4: Point cloud data (rectangular, 20-bit, in use) + */ + uint8_t timeType; /** timeType + * Timestamp Type | Sync Source Type | Data Format | Description + * -------------- | ------------------- | ------------- | ------------------------------------------------- + * 0 | No sync source, | uint64_t | Timestamp is radar uptime, unit: ns + * | | | + * 1 | gPTP/PTP sync, | uint64_t | Timestamp is master clock source time, unit: ns + * | | | + * 2 | PPS + ns time sync | uint64_t | Unit: ns + * | | | + * 3 | PPS + UTC | uint64_t | UTC format is: + * | | struct | struct { + * | | | uint8_t year; + * | | | uint8_t mon; + * | | | uint8_t day; + * | | | uint8_t hour; + * | | | uint32_t us_offset; + * | | | }; + */ + uint64_t timeStamp; +}T_DJIPerceptionLidarDataHeader; + +/** + * @bref Perception Lidar data pkg + */ +typedef struct{ + T_DJIPerceptionLidarDataHeader header; + T_DJIPerceptionLidarPoint points[DJI_PTS_NUM_PER_PKG]; +}T_DjiPerceptionLidarDecodePkg; + +/** + * @bref Perception Lidar data frame + */ +typedef struct{ + uint64_t timeStampNs; /*!< Timestamp of the first point of each packet */ + uint32_t frameCnt; /*!< in increasing order from zero */ + uint16_t pkgNum; /*!< Number of valid pkgs per frame */ + T_DjiPerceptionLidarDecodePkg pkgs[DJI_LIDAR_PKG_BUFFER_NUM]; + uint32_t poseTimeMs; + uint16_t naviFlag; /** naviFlag: + * Bit Position | Field Name | Description | Remarks + * ------------ | ---------- | ------------------------------------------------ | ----------------------------------- + * 0 | vel_x | Horizontal x-axis velocity valid bit (1 valid) | 1 - valid, 0 - invalid + * 1 | vel_y | Horizontal y-axis velocity valid bit (1 valid) | 1 - valid, 0 - invalid + * 2 | vel_z | Vertical velocity valid bit (1 valid) | 1 - valid, 0 - invalid + * 3 | pos_x | Horizontal x-axis position valid bit (1 valid) | 1 - valid, 0 - invalid + * 4 | pos_y | Horizontal y-axis position valid bit (1 valid) | 1 - valid, 0 - invalid + * 5 | pos_z | Vertical position valid bit (1 valid) | 1 - valid, 0 - invalid + * 6 | dwn_vz | Ground speed valid bit (1 valid) | 1 - valid, 0 - invalid + * 7 | dwn_pz | Ground elevation valid bit (1 valid) | 1 - valid, 0 - invalid + * 8 | rtk_pxy | RTK horizontal valid flag (1 valid) | 1 - valid, 0 - invalid + * 9 | rtk_pz | RTK vertical valid flag (1 valid) | 1 - valid, 0 - invalid + * 10 | gns_ll | GPS horizontal valid flag (1 valid) | 1 - valid, vertical direction always invalid + * 11 | fg_ok | FG estimate OK flag (1 valid) | 1 - valid, 0 - invalid + * 12-15 | fg_st | FG mode (4 bits) | Modes: + * | | | 0 - Random initialization + * | | | 1 - Initialization with poor compass + * | | | 2 - Initialization with good compass + * | | | 3 - Magnetic inclination compensation + * | | | 4 - Compass fix during takeoff + * | | | 5 - Compass fix in the air + * | | | 6 - Compass calibration fix + * | | | 7 - Accelerometer alignment + * | | | 8 - Speed alignment + * | | | 9 - RTK heading alignment + */ + float naviPos[3]; /*!< UAV IMU to navigation coordinate system translation vector (xyz) */ + float naviQuat[4]; /*!< Quaternions from UAV IMU to navigation coordinate system */ +}T_DjiLidarFrame; + +/** + * @bref Radar data frame header + */ +typedef struct { + uint16_t dataLen; + uint8_t curPack; /*!< The current packet number, in the range of [1, pack_num]. */ + uint8_t packNum; /*!< Total number of current circle packets, starting from 1. */ +} T_DjiRadarDataHeader; + +/** + * @bref Radar information structure + */ +typedef struct { + uint64_t velocity :16; /** + * Calculating the actual velocity: + * + * Actual velocity (m/s) = (Velocity - 32767) / 100 + * + * Interpreting the results: + * - If the result is > 0, it indicates that the object is moving closer to the target. + * - If the result is < 0, it indicates that the object is moving away from the target. + */ + uint64_t snr :7; /*!< target SNR, in db, ranging from 0 to 127, with 0 being the null point or no echo point + (base_noise calculation base_noise = energy / snr) */ + uint64_t beamAngle:10; /** + * Beam emission angle value: + * - Unit: 0.01 degrees + * - Stored range: 0~1023 + * - Actual value range: [-45°, 45°] + * + * Conversion method: + * - Divide stored value x by 10 + * - If x ≤ 450, the angle remains unchanged + * - If x > 450, the angle is adjusted by subtracting 90 + * + * Examples: + * - Stored value of 449 yields an angle of 44.9° (449/10 = 44.9°) + * - Stored value of 451 yields an angle of -44.9° (451/10 - 90 = -44.9°) + * invalid in M400 + */ + + uint64_t radarType:3; /*!< Radar numbe,is invalid in M400*/ + + uint64_t clitterFlag:1; /*!< Flag for clutter point in planar radar: 1 indicates a clutter point, 0 indicates a valid point */ + + uint64_t reserved :27; +} T_DjiRadarBaseInfo; + +/** + * @bref The single point data structure of millimeter wave radar + */ +typedef struct { + uint16_t azimuth; /*! + * Target azimuth in radar coordinate system: + * - Unit: 0.001 radian + * - Value range: (0 to 2π) / 0.001 + * - Calculation method (azimuth/1000 - 2π) + */ + uint16_t elevation; /*! + * Target pitch angle in radar coordinate system: + * - Unit: 0.001 radian + * - Value range: (0 to 2π) / 0.001 + * - Calculation method (elevation/1000 - 2π) + */ + uint16_t radius; /*! + * Target radial distance in radar coordinate system: + * - Unit: 0.01 meters + * - Value range: 0 to 65553 (in steps of 0.01 meters) + */ + uint16_t ene; /*! + * Radar target energy + * - Actual value: energy / 100 + * - invalid in M400 + */ + T_DjiRadarBaseInfo base_info; +}T_DjiRadarCloudUnit; + +/** + * @bref Perception Radar data frame + */ +typedef struct { + T_DjiRadarDataHeader headInfo; + T_DjiRadarCloudUnit data[1]; +} T_DjiRadarDataFrame; + #pragma pack() /** * @bref Callback type to receive stereo camera image + * @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss. */ typedef void(*DjiPerceptionImageCallback)(T_DjiPerceptionImageInfo imageInfo, uint8_t *imageRawBuffer, uint32_t bufferLen); +/** + * @bref Callback type to receive radar data + * @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss. + */ +typedef void(*DjiPerceptionRadarCallback)(E_DjiPerceptionRadarPosition radarPosition, uint8_t *radarDataBuffer, + uint32_t bufferLen); +/** + * @bref Callback type to process Lidar data + * @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss. + */ +typedef void(*DjiPerceptionLidarDataCallback)(uint8_t* lidarDataBuffer, uint32_t bufferLen); + /* Exported functions --------------------------------------------------------*/ /** * @brief Initialize the perception module. @@ -147,18 +365,44 @@ T_DjiReturnCode DjiPerception_SubscribePerceptionImage(E_DjiPerceptionDirection /** * @brief Unsubscribe the raw image of both stereo cameras in the same direction. - * @param direction: direction to specify the direction of the subscription. Ref to E_DjiPerceptionDirection + * @param direction: direction to specify the direction of the subscription. Ref to E_DjiPerceptionDirection. * @return Execution result. */ T_DjiReturnCode DjiPerception_UnsubscribePerceptionImage(E_DjiPerceptionDirection direction); - /** * @brief Get the internal and external parameters of all stereo cameras. * @return Execution result. */ T_DjiReturnCode DjiPerception_GetStereoCameraParameters(T_DjiPerceptionCameraParametersPacket *packet); +/** + * @brief Subscribe the lidar data. + * @param callback: callback to observer the radar data. + * @return Execution result. + */ +T_DjiReturnCode DjiPerception_SubscribeLidarData(DjiPerceptionLidarDataCallback callback); + +/** + * @brief Unsubscribe the lidar data. + * @return Execution result. + */ +T_DjiReturnCode DjiPerception_UnsubscribeLidarData(void); + +/** + * @brief Subscribe the lidar data of the position. + * @param position: position the radar monted + * @param callback callback to observer the radar data. + * @return Execution result. + */ +T_DjiReturnCode DjiPerception_SubscribeRadarData(E_DjiPerceptionRadarPosition position, DjiPerceptionRadarCallback callback); + +/** + * @brief Unsubscribe the lidar data of the position. + * @param position: position the radar monted + * @return Execution result. + */ +T_DjiReturnCode DjiPerception_UnsubscribeRadarData(E_DjiPerceptionRadarPosition position); #ifdef __cplusplus } #endif diff --git a/psdk_lib/include/dji_platform.h b/psdk_lib/include/dji_platform.h index 5244350..c116ad7 100644 --- a/psdk_lib/include/dji_platform.h +++ b/psdk_lib/include/dji_platform.h @@ -109,6 +109,7 @@ typedef enum { typedef enum { DJI_HAL_USB_BULK_NUM_0 = 0, DJI_HAL_USB_BULK_NUM_1, + DJI_HAL_USB_BULK_NUM_2, DJI_HAL_USB_BULK_NUM_MAX, } E_DjiHalUsbBulkNum; @@ -138,6 +139,11 @@ typedef struct { bool isDir; } T_DjiFileInfo; +typedef struct { + uint16_t pid; + uint16_t vid; +} T_DjiHalUartDeviceInfo; + typedef struct { T_DjiReturnCode (*UartInit)(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle); @@ -148,6 +154,13 @@ typedef struct { T_DjiReturnCode (*UartReadData)(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode (*UartGetStatus)(E_DjiHalUartNum uartNum, T_DjiUartStatus *status); + + /** + * Get the device info of USB uart (virtual com or TTL-To-USB) which directly connected to UAV. + * Use for SDK adapter type Eport V2 ribbon cable. + * When using other types of interface, it is not necessary to implement this member function. + */ + T_DjiReturnCode (*UartGetDeviceInfo)(T_DjiHalUartDeviceInfo *deviceInfo); } T_DjiHalUartHandler; typedef struct { diff --git a/psdk_lib/include/dji_power_management.h b/psdk_lib/include/dji_power_management.h index 8961535..36c9f22 100644 --- a/psdk_lib/include/dji_power_management.h +++ b/psdk_lib/include/dji_power_management.h @@ -45,6 +45,12 @@ typedef enum { DJI_POWER_MANAGEMENT_PIN_STATE_SET = 1, /*!< Specifies pin is in high level state. */ } E_DjiPowerManagementPinState; +typedef enum { + E_DJI_HIGH_POWER_VOLTAGE_13V6 = 0, /*!< Specifies pin is in 13.6V of voltage */ + E_DJI_HIGH_POWER_VOLTAGE_17V = 1, /*!< Specifies pin is in 17V of voltage */ + E_DJI_HIGH_POWER_VOLTAGE_24V = 2, /*!< Specifies pin is in 24V of voltage */ +} E_DjiHighPowerVoltage; + /** * @brief Prototype of callback function used to set level of high power application pin. * @param pinState: level state of pin to be set. @@ -87,6 +93,17 @@ T_DjiReturnCode DjiPowerManagement_DeInit(void); */ T_DjiReturnCode DjiPowerManagement_ApplyHighPowerSync(void); +/** + * @brief Apply high power from aircraft in blocking mode. + * @details Before applying, user should register callback function used to set level state of high power application + * pin using DjiPowerManagement_RegWriteHighPowerApplyPinCallback() function. After applying high power, power pin of + * DJI adapter will output high power based predetermined specification. + * @note Max execution time of this function is slightly larger than 600ms. + * @param voltage: The voltage value will be applied to the VCC pin. + * @return Execution result. + */ +T_DjiReturnCode DjiPowerManagement_ApplyHighPowerSyncV2(E_DjiHighPowerVoltage voltage); + /** * @brief Register callback function used to set level state of high power application pin. Must be called before * applying high power. @@ -108,6 +125,15 @@ T_DjiReturnCode DjiPowerManagement_RegWriteHighPowerApplyPinCallback(DjiWriteHig */ T_DjiReturnCode DjiPowerManagement_RegPowerOffNotificationCallback(DjiPowerOffNotificationCallback callback); +/** + * @brief manifold3 outputs high voltage to external devices + * @param stat: true: output high voltage, false: output low voltage + * @return Execution result. + * @note The gpio12 of manifold3 should be pulled down before requesting a high voltage output. + * @note This interface support on DJI manifold3. + */ +T_DjiReturnCode DjiPowerManagement_OutputHighPower(bool stat); + #ifdef __cplusplus } #endif diff --git a/psdk_lib/include/dji_tethered_battery.h b/psdk_lib/include/dji_tethered_battery.h new file mode 100644 index 0000000..105f301 --- /dev/null +++ b/psdk_lib/include/dji_tethered_battery.h @@ -0,0 +1,77 @@ +/** + ******************************************************************** + * @file dji_tethered_battery.h + * @brief This is the header file for "dji_tethered_battery.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2024 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_TETHERED_BATTERY_H +#define DJI_TETHERED_BATTERY_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +/** + * @brief Tether line status. + */ +typedef struct { + dji_f32_t totalLength; /*!< total length of tether line, range: 0-300, unit: meters. */ + dji_f32_t usedLength; /*!< used length of tether line, range: 0-300, unit: meters. + This value must be less than or equal to the total length of tether line. */ +} T_DjiTetherLineStatus; + +/* Exported functions --------------------------------------------------------*/ +/** + * @brief Initialise tethered battery module + * @note User should call this function before using tethered battery features. + * @return Execution result. + */ +T_DjiReturnCode DjiTetheredBattery_Init(void); + +/** + * @brief DeInitialize tethered battery module. + * @return Execution result. + */ +T_DjiReturnCode DjiTetheredBattery_DeInit(void); + +/** + * @brief Push the real-time tether line length to the Pilot2 for display. + * @note It is recommended that the push frequency does not exceed the data update frequency. The maximum push + * frequency should not exceed 10Hz. + * @param tetherLineStatus: the tether line status. + * @return Execution result. + */ +T_DjiReturnCode DjiTetheredBattery_PushTetherLineStatus(T_DjiTetherLineStatus tetherLineStatus); + +#ifdef __cplusplus +} +#endif + +#endif // DJI_TETHERED_BATTERY_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/psdk_lib/include/dji_typedef.h b/psdk_lib/include/dji_typedef.h index ea5511d..742218f 100644 --- a/psdk_lib/include/dji_typedef.h +++ b/psdk_lib/include/dji_typedef.h @@ -44,6 +44,7 @@ extern "C" { /* Exported constants --------------------------------------------------------*/ #define DJI_PI (3.14159265358979323846f) #define DJI_FILE_NAME_SIZE_MAX 256 +#define DJI_FILE_MD5_LENGTH 16 #define DJI_FILE_PATH_SIZE_MAX (DJI_FILE_NAME_SIZE_MAX + 256) #define DJI_IP_ADDR_STR_SIZE_MAX 16 #define DJI_MD5_BUFFER_LEN 16 @@ -58,6 +59,12 @@ extern "C" { (((((uint32_t)(subscriptionModule)) << (DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET)) & (DJI_SUBSCRIPTION_MODULE_INDEX_MASK)) | \ ((((uint32_t)(topicCode)) << (DJI_SUBSCRIPTION_TOPIC_CODE_OFFSET)) & (DJI_SUBSCRIPTION_TOPIC_CODE_MASK))) +#define DJI_DATA_SUBSCRIPTION_TOPIC_GET_MODULE(topic) \ + ((uint32_t)((topic & DJI_SUBSCRIPTION_MODULE_INDEX_MASK) >> DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET)) + +#define DJI_DATA_SUBSCRIPTION_TOPIC_GET_CODE(topic) \ + ((uint32_t)((topic & DJI_SUBSCRIPTION_TOPIC_CODE_MASK) >> DJI_SUBSCRIPTION_TOPIC_CODE_OFFSET)) + /** * @brief Type define double as dji_f64_t. */ @@ -77,6 +84,8 @@ typedef enum { DJI_MOUNT_POSITION_TYPE_PAYLOAD_PORT = 1, DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT = 2, DJI_MOUNT_POSITION_TYPE_EXTENSION_LITE_PORT = 3, + DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT_V2 = 4, + DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD = 5, } E_DjiMountPositionType; typedef enum { @@ -84,8 +93,15 @@ typedef enum { DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 = 1, DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2 = 2, DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3 = 3, - DJI_MOUNT_POSITION_EXTENSION_PORT = 4, - DJI_MOUNT_POSITION_EXTENSION_LITE_PORT = 5, + DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO1 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1, + DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO2 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2, + DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO3 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3, + DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO4 = 4, + DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO5 = 5, + DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO6 = 6, + DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO7 = 7, + DJI_MOUNT_POSITION_EXTENSION_PORT, + DJI_MOUNT_POSITION_EXTENSION_LITE_PORT, } E_DjiMountPosition; typedef enum { @@ -98,7 +114,8 @@ typedef enum { DJI_AIRCRAFT_SERIES_M3D = 6, DJI_AIRCRAFT_SERIES_FC30 = 7, DJI_AIRCRAFT_SERIES_M4 = 8, - DJI_AIRCRAFT_SERIES_M4D = 9, + DJI_AIRCRAFT_SERIES_M4D = 9, + DJI_AIRCRAFT_SERIES_M400 = 10, } E_DjiAircraftSeries; typedef enum { @@ -115,10 +132,11 @@ typedef enum { DJI_AIRCRAFT_TYPE_M350_RTK = 89, /*!< Aircraft type is Matrice 350 RTK. */ DJI_AIRCRAFT_TYPE_M3D = 91, /*!< Aircraft type is Matrice 3D. */ DJI_AIRCRAFT_TYPE_M3TD = 93, /*!< Aircraft type is Matrice 3TD. */ - DJI_AIRCRAFT_TYPE_M4T = 99, /*!< Aircraft type is Mavic 4T. */ - DJI_AIRCRAFT_TYPE_M4E = 990, /*!< Aircraft type is Mavic 4E. */ + DJI_AIRCRAFT_TYPE_M4T = 99, /*!< Aircraft type is Matrice 4T. */ + DJI_AIRCRAFT_TYPE_M4E = 990, /*!< Aircraft type is Matrice 4E. */ DJI_AIRCRAFT_TYPE_M4TD = 100, /*!< Aircraft type is Matrice 4TD. */ DJI_AIRCRAFT_TYPE_M4D = 1000, /*!< Aircraft type is Matrice 4D. */ + DJI_AIRCRAFT_TYPE_M400 = 103, /*!< Aircraft type is Matrice 400. */ } E_DjiAircraftType; /** @@ -259,6 +277,8 @@ typedef enum { DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 = 1, /*!< SDK adapter type is Skyport V2. */ DJI_SDK_ADAPTER_TYPE_XPORT = 2, /*!< SDK adapter type is X-Port. */ DJI_SDK_ADAPTER_TYPE_NONE = 3, /*!< don't have any adapter outside */ + DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 = 4, /*!< SDK adapter type is Skyport V3 */ + DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE = 5, /*!< SDK adapter type is Eport V2 ribbon cable */ } E_DjiSdkAdapterType; typedef enum { @@ -266,6 +286,13 @@ typedef enum { DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1, DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO2, DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO3, + DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO1 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1, + DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO2 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO2, + DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO3 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO3, + DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO4, + DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO5, + DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO6, + DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO7, DJI_CHANNEL_ADDRESS_EXTENSION_PORT, DJI_CHANNEL_ADDRESS_MASTER_RC_APP, DJI_CHANNEL_ADDRESS_SLAVE_RC_APP, @@ -288,6 +315,7 @@ typedef struct { uint8_t captureCount; /*!< Specifies the total capture count of interval settings. * 0: reserved, 1-254: specific number, 255: continuous capture until stopped. */ uint16_t timeIntervalSeconds; /*!< Specifies the interval time between two captures, unit: s*/ + uint16_t timeIntervalMilliseconds; /*!< Specifies the interval time between two captures, unit: ms*/ } T_DjiCameraPhotoTimeIntervalSettings; /** diff --git a/psdk_lib/include/dji_version.h b/psdk_lib/include/dji_version.h index 92dd16e..3acacb5 100644 --- a/psdk_lib/include/dji_version.h +++ b/psdk_lib/include/dji_version.h @@ -34,10 +34,10 @@ extern "C" { /* Exported constants --------------------------------------------------------*/ #define DJI_VERSION_MAJOR 3 /*!< DJI SDK major version num, when have incompatible API changes. Range from 0 to 99. */ -#define DJI_VERSION_MINOR 11 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */ -#define DJI_VERSION_MODIFY 1 /*!< DJI SDK modify version num, when have backwards compatible bug fixes changes. Range from 0 to 99. */ +#define DJI_VERSION_MINOR 12 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */ +#define DJI_VERSION_MODIFY 0 /*!< DJI SDK modify version num, when have backwards compatible bug fixes changes. Range from 0 to 99. */ #define DJI_VERSION_BETA 0 /*!< DJI SDK version beta info, release version will be 0, when beta version release changes. Range from 0 to 255. */ -#define DJI_VERSION_BUILD 2212 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */ +#define DJI_VERSION_BUILD 2254 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */ /* Exported types ------------------------------------------------------------*/ diff --git a/psdk_lib/include/dji_widget_manager.h b/psdk_lib/include/dji_widget_manager.h new file mode 100644 index 0000000..e9a059d --- /dev/null +++ b/psdk_lib/include/dji_widget_manager.h @@ -0,0 +1,308 @@ +/** + ******************************************************************** + * @file dji_widget_states_manager.h + * @version V1.0.0 + * @date 2020/11/26 + * @brief This is the header file for "dji_widget_manager.h", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_WIDGET_STATES_MANNAGER_H +#define DJI_WIDGET_STATES_MANNAGER_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" +#include "dji_widget.h" +#include "dji_camera_manager.h" +// #include "downloader/dji_download_file.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define WIDGET_MANAGER_MAX_FILE_NAME_LEN 32 +#define WIDGET_MANAGER_MAX_FILE_PATH_LEN 128 + +/* Exported types ------------------------------------------------------------*/ +/** + * @brief Speaker system states. + */ +typedef enum { + DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IDEL = 0, + DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IN_TRANSMISSION = 1, + DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_PLAYING = 2, + DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_EXCEPTION = 3, + DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IN_TTS_CONVERSION = 4, +} E_DjiWidgetManagerSpeakerStates; + +/** + * @brief Speaker parameters. + */ +typedef enum { + DJI_WIDGET_MGR_SPEAKER_PARAM_WORK_MODE = 0, /*!< The working mode fo the speaker */ + DJI_WIDGET_MGR_SPEAKER_PARAM_PALY_ACTION = 1, /*!< The playing action of the speaker */ + DJI_WIDGET_MGR_SPEAKER_PARAM_VOLUME = 2, /*!< The volume action of the speaker */ + DJI_WIDGET_MGR_SPEAKER_PARAM_PLAY_MODE = 3, /*!< The playing mode of the speaker */ + DJI_WIDGET_MGR_SPEAKER_PARAM_PLAY_FILE_NAME = 4, /*! 3 || posNum < 1) { + if (posNum > 4 || posNum < 1) { USER_LOG_ERROR("Input mount position is invalid"); continue; } else { diff --git a/samples/sample_c++/module_sample/flight_controller/test_flight_controller_command_flying.cpp b/samples/sample_c++/module_sample/flight_controller/test_flight_controller_command_flying.cpp index e8916be..ef8aac2 100644 --- a/samples/sample_c++/module_sample/flight_controller/test_flight_controller_command_flying.cpp +++ b/samples/sample_c++/module_sample/flight_controller/test_flight_controller_command_flying.cpp @@ -84,6 +84,7 @@ static T_DjiFcSubscriptionControlDevice DjiUser_FlightControlGetValueOfControlDe static T_DjiFcSubscriptionSingleBatteryInfo DjiUser_FlightControlGetValueOfBattery1(void); static T_DjiFcSubscriptionSingleBatteryInfo DjiUser_FlightControlGetValueOfBattery2(void); static T_DjiReturnCode DjiUser_FlightControlUpdateConfig(void); +static T_DjiReturnCode DjiUser_ShowCommandFlyingMenu(void); /* Exported functions definition ---------------------------------------------*/ void DjiUser_RunFlightControllerCommandFlyingSample(void) @@ -107,7 +108,9 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) return; } - osalHandler->TaskSleepMs(1000); + osalHandler->TaskSleepMs(3000); + + DjiUser_ShowCommandFlyingMenu(); while (1) { osalHandler->TaskSleepMs(1); @@ -119,7 +122,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) s_flyingCommand.z = 0; s_flyingCommand.yaw = 0; s_inputFlag = 0; - USER_LOG_INFO(" - Front\r\n"); break; case 'S': case 's': @@ -128,7 +130,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) s_flyingCommand.z = 0; s_flyingCommand.yaw = 0; s_inputFlag = 0; - USER_LOG_INFO(" - Near\r\n"); break; case 'A': case 'a': @@ -137,7 +138,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) s_flyingCommand.z = 0; s_flyingCommand.yaw = 0; s_inputFlag = 0; - USER_LOG_INFO(" - Left\r\n"); break; case 'D': case 'd': @@ -146,7 +146,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) s_flyingCommand.z = 0; s_flyingCommand.yaw = 0; s_inputFlag = 0; - USER_LOG_INFO(" - Right\r\n"); break; case 'Q': case 'q': @@ -155,7 +154,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) s_flyingCommand.z = s_flyingSpeed; s_flyingCommand.yaw = 0; s_inputFlag = 0; - USER_LOG_INFO(" - Up\r\n"); break; case 'E': case 'e': @@ -164,7 +162,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) s_flyingCommand.z = -s_flyingSpeed; s_flyingCommand.yaw = 0; s_inputFlag = 0; - USER_LOG_INFO(" - Down\r\n"); break; case 'Z': case 'z': @@ -173,7 +170,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) s_flyingCommand.z = 0; s_flyingCommand.yaw = -30; s_inputFlag = 0; - USER_LOG_INFO(" - Yaw--\r\n"); break; case 'C': case 'c': @@ -182,96 +178,112 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void) s_flyingCommand.z = 0; s_flyingCommand.yaw = 30; s_inputFlag = 0; - USER_LOG_INFO(" - Yaw++\r\n"); break; case 'R': case 'r': DjiFlightController_ObtainJoystickCtrlAuthority(); DjiFlightController_StartTakeoff(); USER_LOG_INFO(" - Take off\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'F': case 'f': DjiFlightController_StartForceLanding(); USER_LOG_INFO(" - Force landing\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'H': case 'h': DjiFlightController_StartGoHome(); USER_LOG_INFO(" - Start go home\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'Y': case 'y': DjiFlightController_CancelGoHome(); USER_LOG_INFO(" - Cancel go home\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'G': case 'g': DjiFlightController_StartLanding(); USER_LOG_INFO(" - Start landing\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'T': case 't': DjiFlightController_CancelLanding(); USER_LOG_INFO(" - Cancel landing\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'V': case 'v': DjiFlightController_StartConfirmLanding(); USER_LOG_INFO(" - Confirm landing\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'X': case 'x': s_homeLocation.longitude = (dji_f64_t) s_gpsPosition.x / 10000000; s_homeLocation.latitude = (dji_f64_t) s_gpsPosition.y / 10000000; DjiFlightController_SetHomeLocationUsingCurrentAircraftLocation(); - USER_LOG_INFO(" - Set home location\r\n"); + USER_LOG_INFO(" - Set home location (%.4f, %.4f)\r\n", s_homeLocation.longitude, s_homeLocation.latitude); + DjiUser_ShowCommandFlyingMenu(); break; case 'P': case 'p': DjiFlightController_EmergencyStopMotor(DJI_FLIGHT_CONTROLLER_ENABLE_EMERGENCY_STOP_MOTOR, (char *) "Test is ok"); USER_LOG_INFO(" - Emergency stop motor\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'B': case 'b': DjiFlightController_TurnOnMotors(); USER_LOG_INFO(" - Turn on motors\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'N': case 'n': DjiFlightController_TurnOffMotors(); USER_LOG_INFO(" - Turn off motors\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'J': case 'j': DjiUser_FlightControlUpdateConfig(); USER_LOG_INFO(" - Update config\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'I': case 'i': DjiFlightController_ArrestFlying(); USER_LOG_INFO(" - Enable arrest flying\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'O': case 'o': DjiFlightController_CancelArrestFlying(); USER_LOG_INFO(" - Disable arrest flying\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'K': case 'k': DjiFlightController_ExecuteEmergencyBrakeAction(); USER_LOG_INFO(" - Brake\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'L': case 'l': DjiFlightController_CancelEmergencyBrakeAction(); USER_LOG_INFO(" - Disable Brake\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; case 'M': case 'm': DjiFlightController_ObtainJoystickCtrlAuthority(); USER_LOG_INFO(" - Obtain joystick ctrl authority\r\n"); + DjiUser_ShowCommandFlyingMenu(); break; } } @@ -1086,5 +1098,22 @@ static T_DjiReturnCode DjiUser_FlightControlUpdateConfig(void) return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; #endif } +static T_DjiReturnCode DjiUser_ShowCommandFlyingMenu(void) +{ + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + osalHandler->TaskSleepMs(2); + USER_LOG_INFO("Usage: [W] Front [A]-Left, [S]-Rear, [D]-Right"); + USER_LOG_INFO("Usage: [Q]-Up [E]-Down, [Z]-Yaw--, [C]-Yaw++"); + USER_LOG_INFO("Usage: [R]-Take off [F]-Force landing, [H]-Start go home, [Y]-Cancel go home"); + USER_LOG_INFO("Usage: [G]-Start landing [T]-Cancel landing, [V]-Confirm landing, [X]-Set home location"); + USER_LOG_INFO("Usage: [P]-Emergency stop motor, [B]-Turn on motors, [N]-Turn off motors, [J]-Update config"); + USER_LOG_INFO("Usage: [I]-Enable arrest flying, [O]-Disable arrest flying, [K]-Emergency brake, [L]-Diasble Brake"); + USER_LOG_INFO("Usage: [M]-Obtain joystick ctrl authority"); + osalHandler->TaskSleepMs(2); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + /****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/module_sample/flight_controller/test_flight_controller_entry.cpp b/samples/sample_c++/module_sample/flight_controller/test_flight_controller_entry.cpp index 0d281e2..2770b82 100644 --- a/samples/sample_c++/module_sample/flight_controller/test_flight_controller_entry.cpp +++ b/samples/sample_c++/module_sample/flight_controller/test_flight_controller_entry.cpp @@ -63,6 +63,8 @@ start: << "| [8] Waypoint 3.0 sample - run airline mission by kmz file (not support on M300 RTK) |\n" << "| [9] Interest point sample - run interest point mission by settings (only support on M3E/M3T) |\n" << "| [a] EU-C6 FTS trigger sample - receive fts callback to trigger parachute function (only support on M3D/M3DT) |\n" + << "| [b] Slow rotate blade sample, only support on M400 |\n" + << "| [c] Select FTS pwm trigger position, only support on M4/M4T/M4D/M4TD |\n" << std::endl; std::cin >> inputSelectSample; @@ -100,6 +102,12 @@ start: case 'a': DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_FTS_TRIGGER); break; + case 'b': + DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SLOW_ROTATE_BLADE); + break; + case 'c': + DjiTest_FlightControlFtsPwmTriggerSample(); + break; case 'q': break; default: diff --git a/samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp b/samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp index 6d670f3..d4bab8d 100644 --- a/samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp +++ b/samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp @@ -89,15 +89,7 @@ start: << std::endl; std::cout - << "| [1] Select gimbal mount position at NO.1 payload port |" - << - std::endl; - std::cout - << "| [2] Select gimbal mount position at NO.2 payload port |" - << - std::endl; - std::cout - << "| [3] Select gimbal mount position at NO.3 payload port |" + << "| [1 ~ 4] Select gimbal mount position at NO.1~NO.4 |" << std::endl; std::cout @@ -110,7 +102,7 @@ start: return; } - if (mountPosition > '3' || mountPosition < '1') { + if (mountPosition > '4' || mountPosition < '1') { USER_LOG_ERROR("Input mount position is invalid"); goto start; } @@ -247,6 +239,7 @@ start: T_DjiGimbalManagerRotation rotation; T_DjiAircraftInfoBaseInfo baseInfo; E_DjiAircraftSeries aircraftSeries; + E_DjiFcSubscriptionTopic topicOfPayloadGimablAngle; returnCode = DjiGimbalManager_Init(); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { @@ -288,12 +281,24 @@ start: } else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3D) { + topicOfPayloadGimablAngle = DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES; returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ, NULL); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("DjiFcSubscription_SubscribeTopic %d return %d", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode); goto end; } USER_LOG_INFO("Subscribe topic DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES succefully."); + } else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M400) { + topicOfPayloadGimablAngle = gimbalMountPosition == 1 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO1 : + gimbalMountPosition == 2 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO2 : + gimbalMountPosition == 3 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO3 : + gimbalMountPosition == 4 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO4 : DJI_FC_SUBSCRIPTION_TOPIC_TOTAL_NUMBER; + returnCode = DjiFcSubscription_SubscribeTopic(topicOfPayloadGimablAngle, DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ, NULL); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("DjiFcSubscription_SubscribeTopic %d return %d", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode); + goto end; + } + USER_LOG_INFO("Subscribe topic DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO%d succefully.", gimbalMountPosition); } @@ -403,8 +408,8 @@ start: threeGimbalData.anglesData[gimbalMountPosition - 1].yaw); } else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 || - aircraftSeries == DJI_AIRCRAFT_SERIES_M3D) { - returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, + aircraftSeries == DJI_AIRCRAFT_SERIES_M3D || aircraftSeries == DJI_AIRCRAFT_SERIES_M400) { + returnCode = DjiFcSubscription_GetLatestValueOfTopic(topicOfPayloadGimablAngle, (uint8_t *) &gimbalAngles, sizeof(T_DjiFcSubscriptionGimbalAngles), ×tamp); diff --git a/samples/sample_c++/module_sample/hms_manager/hms_manager_entry.cpp b/samples/sample_c++/module_sample/hms_manager/hms_manager_entry.cpp index ace4531..57e921e 100644 --- a/samples/sample_c++/module_sample/hms_manager/hms_manager_entry.cpp +++ b/samples/sample_c++/module_sample/hms_manager/hms_manager_entry.cpp @@ -28,6 +28,7 @@ #include #include "dji_logger.h" #include "hms/test_hms.h" +#include "dji_hms_customization.h" /* Private constants ---------------------------------------------------------*/ @@ -77,6 +78,38 @@ start: } } +void DjiUser_RunHmsEnhanceSample(void) +{ + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + T_DjiHmsAlarmEnhancedSetting setting; + + USER_LOG_INFO("shake motor times 3, interval 500ms..."); + setting.type = DJI_HMS_ALARM_ENHANCED_TYPE_SHAKE_MOTOR; + setting.times = 3; + setting.interval = 500; + DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_START, setting); + osalHandler->TaskSleepMs(4000); + + USER_LOG_INFO("play sound times 3, interval 500ms..."); + setting.type = DJI_HMS_ALARM_ENHANCED_PLAY_SOUND; + DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_START, setting); + osalHandler->TaskSleepMs(4000); + + USER_LOG_INFO("shake motor and play sound times 3, interval 500ms..."); + setting.times = 3; + setting.type = DJI_HMS_ALARM_ENHANCED_PLAY_SOUND_AND_SHAKE_MOTOR; + DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_START, setting); + osalHandler->TaskSleepMs(4000); + + USER_LOG_INFO("shake motor and play sound times 20, interval 500ms, interrupt 3s exit..."); + setting.times = 20; + setting.type = DJI_HMS_ALARM_ENHANCED_PLAY_SOUND_AND_SHAKE_MOTOR; + DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_START, setting); + osalHandler->TaskSleepMs(4000); + DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_EXIT_ALL, setting); + USER_LOG_INFO("AlarmEnhaned exit."); +} + /* Private functions definition-----------------------------------------------*/ /****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/module_sample/hms_manager/hms_manager_entry.h b/samples/sample_c++/module_sample/hms_manager/hms_manager_entry.h index 26e5f2b..6f7ab35 100644 --- a/samples/sample_c++/module_sample/hms_manager/hms_manager_entry.h +++ b/samples/sample_c++/module_sample/hms_manager/hms_manager_entry.h @@ -40,6 +40,7 @@ extern "C" { /* Exported functions --------------------------------------------------------*/ void DjiUser_RunHmsManagerSample(void); +void DjiUser_RunHmsEnhanceSample(void); #ifdef __cplusplus } diff --git a/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/coco.data b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/coco.data new file mode 100644 index 0000000..9b1b0c5 --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/coco.data @@ -0,0 +1,6 @@ +classes= 80 +train = ~/COCO/train2017.txt +valid = ~/COCO/val2017.txt +names = coco.names +backup = model + diff --git a/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/coco.names b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/coco.names new file mode 100644 index 0000000..ca76c80 --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/coco.names @@ -0,0 +1,80 @@ +person +bicycle +car +motorbike +aeroplane +bus +train +truck +boat +traffic light +fire hydrant +stop sign +parking meter +bench +bird +cat +dog +horse +sheep +cow +elephant +bear +zebra +giraffe +backpack +umbrella +handbag +tie +suitcase +frisbee +skis +snowboard +sports ball +kite +baseball bat +baseball glove +skateboard +surfboard +tennis racket +bottle +wine glass +cup +fork +knife +spoon +bowl +banana +apple +sandwich +orange +broccoli +carrot +hot dog +pizza +donut +cake +chair +sofa +pottedplant +bed +diningtable +toilet +tvmonitor +laptop +mouse +remote +keyboard +cell phone +microwave +oven +toaster +sink +refrigerator +book +clock +vase +scissors +teddy bear +hair drier +toothbrush diff --git a/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/mAP_log.txt b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/mAP_log.txt new file mode 100644 index 0000000..3a98f96 --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/mAP_log.txt @@ -0,0 +1,244 @@ + CUDA-version: 10010 (10010), cuDNN: 7.6.5, GPU count: 4 + OpenCV version: 4.9.1 +0,1,2,3 + 0 : compute_capability = 610, cudnn_half = 0, GPU: GeForce GTX 1080 Ti +net.optimized_memory = 0 +mini_batch = 1, batch = 1, time_steps = 1, train = 0 + layer filters size/strd(dil) input output + 0 Create CUDA-stream - 0 + Create cudnn-handle 0 +conv 8 3 x 3/ 2 320 x 320 x 3 -> 160 x 160 x 8 0.011 BF + 1 conv 8 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 8 0.003 BF + 2 conv 8/ 8 3 x 3/ 1 160 x 160 x 8 -> 160 x 160 x 8 0.004 BF + 3 conv 4 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 4 0.002 BF + 4 conv 8 1 x 1/ 1 160 x 160 x 4 -> 160 x 160 x 8 0.002 BF + 5 conv 8/ 8 3 x 3/ 1 160 x 160 x 8 -> 160 x 160 x 8 0.004 BF + 6 conv 4 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 4 0.002 BF + 7 dropout p = 0.150 102400 -> 102400 + 8 Shortcut Layer: 3, wt = 0, wn = 0, outputs: 160 x 160 x 4 0.000 BF + 9 conv 24 1 x 1/ 1 160 x 160 x 4 -> 160 x 160 x 24 0.005 BF + 10 conv 24/ 24 3 x 3/ 2 160 x 160 x 24 -> 80 x 80 x 24 0.003 BF + 11 conv 8 1 x 1/ 1 80 x 80 x 24 -> 80 x 80 x 8 0.002 BF + 12 conv 32 1 x 1/ 1 80 x 80 x 8 -> 80 x 80 x 32 0.003 BF + 13 conv 32/ 32 3 x 3/ 1 80 x 80 x 32 -> 80 x 80 x 32 0.004 BF + 14 conv 8 1 x 1/ 1 80 x 80 x 32 -> 80 x 80 x 8 0.003 BF + 15 dropout p = 0.150 51200 -> 51200 + 16 Shortcut Layer: 11, wt = 0, wn = 0, outputs: 80 x 80 x 8 0.000 BF + 17 conv 32 1 x 1/ 1 80 x 80 x 8 -> 80 x 80 x 32 0.003 BF + 18 conv 32/ 32 3 x 3/ 1 80 x 80 x 32 -> 80 x 80 x 32 0.004 BF + 19 conv 8 1 x 1/ 1 80 x 80 x 32 -> 80 x 80 x 8 0.003 BF + 20 dropout p = 0.150 51200 -> 51200 + 21 Shortcut Layer: 16, wt = 0, wn = 0, outputs: 80 x 80 x 8 0.000 BF + 22 conv 32 1 x 1/ 1 80 x 80 x 8 -> 80 x 80 x 32 0.003 BF + 23 conv 32/ 32 3 x 3/ 2 80 x 80 x 32 -> 40 x 40 x 32 0.001 BF + 24 conv 8 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 8 0.001 BF + 25 conv 48 1 x 1/ 1 40 x 40 x 8 -> 40 x 40 x 48 0.001 BF + 26 conv 48/ 48 3 x 3/ 1 40 x 40 x 48 -> 40 x 40 x 48 0.001 BF + 27 conv 8 1 x 1/ 1 40 x 40 x 48 -> 40 x 40 x 8 0.001 BF + 28 dropout p = 0.150 12800 -> 12800 + 29 Shortcut Layer: 24, wt = 0, wn = 0, outputs: 40 x 40 x 8 0.000 BF + 30 conv 48 1 x 1/ 1 40 x 40 x 8 -> 40 x 40 x 48 0.001 BF + 31 conv 48/ 48 3 x 3/ 1 40 x 40 x 48 -> 40 x 40 x 48 0.001 BF + 32 conv 8 1 x 1/ 1 40 x 40 x 48 -> 40 x 40 x 8 0.001 BF + 33 dropout p = 0.150 12800 -> 12800 + 34 Shortcut Layer: 29, wt = 0, wn = 0, outputs: 40 x 40 x 8 0.000 BF + 35 conv 48 1 x 1/ 1 40 x 40 x 8 -> 40 x 40 x 48 0.001 BF + 36 conv 48/ 48 3 x 3/ 1 40 x 40 x 48 -> 40 x 40 x 48 0.001 BF + 37 conv 16 1 x 1/ 1 40 x 40 x 48 -> 40 x 40 x 16 0.002 BF + 38 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF + 39 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF + 40 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF + 41 dropout p = 0.150 25600 -> 25600 + 42 Shortcut Layer: 37, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF + 43 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF + 44 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF + 45 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF + 46 dropout p = 0.150 25600 -> 25600 + 47 Shortcut Layer: 42, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF + 48 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF + 49 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF + 50 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF + 51 dropout p = 0.150 25600 -> 25600 + 52 Shortcut Layer: 47, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF + 53 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF + 54 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF + 55 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF + 56 dropout p = 0.150 25600 -> 25600 + 57 Shortcut Layer: 52, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF + 58 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF + 59 conv 96/ 96 3 x 3/ 2 40 x 40 x 96 -> 20 x 20 x 96 0.001 BF + 60 conv 24 1 x 1/ 1 20 x 20 x 96 -> 20 x 20 x 24 0.002 BF + 61 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF + 62 conv 136/ 136 3 x 3/ 1 20 x 20 x 136 -> 20 x 20 x 136 0.001 BF + 63 conv 24 1 x 1/ 1 20 x 20 x 136 -> 20 x 20 x 24 0.003 BF + 64 dropout p = 0.150 9600 -> 9600 + 65 Shortcut Layer: 60, wt = 0, wn = 0, outputs: 20 x 20 x 24 0.000 BF + 66 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF + 67 conv 136/ 136 3 x 3/ 1 20 x 20 x 136 -> 20 x 20 x 136 0.001 BF + 68 conv 24 1 x 1/ 1 20 x 20 x 136 -> 20 x 20 x 24 0.003 BF + 69 dropout p = 0.150 9600 -> 9600 + 70 Shortcut Layer: 65, wt = 0, wn = 0, outputs: 20 x 20 x 24 0.000 BF + 71 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF + 72 conv 136/ 136 3 x 3/ 1 20 x 20 x 136 -> 20 x 20 x 136 0.001 BF + 73 conv 24 1 x 1/ 1 20 x 20 x 136 -> 20 x 20 x 24 0.003 BF + 74 dropout p = 0.150 9600 -> 9600 + 75 Shortcut Layer: 70, wt = 0, wn = 0, outputs: 20 x 20 x 24 0.000 BF + 76 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF + 77 conv 136/ 136 3 x 3/ 1 20 x 20 x 136 -> 20 x 20 x 136 0.001 BF + 78 conv 24 1 x 1/ 1 20 x 20 x 136 -> 20 x 20 x 24 0.003 BF + 79 dropout p = 0.150 9600 -> 9600 + 80 Shortcut Layer: 75, wt = 0, wn = 0, outputs: 20 x 20 x 24 0.000 BF + 81 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF + 82 conv 136/ 136 3 x 3/ 2 20 x 20 x 136 -> 10 x 10 x 136 0.000 BF + 83 conv 48 1 x 1/ 1 10 x 10 x 136 -> 10 x 10 x 48 0.001 BF + 84 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF + 85 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF + 86 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF + 87 dropout p = 0.150 4800 -> 4800 + 88 Shortcut Layer: 83, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF + 89 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF + 90 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF + 91 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF + 92 dropout p = 0.150 4800 -> 4800 + 93 Shortcut Layer: 88, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF + 94 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF + 95 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF + 96 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF + 97 dropout p = 0.150 4800 -> 4800 + 98 Shortcut Layer: 93, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF + 99 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF + 100 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF + 101 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF + 102 dropout p = 0.150 4800 -> 4800 + 103 Shortcut Layer: 98, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF + 104 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF + 105 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF + 106 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF + 107 dropout p = 0.150 4800 -> 4800 + 108 Shortcut Layer: 103, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF + 109 max 3x 3/ 1 10 x 10 x 48 -> 10 x 10 x 48 0.000 BF + 110 route 108 -> 10 x 10 x 48 + 111 max 5x 5/ 1 10 x 10 x 48 -> 10 x 10 x 48 0.000 BF + 112 route 108 -> 10 x 10 x 48 + 113 max 9x 9/ 1 10 x 10 x 48 -> 10 x 10 x 48 0.000 BF + 114 route 113 111 109 108 -> 10 x 10 x 192 + 115 conv 96 1 x 1/ 1 10 x 10 x 192 -> 10 x 10 x 96 0.004 BF + 116 conv 96/ 96 5 x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF + 117 conv 96 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.002 BF + 118 conv 96/ 96 5 x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF + 119 conv 96 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.002 BF + 120 conv 255 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 255 0.005 BF + 121 yolo +[yolo] params: iou loss: ciou (4), iou_norm: 0.07, obj_norm: 1.00, cls_norm: 1.00, delta_norm: 1.00, scale_x_y: 1.00 +nms_kind: greedynms (1), beta = 0.600000 + 122 route 115 -> 10 x 10 x 96 + 123 upsample 2x 10 x 10 x 96 -> 20 x 20 x 96 + 124 route 123 80 -> 20 x 20 x 120 + 125 conv 120/ 120 5 x 5/ 1 20 x 20 x 120 -> 20 x 20 x 120 0.002 BF + 126 conv 120 1 x 1/ 1 20 x 20 x 120 -> 20 x 20 x 120 0.012 BF + 127 conv 120/ 120 5 x 5/ 1 20 x 20 x 120 -> 20 x 20 x 120 0.002 BF + 128 conv 120 1 x 1/ 1 20 x 20 x 120 -> 20 x 20 x 120 0.012 BF + 129 conv 255 1 x 1/ 1 20 x 20 x 120 -> 20 x 20 x 255 0.024 BF + 130 yolo +[yolo] params: iou loss: ciou (4), iou_norm: 0.07, obj_norm: 1.00, cls_norm: 1.00, delta_norm: 1.00, scale_x_y: 1.00 +nms_kind: greedynms (1), beta = 0.600000 +Total BFLOPS 0.252 +avg_outputs = 62893 + Allocate additional workspace_size = 1.23 MB +Loading weights from yolo-fastest-1.1.weights... + seen 64, trained: 14231 K-images (222 Kilo-batches_64) +Done! Loaded 131 layers from weights-file + + calculation mAP (mean average precision)... + Detection layer: 121 - type = 28 + Detection layer: 130 - type = 28 +4952 + detections_count = 897029, unique_truth_count = 36335 +class_id = 0, name = person, ap = 45.27% (TP = 4021, FP = 6119) +class_id = 1, name = bicycle, ap = 16.88% (TP = 43, FP = 72) +class_id = 2, name = car, ap = 20.98% (TP = 484, FP = 1112) +class_id = 3, name = motorcycle, ap = 36.12% (TP = 129, FP = 160) +class_id = 4, name = airplane, ap = 57.68% (TP = 81, FP = 57) +class_id = 5, name = bus, ap = 52.42% (TP = 125, FP = 80) +class_id = 6, name = train, ap = 63.20% (TP = 110, FP = 60) +class_id = 7, name = truck, ap = 18.15% (TP = 70, FP = 104) +class_id = 8, name = boat, ap = 12.82% (TP = 70, FP = 188) +class_id = 9, name = traffic light, ap = 9.76% (TP = 76, FP = 162) +class_id = 10, name = fire hydrant, ap = 49.26% (TP = 46, FP = 40) +class_id = 11, name = stop sign, ap = 51.04% (TP = 39, FP = 21) +class_id = 12, name = parking meter, ap = 25.85% (TP = 13, FP = 5) +class_id = 13, name = bench, ap = 12.02% (TP = 43, FP = 55) +class_id = 14, name = bird, ap = 14.24% (TP = 64, FP = 137) +class_id = 15, name = cat, ap = 59.32% (TP = 98, FP = 126) +class_id = 16, name = dog, ap = 41.95% (TP = 80, FP = 95) +class_id = 17, name = horse, ap = 43.46% (TP = 120, FP = 151) +class_id = 18, name = sheep, ap = 33.25% (TP = 147, FP = 285) +class_id = 19, name = cow, ap = 35.18% (TP = 146, FP = 205) +class_id = 20, name = elephant, ap = 59.49% (TP = 151, FP = 152) +class_id = 21, name = bear, ap = 58.50% (TP = 46, FP = 44) +class_id = 22, name = zebra, ap = 66.36% (TP = 172, FP = 123) +class_id = 23, name = giraffe, ap = 65.48% (TP = 150, FP = 63) +class_id = 24, name = backpack, ap = 1.91% (TP = 4, FP = 22) +class_id = 25, name = umbrella, ap = 21.44% (TP = 91, FP = 138) +class_id = 26, name = handbag, ap = 0.61% (TP = 1, FP = 23) +class_id = 27, name = tie, ap = 10.44% (TP = 31, FP = 94) +class_id = 28, name = suitcase, ap = 12.93% (TP = 39, FP = 78) +class_id = 29, name = frisbee, ap = 27.25% (TP = 28, FP = 41) +class_id = 30, name = skis, ap = 11.67% (TP = 37, FP = 132) +class_id = 31, name = snowboard, ap = 10.36% (TP = 6, FP = 10) +class_id = 32, name = sports ball, ap = 17.34% (TP = 48, FP = 62) +class_id = 33, name = kite, ap = 25.58% (TP = 117, FP = 232) +class_id = 34, name = baseball bat, ap = 11.47% (TP = 15, FP = 27) +class_id = 35, name = baseball glove, ap = 10.58% (TP = 20, FP = 61) +class_id = 36, name = skateboard, ap = 18.58% (TP = 44, FP = 85) +class_id = 37, name = surfboard, ap = 14.43% (TP = 50, FP = 172) +class_id = 38, name = tennis racket, ap = 22.89% (TP = 67, FP = 116) +class_id = 39, name = bottle, ap = 7.63% (TP = 69, FP = 146) +class_id = 40, name = wine glass, ap = 7.97% (TP = 18, FP = 67) +class_id = 41, name = cup, ap = 13.11% (TP = 116, FP = 243) +class_id = 42, name = fork, ap = 4.41% (TP = 9, FP = 13) +class_id = 43, name = knife, ap = 1.48% (TP = 2, FP = 14) +class_id = 44, name = spoon, ap = 0.77% (TP = 1, FP = 6) +class_id = 45, name = bowl, ap = 23.25% (TP = 134, FP = 241) +class_id = 46, name = banana, ap = 8.99% (TP = 39, FP = 105) +class_id = 47, name = apple, ap = 5.32% (TP = 13, FP = 37) +class_id = 48, name = sandwich, ap = 23.40% (TP = 35, FP = 67) +class_id = 49, name = orange, ap = 16.69% (TP = 52, FP = 91) +class_id = 50, name = broccoli, ap = 16.88% (TP = 65, FP = 164) +class_id = 51, name = carrot, ap = 7.64% (TP = 27, FP = 80) +class_id = 52, name = hot dog, ap = 14.46% (TP = 11, FP = 31) +class_id = 53, name = pizza, ap = 41.55% (TP = 113, FP = 124) +class_id = 54, name = donut, ap = 19.84% (TP = 65, FP = 152) +class_id = 55, name = cake, ap = 18.44% (TP = 45, FP = 72) +class_id = 56, name = chair, ap = 10.04% (TP = 142, FP = 275) +class_id = 57, name = couch, ap = 29.89% (TP = 53, FP = 101) +class_id = 58, name = potted plant, ap = 10.76% (TP = 29, FP = 84) +class_id = 59, name = bed, ap = 43.32% (TP = 57, FP = 71) +class_id = 60, name = dining table, ap = 22.00% (TP = 183, FP = 283) +class_id = 61, name = toilet, ap = 58.93% (TP = 94, FP = 89) +class_id = 62, name = tv, ap = 47.13% (TP = 123, FP = 107) +class_id = 63, name = laptop, ap = 40.93% (TP = 75, FP = 112) +class_id = 64, name = mouse, ap = 32.37% (TP = 29, FP = 26) +class_id = 65, name = remote, ap = 4.22% (TP = 12, FP = 19) +class_id = 66, name = keyboard, ap = 31.90% (TP = 51, FP = 67) +class_id = 67, name = cell phone, ap = 15.28% (TP = 30, FP = 30) +class_id = 68, name = microwave, ap = 39.49% (TP = 20, FP = 14) +class_id = 69, name = oven, ap = 24.75% (TP = 34, FP = 45) +class_id = 70, name = toaster, ap = 2.32% (TP = 0, FP = 0) +class_id = 71, name = sink, ap = 20.24% (TP = 46, FP = 86) +class_id = 72, name = refrigerator, ap = 30.95% (TP = 42, FP = 44) +class_id = 73, name = book, ap = 1.74% (TP = 45, FP = 334) +class_id = 74, name = clock, ap = 32.38% (TP = 103, FP = 127) +class_id = 75, name = vase, ap = 13.89% (TP = 40, FP = 48) +class_id = 76, name = scissors, ap = 6.25% (TP = 1, FP = 3) +class_id = 77, name = teddy bear, ap = 33.81% (TP = 59, FP = 56) +class_id = 78, name = hair drier, ap = 0.00% (TP = 0, FP = 0) +class_id = 79, name = toothbrush, ap = 1.16% (TP = 0, FP = 2) + + for conf_thresh = 0.25, precision = 0.39, recall = 0.25, F1-score = 0.31 + for conf_thresh = 0.25, TP = 9204, FP = 14585, FN = 27131, average IoU = 27.42 % + + IoU threshold = 50 %, used Area-Under-Curve for each unique Recall + mean average precision (mAP@0.50) = 0.243967, or 24.40 % +Total Detection Time: 133 Seconds + diff --git a/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/xl-mAP_log.txt b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/xl-mAP_log.txt new file mode 100644 index 0000000..7ed7b45 --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/xl-mAP_log.txt @@ -0,0 +1,239 @@ +mini_batch = 1, batch = 1, time_steps = 1, train = 0 + layer filters size/strd(dil) input output + 0 Create CUDA-stream - 0 + Create cudnn-handle 0 +conv 16 3 x 3/ 2 320 x 320 x 3 -> 160 x 160 x 16 0.022 BF + 1 conv 16 1 x 1/ 1 160 x 160 x 16 -> 160 x 160 x 16 0.013 BF + 2 conv 16/ 16 3 x 3/ 1 160 x 160 x 16 -> 160 x 160 x 16 0.007 BF + 3 conv 8 1 x 1/ 1 160 x 160 x 16 -> 160 x 160 x 8 0.007 BF + 4 conv 16 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 16 0.007 BF + 5 conv 16/ 16 3 x 3/ 1 160 x 160 x 16 -> 160 x 160 x 16 0.007 BF + 6 conv 8 1 x 1/ 1 160 x 160 x 16 -> 160 x 160 x 8 0.007 BF + 7 dropout p = 0.200 204800 -> 204800 + 8 Shortcut Layer: 3, wt = 0, wn = 0, outputs: 160 x 160 x 8 0.000 BF + 9 conv 48 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 48 0.020 BF + 10 conv 48/ 48 3 x 3/ 2 160 x 160 x 48 -> 80 x 80 x 48 0.006 BF + 11 conv 16 1 x 1/ 1 80 x 80 x 48 -> 80 x 80 x 16 0.010 BF + 12 conv 64 1 x 1/ 1 80 x 80 x 16 -> 80 x 80 x 64 0.013 BF + 13 conv 64/ 64 3 x 3/ 1 80 x 80 x 64 -> 80 x 80 x 64 0.007 BF + 14 conv 16 1 x 1/ 1 80 x 80 x 64 -> 80 x 80 x 16 0.013 BF + 15 dropout p = 0.200 102400 -> 102400 + 16 Shortcut Layer: 11, wt = 0, wn = 0, outputs: 80 x 80 x 16 0.000 BF + 17 conv 64 1 x 1/ 1 80 x 80 x 16 -> 80 x 80 x 64 0.013 BF + 18 conv 64/ 64 3 x 3/ 1 80 x 80 x 64 -> 80 x 80 x 64 0.007 BF + 19 conv 16 1 x 1/ 1 80 x 80 x 64 -> 80 x 80 x 16 0.013 BF + 20 dropout p = 0.200 102400 -> 102400 + 21 Shortcut Layer: 16, wt = 0, wn = 0, outputs: 80 x 80 x 16 0.000 BF + 22 conv 64 1 x 1/ 1 80 x 80 x 16 -> 80 x 80 x 64 0.013 BF + 23 conv 64/ 64 3 x 3/ 2 80 x 80 x 64 -> 40 x 40 x 64 0.002 BF + 24 conv 16 1 x 1/ 1 40 x 40 x 64 -> 40 x 40 x 16 0.003 BF + 25 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF + 26 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF + 27 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF + 28 dropout p = 0.200 25600 -> 25600 + 29 Shortcut Layer: 24, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF + 30 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF + 31 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF + 32 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF + 33 dropout p = 0.200 25600 -> 25600 + 34 Shortcut Layer: 29, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF + 35 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF + 36 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF + 37 conv 32 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 32 0.010 BF + 38 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF + 39 conv 192/ 192 3 x 3/ 1 40 x 40 x 192 -> 40 x 40 x 192 0.006 BF + 40 conv 32 1 x 1/ 1 40 x 40 x 192 -> 40 x 40 x 32 0.020 BF + 41 dropout p = 0.200 51200 -> 51200 + 42 Shortcut Layer: 37, wt = 0, wn = 0, outputs: 40 x 40 x 32 0.000 BF + 43 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF + 44 conv 192/ 192 3 x 3/ 1 40 x 40 x 192 -> 40 x 40 x 192 0.006 BF + 45 conv 32 1 x 1/ 1 40 x 40 x 192 -> 40 x 40 x 32 0.020 BF + 46 dropout p = 0.200 51200 -> 51200 + 47 Shortcut Layer: 42, wt = 0, wn = 0, outputs: 40 x 40 x 32 0.000 BF + 48 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF + 49 conv 192/ 192 3 x 3/ 1 40 x 40 x 192 -> 40 x 40 x 192 0.006 BF + 50 conv 32 1 x 1/ 1 40 x 40 x 192 -> 40 x 40 x 32 0.020 BF + 51 dropout p = 0.200 51200 -> 51200 + 52 Shortcut Layer: 47, wt = 0, wn = 0, outputs: 40 x 40 x 32 0.000 BF + 53 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF + 54 conv 192/ 192 3 x 3/ 1 40 x 40 x 192 -> 40 x 40 x 192 0.006 BF + 55 conv 32 1 x 1/ 1 40 x 40 x 192 -> 40 x 40 x 32 0.020 BF + 56 dropout p = 0.200 51200 -> 51200 + 57 Shortcut Layer: 52, wt = 0, wn = 0, outputs: 40 x 40 x 32 0.000 BF + 58 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF + 59 conv 192/ 192 3 x 3/ 2 40 x 40 x 192 -> 20 x 20 x 192 0.001 BF + 60 conv 48 1 x 1/ 1 20 x 20 x 192 -> 20 x 20 x 48 0.007 BF + 61 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF + 62 conv 272/ 272 3 x 3/ 1 20 x 20 x 272 -> 20 x 20 x 272 0.002 BF + 63 conv 48 1 x 1/ 1 20 x 20 x 272 -> 20 x 20 x 48 0.010 BF + 64 dropout p = 0.200 19200 -> 19200 + 65 Shortcut Layer: 60, wt = 0, wn = 0, outputs: 20 x 20 x 48 0.000 BF + 66 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF + 67 conv 272/ 272 3 x 3/ 1 20 x 20 x 272 -> 20 x 20 x 272 0.002 BF + 68 conv 48 1 x 1/ 1 20 x 20 x 272 -> 20 x 20 x 48 0.010 BF + 69 dropout p = 0.200 19200 -> 19200 + 70 Shortcut Layer: 65, wt = 0, wn = 0, outputs: 20 x 20 x 48 0.000 BF + 71 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF + 72 conv 272/ 272 3 x 3/ 1 20 x 20 x 272 -> 20 x 20 x 272 0.002 BF + 73 conv 48 1 x 1/ 1 20 x 20 x 272 -> 20 x 20 x 48 0.010 BF + 74 dropout p = 0.200 19200 -> 19200 + 75 Shortcut Layer: 70, wt = 0, wn = 0, outputs: 20 x 20 x 48 0.000 BF + 76 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF + 77 conv 272/ 272 3 x 3/ 1 20 x 20 x 272 -> 20 x 20 x 272 0.002 BF + 78 conv 48 1 x 1/ 1 20 x 20 x 272 -> 20 x 20 x 48 0.010 BF + 79 dropout p = 0.200 19200 -> 19200 + 80 Shortcut Layer: 75, wt = 0, wn = 0, outputs: 20 x 20 x 48 0.000 BF + 81 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF + 82 conv 272/ 272 3 x 3/ 2 20 x 20 x 272 -> 10 x 10 x 272 0.000 BF + 83 conv 96 1 x 1/ 1 10 x 10 x 272 -> 10 x 10 x 96 0.005 BF + 84 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF + 85 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF + 86 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF + 87 dropout p = 0.200 9600 -> 9600 + 88 Shortcut Layer: 83, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF + 89 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF + 90 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF + 91 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF + 92 dropout p = 0.200 9600 -> 9600 + 93 Shortcut Layer: 88, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF + 94 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF + 95 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF + 96 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF + 97 dropout p = 0.200 9600 -> 9600 + 98 Shortcut Layer: 93, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF + 99 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF + 100 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF + 101 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF + 102 dropout p = 0.200 9600 -> 9600 + 103 Shortcut Layer: 98, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF + 104 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF + 105 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF + 106 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF + 107 dropout p = 0.200 9600 -> 9600 + 108 Shortcut Layer: 103, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF + 109 max 3x 3/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF + 110 route 108 -> 10 x 10 x 96 + 111 max 5x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF + 112 route 108 -> 10 x 10 x 96 + 113 max 9x 9/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.001 BF + 114 route 113 111 109 108 -> 10 x 10 x 384 + 115 conv 96 1 x 1/ 1 10 x 10 x 384 -> 10 x 10 x 96 0.007 BF + 116 conv 96/ 96 5 x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF + 117 conv 96 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.002 BF + 118 conv 96/ 96 5 x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF + 119 conv 96 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.002 BF + 120 conv 255 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 255 0.005 BF + 121 yolo +[yolo] params: iou loss: ciou (4), iou_norm: 0.07, obj_norm: 1.00, cls_norm: 1.00, delta_norm: 1.00, scale_x_y: 1.00 +nms_kind: greedynms (1), beta = 0.600000 + 122 route 115 -> 10 x 10 x 96 + 123 upsample 2x 10 x 10 x 96 -> 20 x 20 x 96 + 124 route 123 80 -> 20 x 20 x 144 + 125 conv 144/ 144 5 x 5/ 1 20 x 20 x 144 -> 20 x 20 x 144 0.003 BF + 126 conv 144 1 x 1/ 1 20 x 20 x 144 -> 20 x 20 x 144 0.017 BF + 127 conv 144/ 144 5 x 5/ 1 20 x 20 x 144 -> 20 x 20 x 144 0.003 BF + 128 conv 144 1 x 1/ 1 20 x 20 x 144 -> 20 x 20 x 144 0.017 BF + 129 conv 255 1 x 1/ 1 20 x 20 x 144 -> 20 x 20 x 255 0.029 BF + 130 yolo +[yolo] params: iou loss: ciou (4), iou_norm: 0.07, obj_norm: 1.00, cls_norm: 1.00, delta_norm: 1.00, scale_x_y: 1.00 +nms_kind: greedynms (1), beta = 0.600000 +Total BFLOPS 0.725 +avg_outputs = 120982 + Allocate additional workspace_size = 0.31 MB +Loading weights from model/yolo-fastest-1_final.weights... + seen 64, trained: 16000 K-images (250 Kilo-batches_64) +Done! Loaded 131 layers from weights-file + + calculation mAP (mean average precision)... + Detection layer: 121 - type = 28 + Detection layer: 130 - type = 28 +4952 + detections_count = 664785, unique_truth_count = 36335 +class_id = 0, name = person, ap = 53.92% (TP = 4976, FP = 5767) +class_id = 1, name = bicycle, ap = 25.29% (TP = 81, FP = 105) +class_id = 2, name = car, ap = 30.59% (TP = 666, FP = 1092) +class_id = 3, name = motorcycle, ap = 47.05% (TP = 157, FP = 174) +class_id = 4, name = airplane, ap = 63.87% (TP = 87, FP = 63) +class_id = 5, name = bus, ap = 60.84% (TP = 160, FP = 90) +class_id = 6, name = train, ap = 72.50% (TP = 124, FP = 59) +class_id = 7, name = truck, ap = 30.67% (TP = 126, FP = 177) +class_id = 8, name = boat, ap = 20.35% (TP = 111, FP = 233) +class_id = 9, name = traffic light, ap = 17.36% (TP = 147, FP = 311) +class_id = 10, name = fire hydrant, ap = 63.01% (TP = 54, FP = 22) +class_id = 11, name = stop sign, ap = 54.51% (TP = 38, FP = 25) +class_id = 12, name = parking meter, ap = 39.62% (TP = 24, FP = 12) +class_id = 13, name = bench, ap = 16.95% (TP = 67, FP = 120) +class_id = 14, name = bird, ap = 22.58% (TP = 104, FP = 185) +class_id = 15, name = cat, ap = 73.95% (TP = 129, FP = 112) +class_id = 16, name = dog, ap = 58.90% (TP = 118, FP = 128) +class_id = 17, name = horse, ap = 57.27% (TP = 153, FP = 120) +class_id = 18, name = sheep, ap = 45.20% (TP = 185, FP = 305) +class_id = 19, name = cow, ap = 48.22% (TP = 191, FP = 212) +class_id = 20, name = elephant, ap = 68.17% (TP = 176, FP = 147) +class_id = 21, name = bear, ap = 77.67% (TP = 51, FP = 28) +class_id = 22, name = zebra, ap = 74.43% (TP = 183, FP = 91) +class_id = 23, name = giraffe, ap = 75.02% (TP = 166, FP = 65) +class_id = 24, name = backpack, ap = 5.03% (TP = 21, FP = 86) +class_id = 25, name = umbrella, ap = 36.33% (TP = 151, FP = 161) +class_id = 26, name = handbag, ap = 1.68% (TP = 11, FP = 72) +class_id = 27, name = tie, ap = 20.32% (TP = 60, FP = 120) +class_id = 28, name = suitcase, ap = 21.99% (TP = 73, FP = 137) +class_id = 29, name = frisbee, ap = 46.40% (TP = 57, FP = 60) +class_id = 30, name = skis, ap = 19.74% (TP = 60, FP = 153) +class_id = 31, name = snowboard, ap = 18.86% (TP = 20, FP = 51) +class_id = 32, name = sports ball, ap = 28.16% (TP = 74, FP = 72) +class_id = 33, name = kite, ap = 35.39% (TP = 139, FP = 247) +class_id = 34, name = baseball bat, ap = 20.85% (TP = 33, FP = 63) +class_id = 35, name = baseball glove, ap = 21.76% (TP = 40, FP = 97) +class_id = 36, name = skateboard, ap = 36.03% (TP = 79, FP = 112) +class_id = 37, name = surfboard, ap = 27.98% (TP = 93, FP = 194) +class_id = 38, name = tennis racket, ap = 36.49% (TP = 99, FP = 175) +class_id = 39, name = bottle, ap = 16.24% (TP = 170, FP = 327) +class_id = 40, name = wine glass, ap = 15.37% (TP = 48, FP = 125) +class_id = 41, name = cup, ap = 23.22% (TP = 211, FP = 348) +class_id = 42, name = fork, ap = 14.48% (TP = 29, FP = 60) +class_id = 43, name = knife, ap = 4.63% (TP = 15, FP = 62) +class_id = 44, name = spoon, ap = 3.32% (TP = 9, FP = 27) +class_id = 45, name = bowl, ap = 33.69% (TP = 209, FP = 261) +class_id = 46, name = banana, ap = 23.40% (TP = 86, FP = 136) +class_id = 47, name = apple, ap = 8.21% (TP = 24, FP = 89) +class_id = 48, name = sandwich, ap = 33.67% (TP = 56, FP = 80) +class_id = 49, name = orange, ap = 22.59% (TP = 77, FP = 137) +class_id = 50, name = broccoli, ap = 23.62% (TP = 88, FP = 178) +class_id = 51, name = carrot, ap = 10.15% (TP = 55, FP = 159) +class_id = 52, name = hot dog, ap = 28.57% (TP = 33, FP = 38) +class_id = 53, name = pizza, ap = 51.21% (TP = 129, FP = 148) +class_id = 54, name = donut, ap = 30.97% (TP = 116, FP = 184) +class_id = 55, name = cake, ap = 32.03% (TP = 99, FP = 155) +class_id = 56, name = chair, ap = 18.50% (TP = 304, FP = 568) +class_id = 57, name = couch, ap = 48.84% (TP = 125, FP = 156) +class_id = 58, name = potted plant, ap = 20.71% (TP = 66, FP = 118) +class_id = 59, name = bed, ap = 52.73% (TP = 88, FP = 97) +class_id = 60, name = dining table, ap = 27.14% (TP = 224, FP = 334) +class_id = 61, name = toilet, ap = 66.39% (TP = 112, FP = 77) +class_id = 62, name = tv, ap = 56.32% (TP = 151, FP = 98) +class_id = 63, name = laptop, ap = 54.05% (TP = 100, FP = 157) +class_id = 64, name = mouse, ap = 44.78% (TP = 46, FP = 44) +class_id = 65, name = remote, ap = 7.84% (TP = 28, FP = 102) +class_id = 66, name = keyboard, ap = 44.37% (TP = 71, FP = 83) +class_id = 67, name = cell phone, ap = 24.25% (TP = 62, FP = 74) +class_id = 68, name = microwave, ap = 46.90% (TP = 21, FP = 19) +class_id = 69, name = oven, ap = 37.19% (TP = 54, FP = 52) +class_id = 70, name = toaster, ap = 10.84% (TP = 0, FP = 0) +class_id = 71, name = sink, ap = 34.06% (TP = 81, FP = 98) +class_id = 72, name = refrigerator, ap = 46.76% (TP = 57, FP = 45) +class_id = 73, name = book, ap = 4.20% (TP = 112, FP = 548) +class_id = 74, name = clock, ap = 53.92% (TP = 144, FP = 92) +class_id = 75, name = vase, ap = 25.27% (TP = 67, FP = 70) +class_id = 76, name = scissors, ap = 21.61% (TP = 7, FP = 10) +class_id = 77, name = teddy bear, ap = 47.50% (TP = 90, FP = 56) +class_id = 78, name = hair drier, ap = 0.70% (TP = 0, FP = 0) +class_id = 79, name = toothbrush, ap = 1.50% (TP = 2, FP = 9) + + for conf_thresh = 0.25, precision = 0.43, recall = 0.35, F1-score = 0.39 + for conf_thresh = 0.25, TP = 12750, FP = 16864, FN = 23585, average IoU = 31.39 % + + IoU threshold = 50 %, used Area-Under-Curve for each unique Recall + mean average precision (mAP@0.50) = 0.343340, or 34.33 % +Total Detection Time: 93 Seconds + diff --git a/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.cfg b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.cfg new file mode 100644 index 0000000..e90f3ce --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.cfg @@ -0,0 +1,947 @@ +[net] +batch=32 +subdivisions=1 +width=320 +height=320 +channels=3 +momentum=0.949 +decay=0.0005 +angle=0 +saturation=1.5 +exposure=1.5 +hue=.1 + + +learning_rate=0.001 +burn_in=4000 +max_batches=500000 +policy=steps +steps=400000,450000 +scales=.1,.1 + +[convolutional] +filters=16 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=16 +filters=16 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=16 +filters=16 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=48 +filters=48 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=64 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=64 +filters=64 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=64 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=64 +filters=64 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=64 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=64 +filters=64 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=96 +filters=96 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=96 +filters=96 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=96 +filters=96 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=32 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=192 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=192 +filters=192 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=32 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=192 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=192 +filters=192 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=32 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=192 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=192 +filters=192 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=32 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=192 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=192 +filters=192 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=32 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=192 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=192 +filters=192 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=272 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=272 +filters=272 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=272 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=272 +filters=272 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=272 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=272 +filters=272 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=272 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=272 +filters=272 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=272 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=272 +filters=272 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=448 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=448 +filters=448 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=448 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=448 +filters=448 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=448 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=448 +filters=448 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=448 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=448 +filters=448 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=448 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=448 +filters=448 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + +[dropout] +probability=.2 + +[shortcut] +from=-5 +activation=linear + +############### +[maxpool] +stride=1 +size=3 + +[route] +layers=-2 + +[maxpool] +stride=1 +size=5 + +[route] +layers=-4 + +[maxpool] +stride=1 +size=9 + +[route] +layers=-1,-3,-5,-6 + +### End SPP ### +############### +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=5 +groups=96 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=1 +batch_normalize=1 +activation=linear + +[convolutional] +filters=96 +size=5 +groups=96 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=1 +batch_normalize=1 +activation=linear + + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=linear + + +[yolo] +mask = 3,4,5 +anchors = 12, 18, 37, 49, 52,132, 115, 73, 119,199, 242,238 +classes=80 +num=6 +jitter=.15 +ignore_thresh = .5 +truth_thresh = 1 +random=0 +scale_x_y = 1.0 +iou_thresh=0.213 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +nms_kind=greedynms +beta_nms=0.6 + +[route] +layers = -7 + +[upsample] +stride = 2 + +[route] +layers=-1,80 + +[convolutional] +filters=144 +size=5 +groups=144 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=144 +size=1 +stride=1 +pad=1 +batch_normalize=1 +activation=linear + +[convolutional] +filters=144 +size=5 +groups=144 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=144 +size=1 +stride=1 +pad=1 +batch_normalize=1 +activation=linear + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=linear + + +[yolo] +mask = 0,1,2 +anchors = 12, 18, 37, 49, 52,132, 115, 73, 119,199, 242,238 +classes=80 +num=6 +jitter=.15 +ignore_thresh = .5 +truth_thresh = 1 +random=0 +scale_x_y = 1.00 +iou_thresh=0.213 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +nms_kind=greedynms +beta_nms=0.6 + diff --git a/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.weights b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.weights new file mode 100644 index 0000000..16f7892 Binary files /dev/null and b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.weights differ diff --git a/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1.cfg b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1.cfg new file mode 100644 index 0000000..d8ce55e --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1.cfg @@ -0,0 +1,946 @@ +[net] +batch=32 +subdivisions=1 +width=320 +height=320 +channels=3 +momentum=0.949 +decay=0.0005 +angle=0 +saturation=1.5 +exposure=1.5 +hue=.1 + + +learning_rate=0.001 +burn_in=4000 +max_batches=500000 +policy=steps +steps=400000,450000 +scales=.1,.1 + +[convolutional] +filters=8 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=8 +filters=8 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=4 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=8 +filters=8 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=4 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=24 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=24 +filters=24 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=32 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=32 +filters=32 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=32 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=32 +filters=32 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=32 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=32 +filters=32 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=48 +filters=48 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=48 +filters=48 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=8 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=48 +filters=48 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=96 +filters=96 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=96 +filters=96 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=96 +filters=96 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=96 +filters=96 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=16 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=96 +filters=96 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=24 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=136 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=136 +filters=136 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=24 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=136 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=136 +filters=136 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=24 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=136 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=136 +filters=136 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=24 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=136 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=136 +filters=136 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=24 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=136 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=136 +filters=136 +size=3 +pad=1 +stride=2 +batch_normalize=1 +activation=leaky + + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[convolutional] +filters=224 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=224 +filters=224 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=224 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=224 +filters=224 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=224 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=224 +filters=224 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=224 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=224 +filters=224 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear + +[convolutional] +filters=224 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +groups=224 +filters=224 +size=3 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=48 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=linear + +[dropout] +probability=.15 + +[shortcut] +from=-5 +activation=linear +############### +[maxpool] +stride=1 +size=3 + +[route] +layers=-2 + +[maxpool] +stride=1 +size=5 + +[route] +layers=-4 + +[maxpool] +stride=1 +size=9 + +[route] +layers=-1,-3,-5,-6 + +### End SPP ### +############### +[convolutional] +filters=96 +size=1 +stride=1 +pad=0 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=5 +groups=96 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=1 +batch_normalize=1 +activation=linear + +[convolutional] +filters=96 +size=5 +groups=96 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=96 +size=1 +stride=1 +pad=1 +batch_normalize=1 +activation=linear + + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=linear + + +[yolo] +mask = 3,4,5 +anchors = 12, 18, 37, 49, 52,132, 115, 73, 119,199, 242,238 +classes=80 +num=6 +jitter=.15 +ignore_thresh = .5 +truth_thresh = 1 +random=0 +scale_x_y = 1.0 +iou_thresh=0.213 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +nms_kind=greedynms +beta_nms=0.6 + +[route] +layers = -7 + +[upsample] +stride = 2 + +[route] +layers=-1,80 + +[convolutional] +filters=120 +size=5 +groups=120 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=120 +size=1 +stride=1 +pad=1 +batch_normalize=1 +activation=linear + +[convolutional] +filters=120 +size=5 +groups=120 +stride=1 +pad=1 +batch_normalize=1 +activation=leaky + +[convolutional] +filters=120 +size=1 +stride=1 +pad=1 +batch_normalize=1 +activation=linear + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=linear + + +[yolo] +mask = 0,1,2 +anchors = 12, 18, 37, 49, 52,132, 115, 73, 119,199, 242,238 +classes=80 +num=6 +jitter=.15 +ignore_thresh = .5 +truth_thresh = 1 +random=0 +scale_x_y = 1.00 +iou_thresh=0.213 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +nms_kind=greedynms +beta_nms=0.6 + diff --git a/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1.weights b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1.weights new file mode 100644 index 0000000..9d755ab Binary files /dev/null and b/samples/sample_c++/module_sample/liveview/data/yolo-fastest-1.1_coco/yolo-fastest-1.1.weights differ diff --git a/samples/sample_c++/module_sample/liveview/dji_liveview_object_detection.cpp b/samples/sample_c++/module_sample/liveview/dji_liveview_object_detection.cpp new file mode 100644 index 0000000..63f3162 --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/dji_liveview_object_detection.cpp @@ -0,0 +1,648 @@ +/** + ******************************************************************** + * + * @copyright (c) 2023 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include "test_liveview_entry.hpp" +#include "dji_liveview_object_detection.hpp" +#include "dji_payload_camera.h" +#include "dji_high_speed_data_channel.h" +#include +#include +#include "dji_typedef.h" +#include +#include +#include +#include +#include +#include "dji_open_ar.h" +#include + +#ifdef OPEN_CV_INSTALLED +#include +#include +#include +#include "image_processor_yolovfastest.hpp" +#endif + +/* Private constants ---------------------------------------------------------*/ +#define YOLO_LABLES_NUM 76 +#define INVALID_CLASS_NUM 4 + +static const char* s_classLables[] = { + "person", "bicycle", "car", "motorbike", + "aeroplane", "bus", "train", "truck", + "boat", "traffic light", "fire hydrant", "stop sign", + "parking meter", "bench", "bird", "cat", + "dog", "horse", "sheep", "cow", + "elephant", "bear", "zebra", "giraffe", + "backpack", "umbrella", "handbag", "tie", + "suitcase", "frisbee", "skis", "snowboard", + "sports ball", "kite", "baseball bat", "baseball glove", + "skateboard", "surfboard", "tennis racket", "bottle", + "wine glass", "cup", "fork", "knife", + "spoon", "bowl", "banana", "apple", + "sandwich", "orange", "broccoli", "carrot", + "hot dog", "pizza", "donut", "cake", + "chair", "sofa", "pottedplant", "bed", + "diningtable", "toilet", "tvmonitor", "laptop", + "mouse", "remote", "keyboard", "cell phone", + "microwave", "oven", "toaster", "sink", + "refrigerator", "book", "clock", "vase", + "scissors", "teddy bear", "hair drier", "toothbrush", +}; + +static const char* s_invalidLables[] = { + "XXX", "WW", "YYYYYYYYYYY", "ZZZZZZZZ" +}; + +static std::ofstream outFileH264; +static std::ofstream outFileYUV; +static std::string getCurrentTimestamp(); +static void outH264Tofile(const uint8_t *buf, int32_t len); +static void outYUVTofile(const uint8_t *buf, int32_t len); +static void DjiLiveview_RcvImageCallback(E_DjiLiveViewCameraPosition position, const uint8_t *buf, uint32_t len ,T_DjiLiveviewImageInfo imageInfo); +static void DjiLiveview_EncoderUseCallback(const uint8_t *buf, uint32_t len); + +#ifdef OPEN_CV_INSTALLED +static ImageProcessorYolovFastest processor("YOLOvFastest"); +static std::queue s_imageQueue; +static std::queue s_metaQueue; +static void *DjiLiveview_ObjectDetectionThread(void *arg); +T_DjiTaskHandle s_procThreadHandle; +T_DjiMutexHandle s_metaQueueMutexHandle; +T_DjiMutexHandle s_imageQueueMutexHandle; +#endif + +void DjiUser_InitOpenAr(T_DjiOpenArPoint* point) +{ + point->uuid = 1; + point->style_id = 10; + point->resource_id = 0; + point->is_always_in_edge = 1; + + point->coordinate = {113.939467, 22.526366, 1.0}; + + point->text_attr.is_show = 1; + memcpy(point->text_attr.text, "测试文本", sizeof("测试文本")); + + point->icon_attr = {0, 1, 33445566}; + point->touch_attr = {1, {0.0, 0.0, 1.0}}; +} + +void ArRrefleshAll() +{ + USER_LOG_INFO("do ar reflesh all"); + uint8_t buf[1024]; + memset(buf, 0, sizeof(buf)); + + T_DjiOpenArCircle* circle = (T_DjiOpenArCircle*)buf; + circle->ids = {50, 10}; + circle->center = {113.939467, 22.526366, 11.}; + circle->radius = 2; + circle->normal_vector = {0, 0, 3}; + circle->face = {0, 1, 1, 1}; + circle->stroke = {1, 1, 1, 1, 1, 1}; + DjiLiveview_ArSetCircle(circle); +} + +void DjiUser_RunOpenArSample() +{ + DjiLiveview_ArRegRefleshAllCallback(ArRrefleshAll); + bool exit = false; + while (!exit) + { + std::cout + << "\n" + << "| Available commands: \n" + << "| [0] Set Point - draw tow points\n" + << "| [1] Update point - append tow points\n" + << "| [2] Delete point - delete tow point\n" + << "| [3] Clear point- clear all points\n" + << "| [4] Set line - draw a line with five points.\n" + << "| [5] Update line - add a line with tow points.\n" + << "| [6] Delete line - delete the line drawn in the [5] step.\n" + << "| [7] Clear line - clear lines\n" + << "| [8] Set polygon - draw a cuboid\n" + << "| [9] Update polygon - draw a triangular prism\n" + << "| [a] Delete polygon - delete the triangular prism\n" + << "| [b] Clear polygon - clear polygon\n" + << "| [c] Set circle - draw a circle\n" + << "| [d] Update circle - add a circle\n" + << "| [e] Delete circle - delete a circle\n" + << "| [f] Clear circle - clear circle\n" + << "| [q] Exit\n" + << std::endl; + + char inputChar; + std::cin >> inputChar; + uint8_t buf[1024]; + memset(buf, 0, sizeof(buf)); + + T_DjiOpenArPoint point; + DjiUser_InitOpenAr(&point); + + T_DjiOpenArPointArray* point_array = (T_DjiOpenArPointArray*)buf; + T_DjiOpenArLine* line = (T_DjiOpenArLine*)buf; + T_DjiOpenArPolygon* polygon = (T_DjiOpenArPolygon*)buf; + T_DjiOpenArCircle* circle = (T_DjiOpenArCircle*)buf; + T_DjiOpenArPivotAxis* pivot = (T_DjiOpenArPivotAxis*)buf; + + T_DjiOpenArDeletePointEntry* delete_point_entry = (T_DjiOpenArDeletePointEntry*)buf; + T_DjiOpenArDeleteLineEntry* delete_line_entry = (T_DjiOpenArDeleteLineEntry*)buf; + T_DjiOpenArDeletePolygonEntry* delete_polygon_entry = (T_DjiOpenArDeletePolygonEntry*)buf; + T_DjiOpenArDeleteCircleEntry* delete_circle_entry = (T_DjiOpenArDeleteCircleEntry*)buf; + T_DjiOpenArDeletePovixAxisEntry* delete_povix_entry = (T_DjiOpenArDeletePovixAxisEntry*)buf; + + switch(inputChar) { + case '0': + point_array->len = 2; + + point.uuid = 1; + memcpy(point.text_attr.text, "测试文本", sizeof("测试文本")); + memcpy(&point_array->points[0], &point, sizeof(point)); + + point.uuid = 2; + point.coordinate.altitude = 2.0f; + memcpy(point.text_attr.text, "test text", sizeof("test text")); + memcpy(&point_array->points[1], &point, sizeof(point)); + + DjiLiveview_ArSetPoint(point_array); + break; + case '1': + point_array->len = 2; + point.uuid = 3; + point.coordinate.altitude = 3.0f; + memcpy(point.text_attr.text, "point update", sizeof("point update")); + memcpy(&point_array->points[0], &point, sizeof(point)); + + point.uuid = 4; + point.coordinate.altitude = 4.0f; + memcpy(&point_array->points[1], &point, sizeof(point)); + DjiLiveview_ArUpdatePoint(point_array); + + break; + case '2': + delete_point_entry->resource_id = 0; + delete_point_entry->uuid_len = 2; + delete_point_entry->uuid_array[0] = 1; + delete_point_entry->uuid_array[1] = 2; + DjiLiveview_ArDeletePoint(delete_point_entry); + break; + + case '3': + DjiLiveview_ArClearPoint(0); + break; + + case '4': + line->ids.uuid = 10; + line->ids.style_id = 10; + line->point_array.len = 5; + + point.uuid = 11; + point.coordinate.altitude = 4.0f; + memcpy(&line->point_array.points[0], &point, sizeof(point)); + + point.uuid = 12; + point.coordinate.altitude = 5.0f; + memcpy(&line->point_array.points[1], &point, sizeof(point)); + + point.uuid = 13; + point.coordinate.altitude = 6.0f; + memcpy(&line->point_array.points[2], &point, sizeof(point)); + + point.uuid = 14; + point.coordinate.altitude = 7.0f; + memcpy(&line->point_array.points[3], &point, sizeof(point)); + + point.uuid = 15; + point.coordinate.altitude = 8.0f; + memcpy(&line->point_array.points[4], &point, sizeof(point)); + + DjiLiveview_ArSetLine(line); + break; + + case '5': + line->ids.uuid = 11; + line->ids.style_id = 10; + line->point_array.len = 2; + + point.uuid = 16; + point.coordinate.altitude = 9.0f; + memcpy(&line->point_array.points[0], &point, sizeof(point)); + + point.uuid = 17; + point.coordinate.altitude = 10.0f; + memcpy(&line->point_array.points[1], &point, sizeof(point)); + + DjiLiveview_ArUpdateLine(line); + break; + + case '6': + delete_line_entry[0].uuid = 10; + DjiLiveview_ArDeleteLine(delete_line_entry, 1); + break; + + case '7': + DjiLiveview_ArClearLine(); + break; + + case '8': + polygon->ids = {40, 11}; + polygon->face = {0, 1, 1, 1}; + polygon->stroke = {1, 1, 1, 1, 1, 1}; + polygon->normal_vector = {0, 0, 6}; + polygon->point_array.len = 4; + point.uuid = 41; + point.coordinate.altitude = 1; + point.coordinate.longitude = 113.939438538; + point.coordinate.latitude = 22.5263937487; + memcpy(&polygon->point_array.points[0], &point, sizeof(point)); + + point.uuid = 42; + point.coordinate.longitude = 113.939496338; + point.coordinate.latitude = 22.5263937487; + memcpy(&polygon->point_array.points[1], &point, sizeof(point)); + + point.uuid = 43; + point.coordinate.longitude = 113.939496338; + point.coordinate.latitude = 22.5263397487; + memcpy(&polygon->point_array.points[2], &point, sizeof(point)); + + point.uuid = 44; + point.coordinate.longitude = 113.939438538; + point.coordinate.latitude = 22.5263397487; + memcpy(&polygon->point_array.points[3], &point, sizeof(point)); + + DjiLiveview_ArSetPolygon(polygon); + break; + + case '9': + polygon->ids = {45, 11}; + polygon->face = {0, 1, 1, 1}; + polygon->stroke = {1, 1, 1, 1, 1, 1}; + polygon->normal_vector = {0, 0, 4}; + polygon->point_array.len = 3; + point.uuid = 46; + point.coordinate.altitude = 12; + point.coordinate.longitude = 113.939438538; + point.coordinate.latitude = 22.5263937487; + memcpy(&polygon->point_array.points[0], &point, sizeof(point)); + + point.uuid = 47; + point.coordinate.longitude = 113.939496338; + point.coordinate.latitude = 22.5263937487; + memcpy(&polygon->point_array.points[1], &point, sizeof(point)); + + point.uuid = 48; + point.coordinate.longitude = 113.939496338; + point.coordinate.latitude = 22.5263397487; + memcpy(&polygon->point_array.points[2], &point, sizeof(point)); + DjiLiveview_ArUpdatePolygon(polygon); + + break; + case 'a': + delete_polygon_entry->uuid = 40; + DjiLiveview_ArDeletePolygon(delete_polygon_entry, 1); + break; + + case 'b': + DjiLiveview_ArClearPolygon(); + break; + + case 'c': + circle->ids = {50, 10}; + circle->center = {113.939467, 22.526366, 11.}; + circle->radius = 3; + circle->normal_vector = {0, 0, 3}; + circle->face = {0, 1, 1, 1}; + circle->stroke = {1, 1, 1, 1, 1, 1}; + DjiLiveview_ArSetCircle(circle); + break; + + case 'd': + circle->ids = {51, 11}; + circle->center = {113.939467, 22.526366, 8.}; + circle->radius = 4; + circle->normal_vector = {0, 0, 5}; + circle->face = {1, 1, 1, 1}; + circle->stroke = {1, 1, 1, 1, 1, 1}; + DjiLiveview_ArUpdateCircle(circle); + break; + + case 'e': + delete_circle_entry->uuid = 50; + DjiLiveview_ArDeleteCircle(delete_circle_entry, 1); + break; + + case 'f': + DjiLiveview_ArClearCircle(); + break; + case 'q': + exit = true; + break; + default: + break; + } + } +} + +void DjiUser_RunCameraAiDetectionSample() +{ + int pos = 1; + int mediaSource = 0; //support 0(app liveview)/1(1080p)/7(4k) for H30 camera + char isQuit; + E_DjiLiveViewCameraPosition CameraPostion; + E_DjiLiveViewCameraSource MediaResource; + + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + if (pos < 1 || pos > 3 || (mediaSource != 0 &&mediaSource != 1 && mediaSource != 7)) + { + USER_LOG_ERROR("invalid param"); + return; + } + + std::string timestamp = getCurrentTimestamp(); + + std::string h264FileName = "output_" + timestamp + ".h264"; + outFileH264.open(h264FileName, std::ios::out | std::ios::binary | std::ios::app); + if (!outFileH264) { + std::cerr << "cant open " << h264FileName << std::endl; + } + +#ifdef OPEN_CV_INSTALLED + osalHandler->MutexCreate(&s_metaQueueMutexHandle); + osalHandler->MutexCreate(&s_imageQueueMutexHandle); + osalHandler->TaskCreate("objectDetectionTask",DjiLiveview_ObjectDetectionThread,1024*1024,NULL, &s_procThreadHandle); + if (processor.Init() != 0) { + std::cerr << "Failed to initialize the processor." << std::endl; + return ; + } +#endif + + CameraPostion = static_cast(pos); + MediaResource = static_cast(mediaSource); + T_DjiReturnCode returnCode; + const T_DjiDataChannelBandwidthProportionOfHighspeedChannel bandwidthProportionOfHighspeedChannel = + {10, 60, 30}; + + returnCode = DjiHighSpeedDataChannel_SetBandwidthProportion(bandwidthProportionOfHighspeedChannel); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Liveview init failed, HighSpeed channel init error: 0x%08llX", returnCode); + return; + } + USER_LOG_INFO("step 1: init liveview"); + + returnCode = DjiLiveview_Init(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Liveview init faild, ret: 0x%08llX", returnCode); + goto init_failed; + } + +#ifdef OPEN_CV_INSTALLED + returnCode = DjiLiveview_RegUserAiTargetLableList(YOLO_LABLES_NUM, s_classLables); +#else + returnCode = DjiLiveview_RegUserAiTargetLableList(INVALID_CLASS_NUM, s_invalidLables); +#endif + + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Reg ai target lable faild, ret: 0x%08llX", returnCode); + goto init_failed; + } + USER_LOG_INFO("step 2: reg encoder callback"); + + returnCode = DjiLiveview_RegEncoderCallback(DjiLiveview_EncoderUseCallback); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR( "reg Yuv Encoder callback faild, ret: 0x%08llX", returnCode); + goto reg_encoder_callback_failed; + } + USER_LOG_INFO("step 3:start yuv stream"); + + returnCode = DjiLiveview_StartImageStream(CameraPostion, MediaResource, + PIXFMT_RGB_PACKED ,DjiLiveview_RcvImageCallback); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR( "start to subscribe YUV stream failed, ret: 0x%08llX", returnCode); + goto start_yuv_stream_failed; + } + USER_LOG_INFO("codec sample start ..."); + + while (true) { + std::cin >> isQuit; + if (isQuit == 'q' || isQuit == 'Q') { + break; + } + } + USER_LOG_INFO("codec sample end"); + +DjiLiveview_UnregUserAiTargetLableList(); +start_yuv_stream_failed: + returnCode = DjiLiveview_StopImageStream(CameraPostion, MediaResource); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR( "stop subscrib YUV stream failed, ret: 0x%08llX", returnCode); + } + +reg_encoder_callback_failed: + returnCode = DjiLiveview_UnregEncoderCallback(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR( "unreg encoder callback failed, ret: 0x%08llX", returnCode); + } + +init_failed: + returnCode = DjiLiveview_Deinit(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR( "deinit liveview failed, ret: 0x%08llX", returnCode); + } + outFileH264.close(); + outFileYUV.close(); + +#ifdef OPEN_CV_INSTALLED + osalHandler->TaskDestroy(s_procThreadHandle); + osalHandler->MutexDestroy(s_imageQueueMutexHandle); + osalHandler->MutexDestroy(s_metaQueueMutexHandle); + + while(!s_imageQueue.empty()){ + s_imageQueue.pop(); + } + while(!s_metaQueue.empty()) { + s_metaQueue.pop(); + } + +#endif + +} + +static std::string getCurrentTimestamp() { + std::time_t now = std::time(nullptr); + std::tm* now_tm = std::localtime(&now); + + std::ostringstream oss; + oss << (now_tm->tm_year + 1900) + << (now_tm->tm_mon + 1) + << now_tm->tm_mday + << now_tm->tm_hour + << now_tm->tm_min; + + return oss.str(); +} +static void outH264Tofile(const uint8_t *buf, int32_t len) { + if (!outFileH264) { + USER_LOG_ERROR( "output.h264 is not open"); + return; + } + outFileH264.write(reinterpret_cast(buf), len); +} + +static void outYUVTofile(const uint8_t *buf, int32_t len) { + if (!outFileYUV) { + USER_LOG_ERROR( "outyuv.h264 is not open"); + return; + } + outFileYUV.write(reinterpret_cast(buf), len); +} + +static void DjiLiveview_RcvImageCallback(E_DjiLiveViewCameraPosition position, const uint8_t *buf, uint32_t len, T_DjiLiveviewImageInfo imageInfo) +{ + T_DjiReturnCode DjiStat; + uint32_t OutPutLen; + std::vector bounding_boxes; + USER_LOG_INFO("catch image frame data, image type = %d height = %d, width = %d, frameId = %d, bufferLen= %d", + imageInfo.pixFmt ,imageInfo.height, imageInfo.width, imageInfo.frameId, len); + T_DjiLiveViewStandardMetaData * metaData = nullptr; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + +#ifdef OPEN_CV_INSTALLED + cv::Mat rgb_image( imageInfo.height, imageInfo.width, CV_8UC3, const_cast(buf)); + cv::Mat rgb_image_copy = rgb_image.clone(); + + osalHandler->MutexLock(s_imageQueueMutexHandle); + while (s_imageQueue.size() > 30) { + USER_LOG_WARN("The image queue is full. Drop this strike."); + s_imageQueue.pop(); + } + s_imageQueue.push(rgb_image_copy); + osalHandler->MutexUnlock(s_imageQueueMutexHandle); + + osalHandler->MutexLock(s_metaQueueMutexHandle); + if (!s_metaQueue.empty()) { + metaData = s_metaQueue.front(); + s_metaQueue.pop(); + } + osalHandler->MutexUnlock(s_metaQueueMutexHandle); + + DjiLiveview_EncodeAFrameToH264(buf, len, imageInfo, metaData); + if(metaData != nullptr) free(metaData); + +#else + + size_t size = sizeof(T_DjiLiveViewStandardMetaData) + 3 * sizeof(T_DjiLiveViewBoundingBox); + metaData = (T_DjiLiveViewStandardMetaData *)malloc(size); + if (!metaData) { + fprintf(stderr, "Failed to allocate memory\n"); + return ; + } + + // 初始化 boxCount + metaData->boxCount = 4; + + // 初始化每个 T_DjiLiveViewBoundingBox + for (int i = 0; i < 4; i++) { + metaData->boxData[i].id = i; + metaData->boxData[i].type = i; + metaData->boxData[i].state = 1; + metaData->boxData[i].box.cx = (i+1)*1000; + metaData->boxData[i].box.cy = (i+1)*1000; + metaData->boxData[i].box.w = 1000; + metaData->boxData[i].box.h = 1000; + metaData->boxData[i].box.distance = 0; + } + + // 打印结果 + + DjiLiveview_SendAiMetaToPilot(metaData); + + DjiLiveview_EncodeAFrameToH264(buf, len,imageInfo, metaData); +#endif +} + +static void DjiLiveview_EncoderUseCallback(const uint8_t *buf, uint32_t len) +{ + T_DjiReturnCode returnCode; + outH264Tofile(buf, len); + returnCode = DjiPayloadCamera_SendVideoStream(buf, len); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("failed to send video to pilot, ret: 0x%08llX", returnCode); + } +} + +static void* DjiLiveview_ObjectDetectionThread(void *arg) { + T_DjiReturnCode DjiStat; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + while(1) { + #ifdef OPEN_CV_INSTALLED + osalHandler->MutexLock(s_imageQueueMutexHandle); + if (s_imageQueue.empty()) { + osalHandler->MutexUnlock(s_imageQueueMutexHandle); + continue; + } + cv::Mat rgb_image = s_imageQueue.front(); + s_imageQueue.pop(); + osalHandler->MutexUnlock(s_imageQueueMutexHandle); + cv::Mat bgr_image; + cv::cvtColor(rgb_image, bgr_image, cv::COLOR_RGB2BGR); + + std::shared_ptr image_ptr = std::make_shared(bgr_image); + + + std::vector bounding_boxes; + processor.Process(image_ptr, bounding_boxes); + + T_DjiLiveViewStandardMetaData *metaData = (T_DjiLiveViewStandardMetaData *)malloc( + sizeof(T_DjiLiveViewStandardMetaData) + bounding_boxes.size() * sizeof(T_DjiLiveViewBoundingBox)); + metaData->boxCount = bounding_boxes.size(); + for (int i = 0; i < bounding_boxes.size(); i++) { + metaData->boxData[i] = bounding_boxes[i]; + } + + DjiLiveview_SendAiMetaToPilot(metaData); + + osalHandler->MutexLock(s_metaQueueMutexHandle); + s_metaQueue.push(metaData); + osalHandler->MutexUnlock(s_metaQueueMutexHandle); + + #else + break; + #endif + } + return NULL; +} diff --git a/samples/sample_c++/module_sample/liveview/dji_liveview_object_detection.hpp b/samples/sample_c++/module_sample/liveview/dji_liveview_object_detection.hpp new file mode 100644 index 0000000..24ecc0e --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/dji_liveview_object_detection.hpp @@ -0,0 +1,41 @@ +/** + ******************************************************************** + * + * @copyright (c) 2023 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef TEST_LIVEVIEW_CODEC_H +#define TEST_LIVEVIEW_CODEC_H + +#include "dji_liveview.h" +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +void DjiUser_RunCameraAiDetectionSample(void); +void DjiUser_RunOpenArSample(void); + +#ifdef __cplusplus +} +#endif +#endif // TEST_LIVEVIEW_CODEC_H + +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/module_sample/liveview/image_processor_yolovfastest.cpp b/samples/sample_c++/module_sample/liveview/image_processor_yolovfastest.cpp new file mode 100644 index 0000000..d448981 --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/image_processor_yolovfastest.cpp @@ -0,0 +1,140 @@ +/** + ******************************************************************** + * + * @copyright (c) 2023 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ +#ifdef OPEN_CV_INSTALLED +#include "image_processor_yolovfastest.hpp" + +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace cv; +using namespace dnn; +using namespace std; + +int32_t ImageProcessorYolovFastest::Init() { + + memset(cur_file_dir_path_, 0, kCurrentFilePathSizeMax); + memset(prototxt_file_dir_path_, 0, kFilePathSizeMax); + memset(weights_file_dir_path_, 0, kFilePathSizeMax); + + if (DjiUserUtil_GetCurrentFileDirPath(__FILE__, sizeof(cur_file_dir_path_), + cur_file_dir_path_) != 0) { + USER_LOG_ERROR("get path failed"); + return -1; + } + + snprintf(prototxt_file_dir_path_, kFilePathSizeMax, + "%s/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.cfg", + cur_file_dir_path_); + snprintf(weights_file_dir_path_, kFilePathSizeMax, + "%s/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.weights", + cur_file_dir_path_); + + USER_LOG_DEBUG("%s, %s", prototxt_file_dir_path_, weights_file_dir_path_); + net_ = readNetFromDarknet(prototxt_file_dir_path_, weights_file_dir_path_); + + if (net_.empty()) { + USER_LOG_ERROR("Failed to load network"); + return -1; + } + + return 0; +} + +void ImageProcessorYolovFastest::post_process(cv::Mat& frame, const std::vector& outs, std::vector& bounding_boxes) { + std::vector class_ids; + std::vector confidences; + std::vector boxes; + + for (size_t i = 0; i < outs.size(); ++i) { + float* data = (float*)outs[i].data; + for (int j = 0; j < outs[i].rows; ++j, data += outs[i].cols) { + cv::Mat scores = outs[i].row(j).colRange(5, outs[i].cols); + cv::Point classid_point; + double confidence; + cv::minMaxLoc(scores, 0, &confidence, 0, &classid_point); + if (confidence > 0.5) { + int cx = (int)(data[0] * frame.cols); + int cy = (int)(data[1] * frame.rows); + int w = (int)(data[2] * frame.cols); + int h = (int)(data[3] * frame.rows); + int left = cx - (w >> 1); + int top = cy - (h >> 1); + class_ids.push_back(classid_point.x); + confidences.push_back((float)confidence); + boxes.push_back(cv::Rect(left, top, w, h)); + } + } + } + + std::vector indices; + cv::dnn::NMSBoxes(boxes, confidences, 0.5, 0.4, indices); + for (size_t i = 0; i < indices.size(); ++i) { + int idx = indices[i]; + cv::Rect box = boxes[idx]; + + T_DjiLiveViewBoundingBox bounding_box; + bounding_box.id = i; + bounding_box.type = class_ids[idx]; + bounding_box.state = 1; + bounding_box.box.cx = (uint16_t)((box.x + box.width / 2) * 10000 / frame.cols); + bounding_box.box.cy = (uint16_t)((box.y + box.height / 2) * 10000 / frame.rows); + bounding_box.box.w = (uint16_t)(box.width * 10000 / frame.cols); + bounding_box.box.h = (uint16_t)(box.height * 10000 / frame.rows); + bounding_box.box.distance = 0; + bounding_boxes.push_back(bounding_box); + + std::cout << "Bounding Box " << i << ": " + << "Class ID = " << class_ids[idx] << ", " + << "Confidence = " << confidences[idx] << ", " + << "Box = [" << box.x << ", " << box.y << ", " << box.width << ", " << box.height << "]" + << std::endl; + + cv::rectangle(frame, box, cv::Scalar(0, 255, 0), 2); + std::string label = cv::format("ID: %d Conf: %.2f", class_ids[idx], confidences[idx]); + cv::putText(frame, label, cv::Point(box.x, box.y - 10), cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 255, 0), 2); + } +} + +void ImageProcessorYolovFastest::Process(const std::shared_ptr& image, std::vector& bounding_boxes) { + auto detect = [&](cv::Mat& frame, std::vector& outs) { + cv::Mat blob; + cv::dnn::blobFromImage(frame, blob, 1 / 255.0, cv::Size(320, 320), cv::Scalar(0, 0, 0), true, false); + net_.setInput(blob); + net_.forward(outs, net_.getUnconnectedOutLayersNames()); + }; + + cv::Mat frame = *image; + std::vector outs; + detect(frame, outs); + + post_process(frame, outs, bounding_boxes); +} + +#endif diff --git a/samples/sample_c++/module_sample/liveview/image_processor_yolovfastest.hpp b/samples/sample_c++/module_sample/liveview/image_processor_yolovfastest.hpp new file mode 100644 index 0000000..bbe9fce --- /dev/null +++ b/samples/sample_c++/module_sample/liveview/image_processor_yolovfastest.hpp @@ -0,0 +1,57 @@ +/** + ******************************************************************** + * + * @copyright (c) 2023 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ +#ifndef __IMAGE_PROCESSOR_DIAPLAY_H__ +#define __IMAGE_PROCESSOR_DIAPLAY_H__ +#ifdef OPEN_CV_INSTALLED + +#include +#include "opencv2/opencv.hpp" +#include + +class ImageProcessorYolovFastest { +public: + ImageProcessorYolovFastest(const std::string& name) : show_name_(name) {} + + ~ImageProcessorYolovFastest() {} + + int32_t Init(); + + using Image = cv::Mat; + void Process(const std::shared_ptr& image, std::vector& bounding_boxes); + std::vector Process(const std::shared_ptr& image); + +private: + std::string show_name_; + enum { + kFilePathSizeMax = 256, + kCurrentFilePathSizeMax = 128, + }; + + cv::dnn::Net net_; + char cur_file_dir_path_[kCurrentFilePathSizeMax]; + char prototxt_file_dir_path_[kFilePathSizeMax]; + char weights_file_dir_path_[kFilePathSizeMax]; + void post_process(cv::Mat& frame, const std::vector& outs, std::vector& bounding_boxes); +}; +#endif +#endif +// #endif diff --git a/samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp b/samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp old mode 100755 new mode 100644 diff --git a/samples/sample_c++/module_sample/perception/test_lidar_entry.cpp b/samples/sample_c++/module_sample/perception/test_lidar_entry.cpp new file mode 100644 index 0000000..ba8d20f --- /dev/null +++ b/samples/sample_c++/module_sample/perception/test_lidar_entry.cpp @@ -0,0 +1,272 @@ +/** +******************************************************************** +* @file test_lidar_entry.cpp +* @brief +* +* @copyright (c) 2021 DJI. All rights reserved. +* +* All information contained herein is, and remains, the property of DJI. +* The intellectual and technical concepts contained herein are proprietary +* to DJI and may be covered by U.S. and foreign patents, patents in process, +* and protected by trade secret or copyright law. Dissemination of this +* information, including but not limited to data and other proprietary +* material(s) incorporated within the information, in any form, is strictly +* prohibited without the express written consent of DJI. +* +* If you receive this source code without DJI’s authorization, you may not +* further disseminate the information, and you must immediately remove the +* source code and notify DJI of its removal. DJI reserves the right to pursue +* legal actions against you for any loss(es) or damage(s) caused by your +* failure to do so. +* +********************************************************************* +*/ + +/* Includes ------------------------------------------------------------------*/ +#include "test_lidar_entry.hpp" +#include +#include "dji_logger.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +/* Private constants ---------------------------------------------------------*/ +#define PCD_FILE_DEFAULT_LENGTH (512) +#define FRAME_BUFFER_LENGTH (1024 * 1024) +#define SUBSCRIBE_DATA_TIME_MS (1000 * 10) +#define USER_PERCEPTION_LIRDAR_TASK_STACK_SIZE (2042) +#define PCD_FILE_PATH "./DJI_cloud_data" + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static int lastFrameCnt = 0; +static std::queue lidarFrameQueue; +static T_DjiMutexHandle queueMutex; +static T_DjiSemaHandle dataSemaphore; +static bool stopProcessing = false; +static T_DjiSemaHandle taskExitSema; + +/* Private functions declaration ---------------------------------------------*/ +static void DjiTest_PerceptionLidarCallback(uint8_t *recvBuffer, uint32_t bufferLen); +static std::string DjiTest_getCurrentTimestamp(); +static void DjiTest_WriteLidarFrameToBinaryPcdFile(const T_DjiLidarFrame *frame); +static void* DjiTest_ProcessLidarDataTask(void* arg); + +/* Exported functions definition ---------------------------------------------*/ +void DjiUser_RunLidarDataSubscriptionSample(void) { + int subscriptionDuration = 10; + lastFrameCnt = 0; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + osalHandler->MutexCreate(&queueMutex); + osalHandler->SemaphoreCreate(0, &dataSemaphore); + osalHandler->SemaphoreCreate(0, &taskExitSema); + + std::cout << "Please ensure that there is enough storage space for the PCD files." << std::endl; + + T_DjiTaskHandle processingThread; + osalHandler->TaskCreate("LidarProcessingThread", DjiTest_ProcessLidarDataTask, USER_PERCEPTION_LIRDAR_TASK_STACK_SIZE, nullptr, &processingThread); + +start: + T_DjiReturnCode returnCode; + returnCode = DjiPerception_Init(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + std::cout << "DjiPerception Init failed" << std::endl; + return; + } + + std::cout << "start subscribe Lidar data from aircraft" << std::endl; + + returnCode = DjiPerception_SubscribeLidarData(DjiTest_PerceptionLidarCallback); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + std::cout << "Request to subscribe Lidar data failed" << std::endl; + goto subscribeFailed; + } + + osalHandler->TaskSleepMs(subscriptionDuration * 1000); + + std::cout << "unsubscribe Lidar data " << std::endl; + + subscribeFailed: + returnCode = DjiPerception_UnsubscribeLidarData(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + std::cout << "Request to unsubscribe Lidar data failed" << std::endl; + } + + returnCode = DjiPerception_Deinit(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + std::cout << "DjiPerception DeInit failed" << std::endl; + return; + } + + std::cout << "unsubscribe Lidar data success" << std::endl; + + osalHandler->MutexLock(queueMutex); + stopProcessing = true; + osalHandler->MutexUnlock(queueMutex); + + osalHandler->SemaphorePost(dataSemaphore); + osalHandler->SemaphoreWait(taskExitSema); + osalHandler->TaskDestroy(processingThread); + osalHandler->MutexDestroy(queueMutex); + osalHandler->SemaphoreDestroy(dataSemaphore); + osalHandler->SemaphoreDestroy(taskExitSema); +} + +/* Private functions definition-----------------------------------------------*/ +static void DjiTest_PerceptionLidarCallback(uint8_t *LidarFrame, uint32_t bufferLen) { + if (bufferLen != sizeof(T_DjiLidarFrame)) { + std::cout << "usb recv Lidar length wrong, length = " << bufferLen << std::endl; + return; + } + + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + T_DjiLidarFrame * curFrame = (T_DjiLidarFrame *)osalHandler->Malloc(bufferLen); + memcpy(curFrame, LidarFrame, bufferLen); + + osalHandler->MutexLock(queueMutex); + lidarFrameQueue.push(curFrame); + osalHandler->MutexUnlock(queueMutex); + + osalHandler->SemaphorePost(dataSemaphore); +} +std::string DjiTest_getCurrentTimestamp() { + auto now = std::chrono::system_clock::now(); + + std::time_t nowTimeT = std::chrono::system_clock::to_time_t(now); + + auto milliseconds = std::chrono::duration_cast(now.time_since_epoch()) % 1000; + + std::tm nowTm = *std::localtime(&nowTimeT); + std::ostringstream oss; + oss << std::put_time(&nowTm, "%Y%m%d_%H%M%S"); + oss << std::setfill('0') << std::setw(3) << milliseconds.count(); + + return oss.str(); +} + +static void DjiTest_WriteLidarFrameToBinaryPcdFile(const T_DjiLidarFrame *frame) { + uint32_t totalPoints = 0; + size_t headerLen = 0; + size_t pointDataSize = 0; + size_t bufferSize = 0; + char *buffer = NULL; + size_t bufferPos = 0; + int fd = 0; + std::string directory = PCD_FILE_PATH; + std::string filename = directory + "/DJI_cloud_data_" + DjiTest_getCurrentTimestamp() + ".pcd"; + char header[PCD_FILE_DEFAULT_LENGTH]; + + if (mkdir(directory.c_str(), 0755) != 0 && errno != EEXIST) { + fprintf(stderr, "Error creating directory: %s\n", strerror(errno)); + return; + } + + for (uint16_t i = 0; i < frame->pkgNum; ++i) { + totalPoints += frame->pkgs[i].header.dotNum; + } + + snprintf(header, sizeof(header), + "# .PCD v0.7 - Point Cloud Data file format\n" + "VERSION 0.7\n" + "FIELDS x y z intensity label\n" + "SIZE 4 4 4 1 1\n" + "TYPE F F F U U\n" + "COUNT 1 1 1 1 1\n" + "WIDTH %u\n" + "HEIGHT 1\n" + "VIEWPOINT 0 0 0 1 0 0 0\n" + "POINTS %u\n" + "DATA binary\n", + totalPoints, totalPoints); + + // Calculate the size of the buffer needed + headerLen = strlen(header); + pointDataSize = totalPoints * (sizeof(float) * 3 + sizeof(uint8_t) * 2); + bufferSize = headerLen + pointDataSize; + + buffer = (char *)malloc(bufferSize); + if (buffer == NULL) { + fprintf(stderr, "Error allocating memory for buffer\n"); + return; + } + + memcpy(buffer + bufferPos, header, headerLen); + bufferPos += headerLen; + + for (uint16_t i = 0; i < frame->pkgNum; ++i) { + const T_DjiPerceptionLidarDecodePkg *pkg = &frame->pkgs[i]; + for (uint16_t j = 0; j < pkg->header.dotNum; ++j) { + const T_DJIPerceptionLidarPoint *point = &pkg->points[j]; + memcpy(buffer + bufferPos, &point->x, sizeof(float)); + bufferPos += sizeof(float); + memcpy(buffer + bufferPos, &point->y, sizeof(float)); + bufferPos += sizeof(float); + memcpy(buffer + bufferPos, &point->z, sizeof(float)); + bufferPos += sizeof(float); + memcpy(buffer + bufferPos, &point->intensity, sizeof(uint8_t)); + bufferPos += sizeof(uint8_t); + memcpy(buffer + bufferPos, &point->label, sizeof(uint8_t)); + bufferPos += sizeof(uint8_t); + } + } + + fd = open(filename.c_str(), O_WRONLY | O_APPEND | O_CREAT, 0644); + if (fd == -1) { + fprintf(stderr, "Error opening file for writing\n"); + free(buffer); + return; + } + + if (write(fd, buffer, bufferSize) == -1) { + fprintf(stderr, "Error writing buffer to file\n"); + } + + close(fd); + free(buffer); +} + +static void* DjiTest_ProcessLidarDataTask(void* arg) { + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + while(true) { + osalHandler->SemaphoreWait(dataSemaphore); + + osalHandler->MutexLock(queueMutex); + bool shouldStop = stopProcessing && lidarFrameQueue.empty(); + if(shouldStop) { + osalHandler->MutexUnlock(queueMutex); + break; + } + + T_DjiLidarFrame *lidarFrame = lidarFrameQueue.front(); + lidarFrameQueue.pop(); + osalHandler->MutexUnlock(queueMutex); + + DjiTest_WriteLidarFrameToBinaryPcdFile(lidarFrame); + + int curFrameCnt = lidarFrame->frameCnt; + std::cout << "Lidar data : curFrameCnt=" << curFrameCnt << std::endl; + if(lastFrameCnt != 0 && (curFrameCnt - lastFrameCnt) > 1) { + std::cout << "The number of lost packets during transmission is: " << curFrameCnt - lastFrameCnt - 1 << std::endl; + } + lastFrameCnt = curFrameCnt; + + osalHandler->Free(lidarFrame); + } + + osalHandler->SemaphorePost(taskExitSema); + return nullptr; +} +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/module_sample/perception/test_lidar_entry.hpp b/samples/sample_c++/module_sample/perception/test_lidar_entry.hpp new file mode 100644 index 0000000..2fd2943 --- /dev/null +++ b/samples/sample_c++/module_sample/perception/test_lidar_entry.hpp @@ -0,0 +1,49 @@ +/** + ******************************************************************** + * @file test_lidar_entry.hpp + * @brief This is the header file for "test_lidar_entry.cpp", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef TEST_LIDAR_ENTRY_H +#define TEST_LIDAR_ENTRY_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_perception.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +void DjiUser_RunLidarDataSubscriptionSample(void); + +#ifdef __cplusplus +} +#endif + +#endif // TEST_LIDAR_ENTRY_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ \ No newline at end of file diff --git a/samples/sample_c++/module_sample/perception/test_radar_entry.cpp b/samples/sample_c++/module_sample/perception/test_radar_entry.cpp new file mode 100644 index 0000000..981ac4a --- /dev/null +++ b/samples/sample_c++/module_sample/perception/test_radar_entry.cpp @@ -0,0 +1,190 @@ +/** + ******************************************************************** + * @file test_radar_entry.cpp + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "test_radar_entry.hpp" +#include "dji_logger.h" +#include +#include +#include +/* Private constants ---------------------------------------------------------*/ + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ +static void DjiTest_PerceptionRadarCallback(E_DjiPerceptionRadarPosition radarPosition, + uint8_t *radarDataBuffer, uint32_t bufferLen); +static float parseVelocity(uint16_t velocity); +static float parseBeamAngle(uint16_t beamAngle); +/* Exported functions definition ---------------------------------------------*/ +void DjiUser_RunRadarDataSubscriptionSample(void) { + int subscriptionDuration = 10; + T_DjiReturnCode returnCode; + char inputChar; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + E_DjiPerceptionRadarPosition curPosition = MAX_RADAR_NUM; + returnCode = DjiPerception_Init(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("DjiPerception Init failed"); + return; + } + +inputAgain: + std::cout + << "| Available commands: |" + << + std::endl; + std::cout + << "| [d] Subscribe to downward millimeter wave radar data. |" + << + std::endl; + std::cout + << "| [u] Subscribe to upward millimeter wave radar data. |" + << + std::endl; + std::cout + << "| [f] Subscribe to forward millimeter wave radar data. |" + << + std::endl; + std::cout + << "| [b] Subscribe to backward millimeter wave radar data. |" + << + std::endl; + std::cout + << "| [l] Subscribe to leftward millimeter wave radar data. |" + << + std::endl; + std::cout + << "| [r] Subscribe to rightward millimeter wave radar data. |" + << + std::endl; + std::cout + << "| [q] quit |" + << + std::endl; + + std::cin >> inputChar; + switch (inputChar) { + case 'd': + USER_LOG_INFO("Subscribe to downward millimeter wave radar data"); + curPosition = RADAR_POSITION_DOWN; + break; + case 'u': + USER_LOG_INFO("Subscribe to upward millimeter wave radar data."); + curPosition = RADAR_POSITION_UP; + break; + case 'f': + USER_LOG_INFO("Subscribe to forward millimeter wave radar data."); + curPosition = RADAR_POSITION_FRONT; + break; + case 'b': + USER_LOG_INFO("Subscribe to backward millimeter wave radar data."); + curPosition = RADAR_POSITION_BACK; + break; + case 'l': + USER_LOG_INFO("Subscribe to leftward millimeter wave radar data."); + curPosition = RADAR_POSITION_LEFT; + break; + case 'r': + USER_LOG_INFO("Subscribe to rightward millimeter wave radar data."); + curPosition = RADAR_POSITION_RIGHT; + break; + case 'q': + goto endOfSample; + default: + goto inputAgain; + } + + returnCode = DjiPerception_SubscribeRadarData(curPosition, DjiTest_PerceptionRadarCallback); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Request to subscribe radar data failed"); + goto subscribeFailed; + } + + osalHandler->TaskSleepMs(subscriptionDuration * 1000); + +subscribeFailed: + + returnCode = DjiPerception_UnsubscribeRadarData(curPosition); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Request to unsubscribe Radar data failed"); + } + goto inputAgain; + +endOfSample: + returnCode = DjiPerception_Deinit(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("DjiPerception DeInit failed"); + return; + } +} + +/* Private functions definition-----------------------------------------------*/ +static void DjiTest_PerceptionRadarCallback(E_DjiPerceptionRadarPosition radarPosition, + uint8_t *radarDataBuffer, uint32_t bufferLen) { + T_DjiRadarDataFrame* radarData; + radarData = (T_DjiRadarDataFrame*)radarDataBuffer; + + if (radarDataBuffer == nullptr || bufferLen == 0) { + USER_LOG_ERROR("Invalid radar data: buffer=%p len=%u", radarDataBuffer, bufferLen); + return; + } + + USER_LOG_INFO("RadarData[pos:%d][len:%u][units:%u][pack:%u/%u]", + radarPosition, + bufferLen, + static_cast(radarData->headInfo.dataLen), + static_cast(radarData->headInfo.curPack), + static_cast(radarData->headInfo.packNum)); + + for (uint32_t i = 0; i < radarData->headInfo.dataLen; ++i) { + const T_DjiRadarCloudUnit* unit = &radarData->data[i]; + float azimuth = unit->azimuth / 1000.0f - 2*3.14; + float elevation = unit->elevation / 1000.0f - 2*3.14; + float radius = unit->radius / 100.0f; + float energy = unit->ene / 100.0f; + float velocity = parseVelocity(unit->base_info.velocity); + uint8_t snr = unit->base_info.snr; + float beamAngle = parseBeamAngle(unit->base_info.beamAngle); + + USER_LOG_INFO( + "[Unit%d] Azimuth=%.3f(rad), Elevation=%.3f(rad), Radius=%.2f(m), Energy=%.2f, " + "Velocity=%.2f(m/s), SNR=%u(dB), BeamAngle=%.2f(deg)", + i, azimuth, elevation, radius, energy, velocity, snr, beamAngle); + } +} + +static float parseVelocity(uint16_t velocity) { + return (velocity - 32767) / 100.0f; +} +static float parseBeamAngle(uint16_t beamAngle) { + if (beamAngle <= 450) { + return beamAngle / 10.0f; + } else { + return (beamAngle / 10.0f) - 90.0f; + } +} +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/module_sample/perception/test_radar_entry.hpp b/samples/sample_c++/module_sample/perception/test_radar_entry.hpp new file mode 100644 index 0000000..effa621 --- /dev/null +++ b/samples/sample_c++/module_sample/perception/test_radar_entry.hpp @@ -0,0 +1,49 @@ +/** + ******************************************************************** + * @file test_radar_entry.hpp + * @brief This is the header file for "test_radar_entry.cpp", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef TEST_RADAR_ENTRY_H +#define TEST_RADAR_ENTRY_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_perception.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +void DjiUser_RunRadarDataSubscriptionSample(void); + +#ifdef __cplusplus +} +#endif + +#endif // TEST_RADAR_ENTRY_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ \ No newline at end of file diff --git a/samples/sample_c++/module_sample/widget_manager/data/3K-5K.opus b/samples/sample_c++/module_sample/widget_manager/data/3K-5K.opus new file mode 100644 index 0000000..0da2097 Binary files /dev/null and b/samples/sample_c++/module_sample/widget_manager/data/3K-5K.opus differ diff --git a/samples/sample_c++/module_sample/widget_manager/test_widget_manager.cpp b/samples/sample_c++/module_sample/widget_manager/test_widget_manager.cpp new file mode 100644 index 0000000..59f4403 --- /dev/null +++ b/samples/sample_c++/module_sample/widget_manager/test_widget_manager.cpp @@ -0,0 +1,461 @@ +/** + ******************************************************************** + * @file test_widget_manager.cpp + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include +#include "test_widget_manager.hpp" +#include "dji_widget_manager.h" +#include +#include +#include "unistd.h" +#include "utils/util_misc.h" +#include +#include +#include +/* Private constants ---------------------------------------------------------*/ + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +T_DjiWidgetManagerFileList s_fileList; +static FILE* s_widgetFileFd; +/* Private functions declaration ---------------------------------------------*/ +static void DjiTestWidgetManager_RecvWidgetStatesCallback(E_DjiMountPosition position, T_DjiWidgetStates *statesData, uint8_t widgetNum); +static void DjiTestWidgetManager_RecvSpeakerStatesCallback(E_DjiMountPosition position, T_DjiSpeakerWidgetStates *speakerStates); +static void DjiTestWidgetManager_RunSeachLightManagerSample(E_DjiMountPosition position); +static void DjiTestWidgetManager_RunSpeakerManagerSample(E_DjiMountPosition position); +static T_DjiReturnCode DjiWidgetManager_UsrDownloadCallback(T_DjiDownloadWidgetFileInfo packetInfo, + const uint8_t *data, + uint16_t dataLen); +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode DjiTest_WidgetMannagerStart(void) +{ + T_DjiReturnCode djiStat; + E_DjiMountPosition position; + uint8_t index; + uint32_t value; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + T_DjiWidgetStates state; + int widget_type_input; + int inputPosition = 0; + int inputIndex = 0; + bool continueFlag = true; + int payloadType; + T_DjiWidgetManagerFileList fileList; + + std::cout << "Please select the position where the payload needs to be managed." << std::endl; + std::cin >> inputPosition; + std::cout << "Please select load type (1: third party payload; 2: DJI searchlight; 3: DJI speaker) "; + std::cin >>payloadType; + if (inputPosition < 1 || inputPosition > 8) { + std::cerr << "Invalid input for position. Must be between 1 and 8." << std::endl; + return -1; + } + + if (payloadType < 1 || payloadType > 3) { + std::cerr << "Invalid input for payload type. Must be between 1 and 3." << std::endl; + return -1; + } + + position = static_cast(inputPosition); + + djiStat = DjiWidgetManager_Init(); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test widget manager init error, stat = 0x%08llX", djiStat); + return djiStat; + } + + djiStat = DjiWidgetManager_RegDownloadFileDataCallback(position, DjiWidgetManager_UsrDownloadCallback); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test regist download callback on position:%d error, stat = 0x%08llX", position, djiStat); + goto finish_management; + } + + switch(payloadType){ + case 1: + djiStat = DjiWidgetManager_WidgetDownloadFileList(position, &s_fileList); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test download payload widget file list on position:%d error, stat = 0x%08llX", position, djiStat); + goto finish_management; + } + + for(int i = 0; i < s_fileList.totalCount; i++) { + djiStat = DjiWidgetManager_DownloadFileByIndex(position, i); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test download payload widget by index on position:%d error, stat = 0x%08llX", position, djiStat); + goto finish_management; + } + } + + djiStat = DjiWidgetManager_SubscribePayloadWidgetStates(position, DjiTestWidgetManager_RecvWidgetStatesCallback); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test subscribe payload widget state on position:%d error, stat = 0x%08llX", position, djiStat); + goto finish_management; + } + break; + case 2: + djiStat = DjiWidgetManager_WidgetDownloadFileList(position, &s_fileList); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test download payload widget file list on position:%d error, stat = 0x%08llX", position, djiStat); + goto finish_management; + } + + for(int i = 0; i < s_fileList.totalCount; i++) { + djiStat = DjiWidgetManager_DownloadFileByIndex(position, i); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test download payload widget by index on position:%d error, stat = 0x%08llX", position, djiStat); + goto finish_management; + } + } + + DjiTestWidgetManager_RunSeachLightManagerSample(position); + goto finish_management; + case 3: + DjiTestWidgetManager_RunSpeakerManagerSample(position); + goto finish_management; + } + +set_value: + std::cout << "If you need to change the widget state, enter 1 " << std::endl; + std::cin >> continueFlag; + if(continueFlag != 1) goto finish_management; + + std::cout << "Please enter the index and type to be set and the value to be set to :" << std::endl; + std::cin >> inputIndex >> widget_type_input >> state.widgetValue; + + if (widget_type_input >= 1 && widget_type_input <= 5) + { + state.widgetType = static_cast(widget_type_input); + state.widgetIndex = inputIndex; + } + else + { + std::cout << "Invalid widget type input." << std::endl; + goto finish_management; + } + + djiStat = DjiWidgetManager_SetWidgetState(position, state); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test set payload widget state on position: error, stat = 0x%08llX", position, djiStat); + goto finish_management; + } + + goto set_value; + +finish_management: + djiStat = DjiWidgetManager_DeInit(); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test deinit widget manager error, stat = 0x%08llX", djiStat); + return djiStat; + } + + if(s_fileList.fileListInfo != NULL) { + free(s_fileList.fileListInfo); + s_fileList.fileListInfo = NULL; + } + return djiStat; +} + +/* Private functions definition-----------------------------------------------*/ +static void DjiTestWidgetManager_RecvWidgetStatesCallback(E_DjiMountPosition position, T_DjiWidgetStates *statesData, uint8_t widgetNum) +{ + printf("\033[32mrecv widget state form pos: %u\n", position); + for (int i = 0; i < widgetNum; i++) + { + printf("widget index: %u type: %u value: %u\n", + statesData[i].widgetIndex, + static_cast(statesData[i].widgetType), + statesData[i].widgetValue); + } + printf("\033[0m"); +} + +static void DjiTestWidgetManager_RecvSpeakerStatesCallback(E_DjiMountPosition position, T_DjiSpeakerWidgetStates *speakerStates) { + printf("\033[0;34mrecv speaker state form pos: %u\n", position); + printf("speaker playMode = %d\n", speakerStates->playMode); + printf("speaker workMode = %d\n", speakerStates->workMode); + printf("speaker playVloume = %u\n", speakerStates->playVloume); + printf("speaker systemStates = %d\n", speakerStates->systemStates); + printf("speaker playFileUuid = %s\n", speakerStates->playFileUuid); + printf("speaker playFileName = %s\n", speakerStates->playFileName); + printf("speaker playQuality = %u\n", speakerStates->playFileName); + printf("speaker actualVolume = %u\n", speakerStates->actualVolume); + printf("speaker limitVolumeOnTheGround = %u\n", speakerStates->limitVolumeOnTheGround); + printf("\033[0m"); +} + +void DjiTestWidgetManager_RunSeachLightManagerSample(E_DjiMountPosition position) { + T_DjiReturnCode djiStat; + T_DjiWidgetStates state; + + djiStat = DjiWidgetManager_SubscribePayloadWidgetStates(position, DjiTestWidgetManager_RecvWidgetStatesCallback); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) + { + USER_LOG_ERROR("Dji test subscribe search light widget state on position:%d error, stat = 0x%08llX", position, djiStat); + // return ; + } + + std::cout<<"step 1: Turn on the searchlight."<socketFd, buf, len, 0, (struct sockaddr *) &addr, sizeof(struct sockaddr_in)); - if (ret >= 0) { - *realLen = ret; - } else { - return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + while (len > 0) { + size_t chunk_size = (len > MAX_UDP_PAYLOAD_SIZE) ? MAX_UDP_PAYLOAD_SIZE : len; + ssize_t sent = sendto(socketHandleStruct->socketFd, buf, chunk_size, 0, (struct sockaddr *) &addr, sizeof(struct sockaddr_in)); + + if (sent < 0) { + perror("sendto failed"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + buf += sent; + len -= sent; + total_sent += sent; } + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } diff --git a/samples/sample_c++/platform/linux/manifold2/CMakeLists.txt b/samples/sample_c++/platform/linux/manifold2/CMakeLists.txt index 991cc2d..418bae7 100644 --- a/samples/sample_c++/platform/linux/manifold2/CMakeLists.txt +++ b/samples/sample_c++/platform/linux/manifold2/CMakeLists.txt @@ -138,3 +138,5 @@ if (OpenCV_FOUND) target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS}) endif () +target_link_libraries(${PROJECT_NAME} dl) + diff --git a/samples/sample_c++/platform/linux/manifold2/application/main.cpp b/samples/sample_c++/platform/linux/manifold2/application/main.cpp index f7a14b0..cbcfa23 100644 --- a/samples/sample_c++/platform/linux/manifold2/application/main.cpp +++ b/samples/sample_c++/platform/linux/manifold2/application/main.cpp @@ -25,6 +25,8 @@ /* Includes ------------------------------------------------------------------*/ #include #include +#include +#include #include #include #include "application.hpp" @@ -71,6 +73,8 @@ start: << "| [d] Stereo vision view sample - display the stereo image |\n" << "| [e] Run camera manager sample - you can test camera's functions interactively |\n" << "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n" + << "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n" + << "| [h] Request Radar data sample - Request radar data |\n" << std::endl; std::cin >> inputChar; @@ -105,6 +109,12 @@ start: USER_LOG_INFO("Start rtk positioning sample successfully"); break; + case 'g': + DjiUser_RunLidarDataSubscriptionSample(); + break; + case 'h': + DjiUser_RunRadarDataSubscriptionSample(); + break; default: break; } diff --git a/samples/sample_c++/platform/linux/manifold3/CMakeLists.txt b/samples/sample_c++/platform/linux/manifold3/CMakeLists.txt new file mode 100644 index 0000000..5fd47d9 --- /dev/null +++ b/samples/sample_c++/platform/linux/manifold3/CMakeLists.txt @@ -0,0 +1,88 @@ +cmake_minimum_required(VERSION 3.5) +project(dji_sdk_demo_on_manifold3_cxx LANGUAGES CXX C) + +set(CMAKE_C_COMPILER "aarch64-linux-gnu-gcc" CACHE STRING "C compiler") +set(CMAKE_CXX_COMPILER "aarch64-linux-gnu-g++" CACHE STRING "C++ compiler") + +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -pthread -std=gnu99") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -pthread") +set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -pthread") + +add_compile_definitions( + _GNU_SOURCE + PLATFORM_ARCH_AARCH64=1 + SYSTEM_ARCH_LINUX=1 +) + +include_directories( + ../../../module_sample + ../../../../sample_c/module_sample + ../common + ../manifold3/application + include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include) +) + +file(GLOB_RECURSE MODULE_SAMPLE_SRC + ../../../module_sample/liveview/*.c* + ../../../module_sample/camera_manager/*.c* + ../../../module_sample/hms_manager/*.c* + ../../../module_sample/perception/*.c* + ../../../module_sample/gimbal/*.c* + ../../../module_sample/flight_controller/*.c* + ../../../module_sample/hms_manager/*.c* + ../../../module_sample/widget_manager/*.c* + ../../../../sample_c/module_sample/*.c + ../../../../sample_c/module_sample/widget_interaction_test/*.c +) +file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*) +file(GLOB_RECURSE MODULE_HAL_SRC hal/*.c*) +file(GLOB_RECURSE MODULE_APP_SRC application/*.c*) + +set(TOOLCHAIN_NAME aarch64-linux-gnu-gcc) +link_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME}) + +add_executable(${PROJECT_NAME} + ${MODULE_APP_SRC} + ${MODULE_SAMPLE_SRC} + ${MODULE_COMMON_SRC} + ${MODULE_HAL_SRC} +) + +target_link_libraries(${PROJECT_NAME} + PRIVATE + ${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME}/libpayloadsdk.a + stdc++ + m + dl +) + +# OpenCV +find_package(OpenCV QUIET) +if (OpenCV_FOUND) + message("\n${PROJECT_NAME}...") + message(STATUS "Found OpenCV installed in the system, will use it to display image in AdvancedSensing APIs") + message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}") + message(STATUS " - Libraries: ${OpenCV_LIBRARIES}") + add_definitions(-DOPEN_CV_INSTALLED) + target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS}) + target_link_libraries(${PROJECT_NAME} PRIVATE ${OpenCV_LIBRARIES}) +else () + message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data") +endif () + +# FFMPEG +find_package(PkgConfig) +pkg_check_modules(FFMPEG REQUIRED libavcodec libavformat libavutil libswscale) +if (FFMPEG_FOUND) + message(STATUS "Found FFMPEG installed in the system") + message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIRS}") + message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}") + + target_link_libraries(${PROJECT_NAME} PRIVATE ${FFMPEG_LIBRARIES}) + target_include_directories(${PROJECT_NAME} PRIVATE ${FFMPEG_INCLUDE_DIRS}) + target_compile_definitions(${PROJECT_NAME} PRIVATE FFMPEG_INSTALLED) +else() + message(STATUS "Cannot Find FFMPEG") +endif() + +set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin) \ No newline at end of file diff --git a/samples/sample_c++/platform/linux/manifold3/application/application.cpp b/samples/sample_c++/platform/linux/manifold3/application/application.cpp new file mode 100644 index 0000000..b01bf40 --- /dev/null +++ b/samples/sample_c++/platform/linux/manifold3/application/application.cpp @@ -0,0 +1,404 @@ +/** + ******************************************************************** + * @file application.cpp + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "application.hpp" +#include "dji_sdk_app_info.h" +#include +#include +#include +#include +#include +#include "dji_sdk_config.h" + +#include "../common/osal/osal.h" +#include "../common/osal/osal_fs.h" +#include "../common/osal/osal_socket.h" +#include "../hal/hal_usb_bulk.h" + +/* Private constants ---------------------------------------------------------*/ +#define DJI_LOG_PATH "logs/DJI" +#define DJI_LOG_INDEX_FILE_NAME "logs/index" +#define DJI_LOG_FOLDER_NAME "logs" +#define DJI_LOG_PATH_MAX_SIZE (128) +#define DJI_LOG_FOLDER_NAME_MAX_SIZE (32) +#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64) +#define DJI_LOG_MAX_COUNT (10) + +#define USER_UTIL_UNUSED(x) ((x) = (x)) +#define USER_UTIL_MIN(a, b) (((a) < (b)) ? (a) : (b)) +#define USER_UTIL_MAX(a, b) (((a) > (b)) ? (a) : (b)) + +extern "C" { +T_DjiReturnCode DjiTest_WidgetStartService(void); +} +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static FILE *s_djiLogFile; +static FILE *s_djiLogFileCnt; + +/* Private functions declaration ---------------------------------------------*/ +static void DjiUser_NormalExitHandler(int signalNum); + +/* Exported functions definition ---------------------------------------------*/ +Application::Application(int argc, char **argv) +{ + Application::DjiUser_SetupEnvironment(); + Application::DjiUser_ApplicationStart(); + + Osal_TaskSleepMs(3000); +} + +Application::~Application() += default; + +/* Private functions definition-----------------------------------------------*/ +void Application::DjiUser_SetupEnvironment() +{ + T_DjiReturnCode returnCode; + T_DjiOsalHandler osalHandler = {0}; + T_DjiHalUsbBulkHandler usbBulkHandler = {0}; + T_DjiLoggerConsole printConsole; + T_DjiLoggerConsole localRecordConsole; + T_DjiFileSystemHandler fileSystemHandler = {0}; + T_DjiSocketHandler socketHandler = {0}; + T_DjiHalNetworkHandler networkHandler = {0}; + + socketHandler.Socket = Osal_Socket; + socketHandler.Bind = Osal_Bind; + socketHandler.Close = Osal_Close; + socketHandler.UdpSendData = Osal_UdpSendData; + socketHandler.UdpRecvData = Osal_UdpRecvData; + socketHandler.TcpListen = Osal_TcpListen; + socketHandler.TcpAccept = Osal_TcpAccept; + socketHandler.TcpConnect = Osal_TcpConnect; + socketHandler.TcpSendData = Osal_TcpSendData; + socketHandler.TcpRecvData = Osal_TcpRecvData; + + osalHandler.TaskCreate = Osal_TaskCreate; + osalHandler.TaskDestroy = Osal_TaskDestroy; + osalHandler.TaskSleepMs = Osal_TaskSleepMs; + osalHandler.MutexCreate = Osal_MutexCreate; + osalHandler.MutexDestroy = Osal_MutexDestroy; + osalHandler.MutexLock = Osal_MutexLock; + osalHandler.MutexUnlock = Osal_MutexUnlock; + osalHandler.SemaphoreCreate = Osal_SemaphoreCreate; + osalHandler.SemaphoreDestroy = Osal_SemaphoreDestroy; + osalHandler.SemaphoreWait = Osal_SemaphoreWait; + osalHandler.SemaphoreTimedWait = Osal_SemaphoreTimedWait; + osalHandler.SemaphorePost = Osal_SemaphorePost; + osalHandler.Malloc = Osal_Malloc; + osalHandler.Free = Osal_Free; + osalHandler.GetTimeMs = Osal_GetTimeMs; + osalHandler.GetTimeUs = Osal_GetTimeUs; + osalHandler.GetRandomNum = Osal_GetRandomNum, + + printConsole.func = DjiUser_PrintConsole; + printConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO; + printConsole.isSupportColor = true; + + localRecordConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG; + localRecordConsole.func = DjiUser_LocalWrite; + localRecordConsole.isSupportColor = false; + + usbBulkHandler.UsbBulkInit = HalUsbBulk_Init; + usbBulkHandler.UsbBulkDeInit = HalUsbBulk_DeInit; + usbBulkHandler.UsbBulkWriteData = HalUsbBulk_WriteData; + usbBulkHandler.UsbBulkReadData = HalUsbBulk_ReadData; + usbBulkHandler.UsbBulkGetDeviceInfo = HalUsbBulk_GetDeviceInfo; + + fileSystemHandler.FileOpen = Osal_FileOpen, + fileSystemHandler.FileClose = Osal_FileClose, + fileSystemHandler.FileWrite = Osal_FileWrite, + fileSystemHandler.FileRead = Osal_FileRead, + fileSystemHandler.FileSync = Osal_FileSync, + fileSystemHandler.FileSeek = Osal_FileSeek, + fileSystemHandler.DirOpen = Osal_DirOpen, + fileSystemHandler.DirClose = Osal_DirClose, + fileSystemHandler.DirRead = Osal_DirRead, + fileSystemHandler.Mkdir = Osal_Mkdir, + fileSystemHandler.Unlink = Osal_Unlink, + fileSystemHandler.Rename = Osal_Rename, + fileSystemHandler.Stat = Osal_Stat, + + returnCode = DjiPlatform_RegOsalHandler(&osalHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register osal handler error."); + } + + returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal network handler error"); + } + + returnCode = DjiPlatform_RegSocketHandler(&socketHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("register osal socket handler error"); + } + + returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register osal filesystem handler error."); + } + + if (DjiUser_LocalWriteFsInit(DJI_LOG_PATH) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("File system init error."); + } + + returnCode = DjiLogger_AddConsole(&printConsole); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Add printf console error."); + } + + returnCode = DjiLogger_AddConsole(&localRecordConsole); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Add printf console error."); + } +} + +void Application::DjiUser_ApplicationStart() +{ + T_DjiUserInfo userInfo; + T_DjiReturnCode returnCode; + T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo; + T_DjiFirmwareVersion firmwareVersion = { + .majorVersion = 1, + .minorVersion = 0, + .modifyVersion = 0, + .debugVersion = 1, + }; + + // attention: when the program is hand up ctrl-c will generate the coredump file + signal(SIGTERM, DjiUser_NormalExitHandler); + + returnCode = DjiUser_FillInUserInfo(&userInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Fill user info error, please check user info config."); + } + + returnCode = DjiCore_Init(&userInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Core init error."); + } + + returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Get aircraft base info error."); + } + + if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT && + aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE && + aircraftInfoBaseInfo.mountPositionType != DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD && + aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_SKYPORT_V3) { + throw std::runtime_error("Please run this sample on extension port or skyport v3."); + } + + returnCode = DjiCore_SetAlias("PSDK_APPALIAS"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Set alias error."); + } + + returnCode = DjiCore_SetFirmwareVersion(firmwareVersion); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Set firmware version error."); + } + + returnCode = DjiCore_SetSerialNumber("PSDK12345678XX"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Set serial number error"); + } + + returnCode = DjiTest_WidgetStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget sample init error"); + } + + returnCode = DjiCore_ApplicationStart(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Start sdk application error."); + } + + USER_LOG_INFO("Application start."); +} + +T_DjiReturnCode Application::DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen) +{ + printf("%s", data); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode Application::DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen) +{ + int32_t realLen; + + if (s_djiLogFile == nullptr) { + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } + + realLen = fwrite(data, 1, dataLen, s_djiLogFile); + fflush(s_djiLogFile); + if (realLen == dataLen) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else { + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } +} + +T_DjiReturnCode Application::DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo) +{ + memset(userInfo->appName, 0, sizeof(userInfo->appName)); + memset(userInfo->appId, 0, sizeof(userInfo->appId)); + memset(userInfo->appKey, 0, sizeof(userInfo->appKey)); + memset(userInfo->appLicense, 0, sizeof(userInfo->appLicense)); + memset(userInfo->developerAccount, 0, sizeof(userInfo->developerAccount)); + memset(userInfo->baudRate, 0, sizeof(userInfo->baudRate)); + + if (strlen(USER_APP_NAME) >= sizeof(userInfo->appName) || + strlen(USER_APP_ID) > sizeof(userInfo->appId) || + strlen(USER_APP_KEY) > sizeof(userInfo->appKey) || + strlen(USER_APP_LICENSE) > sizeof(userInfo->appLicense) || + strlen(USER_DEVELOPER_ACCOUNT) >= sizeof(userInfo->developerAccount) || + strlen(USER_BAUD_RATE) > sizeof(userInfo->baudRate)) { + USER_LOG_ERROR("Length of user information string is beyond limit. Please check."); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + if (!strcmp(USER_APP_NAME, "your_app_name") || + !strcmp(USER_APP_ID, "your_app_id") || + !strcmp(USER_APP_KEY, "your_app_key") || + !strcmp(USER_BAUD_RATE, "your_app_license") || + !strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") || + !strcmp(USER_BAUD_RATE, "your_baud_rate")) { + USER_LOG_ERROR( + "Please fill in correct user information to 'samples/sample_c++/platform/linux/nvidia_jetson/application/dji_sdk_app_info.h' file."); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + strncpy(userInfo->appName, USER_APP_NAME, sizeof(userInfo->appName) - 1); + memcpy(userInfo->appId, USER_APP_ID, USER_UTIL_MIN(sizeof(userInfo->appId), strlen(USER_APP_ID))); + memcpy(userInfo->appKey, USER_APP_KEY, USER_UTIL_MIN(sizeof(userInfo->appKey), strlen(USER_APP_KEY))); + memcpy(userInfo->appLicense, USER_APP_LICENSE, + USER_UTIL_MIN(sizeof(userInfo->appLicense), strlen(USER_APP_LICENSE))); + memcpy(userInfo->baudRate, USER_BAUD_RATE, USER_UTIL_MIN(sizeof(userInfo->baudRate), strlen(USER_BAUD_RATE))); + strncpy(userInfo->developerAccount, USER_DEVELOPER_ACCOUNT, sizeof(userInfo->developerAccount) - 1); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode Application::DjiUser_LocalWriteFsInit(const char *path) +{ + T_DjiReturnCode djiReturnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + char filePath[DJI_LOG_PATH_MAX_SIZE]; + char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE]; + char folderName[DJI_LOG_FOLDER_NAME_MAX_SIZE]; + time_t currentTime = time(nullptr); + struct tm *localTime = localtime(¤tTime); + uint16_t logFileIndex = 0; + uint16_t currentLogFileIndex; + uint8_t ret; + + if (localTime == nullptr) { + printf("Get local time error.\r\n"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (access(DJI_LOG_FOLDER_NAME, F_OK) != 0) { + sprintf(folderName, "mkdir %s", DJI_LOG_FOLDER_NAME); + ret = system(folderName); + if (ret != 0) { + printf("Create new log folder error, ret:%d.\r\n", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + + s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "rb+"); + if (s_djiLogFileCnt == nullptr) { + s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "wb+"); + if (s_djiLogFileCnt == nullptr) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else { + ret = fseek(s_djiLogFileCnt, 0, SEEK_SET); + if (ret != 0) { + printf("Seek log count file error, ret: %d, errno: %d.\r\n", ret, errno); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = fread((uint16_t * ) & logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt); + if (ret != sizeof(uint16_t)) { + printf("Read log file index error.\r\n"); + } + } + + currentLogFileIndex = logFileIndex; + logFileIndex++; + + ret = fseek(s_djiLogFileCnt, 0, SEEK_SET); + if (ret != 0) { + printf("Seek log file error, ret: %d, errno: %d.\r\n", ret, errno); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = fwrite((uint16_t * ) & logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt); + if (ret != sizeof(uint16_t)) { + printf("Write log file index error.\r\n"); + fclose(s_djiLogFileCnt); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + fclose(s_djiLogFileCnt); + + sprintf(filePath, "%s_%04d_%04d%02d%02d_%02d-%02d-%02d.log", path, currentLogFileIndex, + localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday, + localTime->tm_hour, localTime->tm_min, localTime->tm_sec); + + s_djiLogFile = fopen(filePath, "wb+"); + if (s_djiLogFile == nullptr) { + USER_LOG_ERROR("Open filepath time error."); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (logFileIndex >= DJI_LOG_MAX_COUNT) { + sprintf(systemCmd, "rm -rf %s_%04d*.log", path, currentLogFileIndex - DJI_LOG_MAX_COUNT); + ret = system(systemCmd); + if (ret != 0) { + printf("Remove file error, ret:%d.\r\n", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + + sprintf(systemCmd, "ln -sfrv %s " DJI_LOG_FOLDER_NAME "/latest.log", filePath); + system(systemCmd); + return djiReturnCode; +} + +static void DjiUser_NormalExitHandler(int signalNum) +{ + USER_UTIL_UNUSED(signalNum); + exit(0); +} + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/manifold3/application/application.hpp b/samples/sample_c++/platform/linux/manifold3/application/application.hpp new file mode 100644 index 0000000..987abf0 --- /dev/null +++ b/samples/sample_c++/platform/linux/manifold3/application/application.hpp @@ -0,0 +1,67 @@ +/** + ******************************************************************** + * @file dji_application.hpp + * @brief This is the header file for "dji_application.cpp", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef APPLICATION_H +#define APPLICATION_H + +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include "dji_typedef.h" +#include "dji_core.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +using namespace std; + +class Application { +public: + Application(int argc, char **argv); + ~Application(); + +private: + static void DjiUser_SetupEnvironment(); + static void DjiUser_ApplicationStart(); + static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen); + static T_DjiReturnCode DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen); + static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo); + static T_DjiReturnCode DjiUser_LocalWriteFsInit(const char *path); +}; + +/* Exported functions --------------------------------------------------------*/ + + +#ifdef __cplusplus +} +#endif + +#endif // APPLICATION_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/manifold3/application/dji_sdk_app_info.h b/samples/sample_c++/platform/linux/manifold3/application/dji_sdk_app_info.h new file mode 100644 index 0000000..7330d8d --- /dev/null +++ b/samples/sample_c++/platform/linux/manifold3/application/dji_sdk_app_info.h @@ -0,0 +1,55 @@ +/** + ******************************************************************** + * @file dji_sdk_app_info.h + * @brief This is the header file for defining the structure and (exported) function prototypes. + * + * @copyright (c) 2018 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_SDK_APP_INFO_H +#define DJI_SDK_APP_INFO_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +// ATTENTION: User must goto https://developer.dji.com/user/apps/#all to create your own dji sdk application, get dji sdk application +// information then fill in the application information here. +#define USER_APP_NAME "your_app_name" +#define USER_APP_ID "your_app_id" +#define USER_APP_KEY "your_app_key" +#define USER_APP_LICENSE "your_app_license" +#define USER_DEVELOPER_ACCOUNT "your_developer_account" +#define USER_BAUD_RATE "460800" + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + + +#ifdef __cplusplus +} +#endif + +#endif // DJI_SDK_APP_INFO_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/manifold3/application/dji_sdk_config.h b/samples/sample_c++/platform/linux/manifold3/application/dji_sdk_config.h new file mode 100644 index 0000000..9b4a36d --- /dev/null +++ b/samples/sample_c++/platform/linux/manifold3/application/dji_sdk_config.h @@ -0,0 +1,56 @@ +/** + ******************************************************************** + * @file dji_sdk_config.h + * @brief This is the header file for "dji_config.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_SDK_CONFIG_H +#define DJI_SDK_CONFIG_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define DJI_USE_ONLY_UART (0) +#define DJI_USE_UART_AND_USB_BULK_DEVICE (1) +#define DJI_USE_UART_AND_NETWORK_DEVICE (2) +#define DJI_USE_ONLY_USB_BULK_DEVICE (3) +#define DJI_USE_ONLY_NETWORK_DEVICE (4) + +/*!< Attention: Select your hardware connection mode here. +* */ +#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_USB_BULK_DEVICE + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + +#ifdef __cplusplus +} +#endif + +#endif // DJI_SDK_CONFIG_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/manifold3/application/main.cpp b/samples/sample_c++/platform/linux/manifold3/application/main.cpp new file mode 100644 index 0000000..4e99daa --- /dev/null +++ b/samples/sample_c++/platform/linux/manifold3/application/main.cpp @@ -0,0 +1,145 @@ +/** + ******************************************************************** + * @file main.cpp + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include +#include +#include +#include +#include "application.hpp" +#include "fc_subscription/test_fc_subscription.h" +#include +#include +#include +#include +#include "widget/test_widget.h" +#include "widget/test_widget_speaker.h" +#include +#include +#include "data_transmission/test_data_transmission.h" +#include +#include +#include +#include "camera_manager/test_camera_manager_entry.h" +#include +#include +#include +/* Private constants ---------------------------------------------------------*/ + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +int main(int argc, char **argv) +{ + signal(SIGINT, [](int signalNum) -> void { exit(0); }); + Application application(argc, argv); + char inputChar; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + T_DjiReturnCode returnCode; + +start: + std::cout + << "\n" + << "| Available commands: |\n" + << "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n" + << "| [1] Flight controller sample - you can control flying by PSDK |\n" + << "| [2] Hms info manager sample - get health manger system info by language |\n" + << "| [a] Gimbal manager sample - you can control gimbal by PSDK |\n" + << "| [d] Stereo vision view sample - display the stereo image |\n" + << "| [e] Run camera manager sample - you can test camera's functions interactively |\n" + << "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n" + << "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n" + << "| [h] Request Radar data sample - Request radar data |\n" + << "| [i] Run manifold3 AI sample - request h.264 bitstream data, codec it and display it on pilot |\n" + << "| [j] Run Hms Enhance sample - shake motor and play sound on pilot |\n" + << "| [l] Run widget states manager sample, control widget states on other payload |\n" + << "| [m] Run Open Ar sample - draw ar gragh\n" + << std::endl; + + std::cin >> inputChar; + switch (inputChar) { + case '0': + DjiTest_FcSubscriptionRunSample(); + break; + case '1': + DjiUser_RunFlightControllerSample(); + break; + case '2': + DjiUser_RunHmsManagerSample(); + break; + case 'a': + DjiUser_RunGimbalManagerSample(); + break; + case 'd': + DjiUser_RunStereoVisionViewSample(); + break; + case 'e': + DjiUser_RunCameraManagerSample(); + break; + case 'f': + returnCode = DjiTest_PositioningStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("rtk positioning sample init error"); + break; + } + USER_LOG_INFO("Start rtk positioning sample successfully"); + break; + case 'g': + DjiUser_RunLidarDataSubscriptionSample(); + break; + case 'h': + DjiUser_RunRadarDataSubscriptionSample(); + break; + case 'i': + DjiUser_RunCameraAiDetectionSample(); + break; + case 'j': + DjiUser_RunHmsEnhanceSample(); + break; + case 'l': + DjiTest_WidgetMannagerStart(); + break; + case 'm': + DjiUser_RunOpenArSample(); + break; + case 'q': + break; + default: + break; + } + + osalHandler->TaskSleepMs(2000); + + goto start; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/manifold3/hal/hal_usb_bulk.c b/samples/sample_c++/platform/linux/manifold3/hal/hal_usb_bulk.c new file mode 100644 index 0000000..4723df0 --- /dev/null +++ b/samples/sample_c++/platform/linux/manifold3/hal/hal_usb_bulk.c @@ -0,0 +1,252 @@ +/** + ******************************************************************** + * @file hal_usb_bulk.c + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "hal_usb_bulk.h" +#include "dji_logger.h" +#include + +/* Private constants ---------------------------------------------------------*/ +#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50) +#define LINUX_USB_BULK_TRANSFER_WAIT_FOREVER (-1) + +/* Private types -------------------------------------------------------------*/ +typedef struct { +#ifdef LIBUSB_INSTALLED + libusb_device_handle *handle; +#else + void *handle; +#endif + int32_t ep1; + int32_t ep2; + uint32_t interfaceNum; + T_DjiHalUsbBulkInfo usbBulkInfo; +} T_HalUsbBulkObj; + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle) +{ + int32_t ret; + struct libusb_device_handle *handle = NULL; + + *usbBulkHandle = malloc(sizeof(T_HalUsbBulkObj)); + if (*usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_init(NULL); + if (ret < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid); + if (handle == NULL) { + USER_LOG_ERROR("libusb open device error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = libusb_claim_interface(handle, usbBulkInfo.channelInfo.interfaceNum); + if (ret != LIBUSB_SUCCESS) { + USER_LOG_ERROR("libusb claim interface error"); + libusb_close(handle); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle; + memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo)); +#endif + } else { + ((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle; + memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo)); + ((T_HalUsbBulkObj *) *usbBulkHandle)->interfaceNum = usbBulkInfo.channelInfo.interfaceNum; + + if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK1_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK1_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK1_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK2_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK2_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK2_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle) +{ + struct libusb_device_handle *handle = NULL; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum); + osalHandler->TaskSleepMs(100); + libusb_exit(NULL); +#endif + } else { + close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1); + close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2); + } + + free(usbBulkHandle); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len, + uint32_t *realLen) +{ + int32_t ret; + int32_t actualLen; + struct libusb_device_handle *handle = NULL; + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut, + (uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS); + if (ret < 0) { + USER_LOG_ERROR("Write usb bulk data failed, errno = %d", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + *realLen = actualLen; +#endif + } else { + ret = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len); + if (ret < 0) { + USER_LOG_ERROR("write ret %d %d %s\n", ret, errno, strerror(errno)); + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else { + *realLen = ret; + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, + uint32_t *realLen) +{ + int32_t ret; + struct libusb_device_handle *handle = NULL; + int32_t actualLen; + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn, + buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER); + if (ret < 0) { + USER_LOG_ERROR("Read usb bulk data failed, errno = %d", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + *realLen = actualLen; +#endif + } else { + ret = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len); + if (ret < 0) { + USER_LOG_ERROR("read ret %d %d %s\n", ret, errno, strerror(errno)); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } else { + *realLen = ret; + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo) +{ + //attention: this interface only be called in usb device mode. + deviceInfo->vid = LINUX_USB_VID; + deviceInfo->pid = LINUX_USB_PID; + + // This bulk channel is used to obtain DJI camera video stream and push 3rd-party camera video stream. + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].interfaceNum = LINUX_USB_BULK1_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointIn = LINUX_USB_BULK1_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointOut = LINUX_USB_BULK1_END_POINT_OUT; + + // This bulk channel is used to obtain DJI perception image and download camera media file. + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].interfaceNum = LINUX_USB_BULK2_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT; + + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/manifold3/hal/hal_usb_bulk.h b/samples/sample_c++/platform/linux/manifold3/hal/hal_usb_bulk.h new file mode 100644 index 0000000..36688ff --- /dev/null +++ b/samples/sample_c++/platform/linux/manifold3/hal/hal_usb_bulk.h @@ -0,0 +1,93 @@ +/** + ******************************************************************** + * @file hal_usb_bulk.h + * @brief This is the header file for "hal_usb_bulk.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef HAL_USB_BULK_H +#define HAL_USB_BULK_H + +/* Includes ------------------------------------------------------------------*/ +#include "stdint.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef LIBUSB_INSTALLED + +#include + +#endif + +#include "dji_platform.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define LINUX_USB_BULK1_EP_IN_FD "/dev/usb-ffs/bulk2/ep2" +#define LINUX_USB_BULK1_EP_OUT_FD "/dev/usb-ffs/bulk2/ep1" + +#define LINUX_USB_BULK1_INTERFACE_NUM (2) +#define LINUX_USB_BULK1_END_POINT_IN (0x83) +#define LINUX_USB_BULK1_END_POINT_OUT (0x02) + +#define LINUX_USB_BULK2_EP_IN_FD "/dev/usb-ffs/bulk6/ep2" +#define LINUX_USB_BULK2_EP_OUT_FD "/dev/usb-ffs/bulk6/ep1" + +#define LINUX_USB_BULK2_INTERFACE_NUM (6) +#define LINUX_USB_BULK2_END_POINT_IN (0x87) +#define LINUX_USB_BULK2_END_POINT_OUT (0x06) + +#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep2" +#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep1" + +#define LINUX_USB_BULK3_INTERFACE_NUM (3) +#define LINUX_USB_BULK3_END_POINT_IN (0x84) +#define LINUX_USB_BULK3_END_POINT_OUT (0x03) + +#define LINUX_USB_VID (0x2CA3) +#define LINUX_USB_PID (0x3181) +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle); +T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle); +T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len, + uint32_t *realLen); +T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo); + +#ifdef __cplusplus +} +#endif + +#endif // HAL_USB_BULK_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/CMakeLists.txt b/samples/sample_c++/platform/linux/nvidia_jetson/CMakeLists.txt index e2b34fd..27061f8 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/CMakeLists.txt +++ b/samples/sample_c++/platform/linux/nvidia_jetson/CMakeLists.txt @@ -48,79 +48,80 @@ add_executable(${PROJECT_NAME} ${MODULE_COMMON_SRC} ${MODULE_HAL_SRC}) -# Try to see if user has OpenCV installed -# if yes, default callback will display the image -find_package(OpenCV QUIET) -if (OpenCV_FOUND) - message("\n${PROJECT_NAME}...") - message(STATUS "Found OpenCV installed in the system, will use it to display image in AdvancedSensing APIs") - message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}") - message(STATUS " - Libraries: ${OpenCV_LIBRARIES}") - # add_definitions(-DOPEN_CV_INSTALLED) - # target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS}) - # target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS}) -else () - message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data") -endif () - -find_package(FFMPEG REQUIRED) -if (FFMPEG_FOUND) - message(STATUS "Found FFMPEG installed in the system") - message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIR}") - message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}") - - EXECUTE_PROCESS(COMMAND ffmpeg -version - OUTPUT_VARIABLE ffmpeg_version_output - OUTPUT_STRIP_TRAILING_WHITESPACE - ) - string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output}) - string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line}) - string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version}) - - if (HEAD${ffmpeg_major_version} STREQUAL "HEAD") - message(STATUS " - Version: ${ffmpeg_version}") - else () - message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.") - endif () - - # target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES}) - # include_directories(${FFMPEG_INCLUDE_DIR}) - # add_definitions(-DFFMPEG_INSTALLED) -else () - message(STATUS "Cannot Find FFMPEG") -endif (FFMPEG_FOUND) - include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include) +if (BUILD_CROSS_COMPILE MATCHES TRUE) + # Try to see if user has OpenCV installed + # if yes, default callback will display the image + find_package(OpenCV QUIET) + if (OpenCV_FOUND) + message("\n${PROJECT_NAME}...") + message(STATUS "Found OpenCV installed in the system, will use it to display image in AdvancedSensing APIs") + message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}") + message(STATUS " - Libraries: ${OpenCV_LIBRARIES}") + add_definitions(-DOPEN_CV_INSTALLED) + target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS}) + target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS}) + else () + message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data") + endif () -find_package(OPUS REQUIRED) -if (OPUS_FOUND) - message(STATUS "Found OPUS installed in the system") - message(STATUS " - Includes: ${OPUS_INCLUDE_DIR}") - message(STATUS " - Libraries: ${OPUS_LIBRARY}") + find_package(FFMPEG REQUIRED) + if (FFMPEG_FOUND) + message(STATUS "Found FFMPEG installed in the system") + message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIR}") + message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}") - # add_definitions(-DOPUS_INSTALLED) - # target_link_libraries(${PROJECT_NAME} /usr/local/lib/libopus.a) -else () - message(STATUS "Cannot Find OPUS") -endif (OPUS_FOUND) + EXECUTE_PROCESS(COMMAND ffmpeg -version + OUTPUT_VARIABLE ffmpeg_version_output + OUTPUT_STRIP_TRAILING_WHITESPACE + ) + string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output}) + string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line}) + string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version}) -find_package(LIBUSB REQUIRED) -if (LIBUSB_FOUND) - message(STATUS "Found LIBUSB installed in the system") - message(STATUS " - Includes: ${LIBUSB_INCLUDE_DIR}") - message(STATUS " - Libraries: ${LIBUSB_LIBRARY}") + if (HEAD${ffmpeg_major_version} STREQUAL "HEAD") + message(STATUS " - Version: ${ffmpeg_version}") + else () + message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.") + endif () - # add_definitions(-DLIBUSB_INSTALLED) - # target_link_libraries(${PROJECT_NAME} usb-1.0) -else () - message(STATUS "Cannot Find LIBUSB") -endif (LIBUSB_FOUND) + target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES}) + include_directories(${FFMPEG_INCLUDE_DIR}) + add_definitions(-DFFMPEG_INSTALLED) + else () + message(STATUS "Cannot Find FFMPEG") + endif (FFMPEG_FOUND) + + find_package(OPUS REQUIRED) + if (OPUS_FOUND) + message(STATUS "Found OPUS installed in the system") + message(STATUS " - Includes: ${OPUS_INCLUDE_DIR}") + message(STATUS " - Libraries: ${OPUS_LIBRARY}") + + add_definitions(-DOPUS_INSTALLED) + target_link_libraries(${PROJECT_NAME} /usr/local/lib/libopus.a) + else () + message(STATUS "Cannot Find OPUS") + endif (OPUS_FOUND) + + find_package(LIBUSB REQUIRED) + if (LIBUSB_FOUND) + message(STATUS "Found LIBUSB installed in the system") + message(STATUS " - Includes: ${LIBUSB_INCLUDE_DIR}") + message(STATUS " - Libraries: ${LIBUSB_LIBRARY}") + + add_definitions(-DLIBUSB_INSTALLED) + target_link_libraries(${PROJECT_NAME} usb-1.0) + else () + message(STATUS "Cannot Find LIBUSB") + endif (LIBUSB_FOUND) +endif () if (NOT EXECUTABLE_OUTPUT_PATH) set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin) endif () target_link_libraries(${PROJECT_NAME} m) +target_link_libraries(${PROJECT_NAME} dl) -add_dependencies(${PROJECT_NAME} djisdk) \ No newline at end of file diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/application/application.cpp b/samples/sample_c++/platform/linux/nvidia_jetson/application/application.cpp index 0825e29..a36d29c 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/application/application.cpp +++ b/samples/sample_c++/platform/linux/nvidia_jetson/application/application.cpp @@ -132,6 +132,7 @@ void Application::DjiUser_SetupEnvironment() uartHandler.UartWriteData = HalUart_WriteData; uartHandler.UartReadData = HalUart_ReadData; uartHandler.UartGetStatus = HalUart_GetStatus; + uartHandler.UartGetDeviceInfo = HalUart_GetDeviceInfo; usbBulkHandler.UsbBulkInit = HalUsbBulk_Init; usbBulkHandler.UsbBulkDeInit = HalUsbBulk_DeInit; @@ -184,6 +185,23 @@ void Application::DjiUser_SetupEnvironment() throw std::runtime_error("Register hal network handler error"); } +#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_USB_BULK_DEVICE) + returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal network handler error"); + } + +#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_NETWORK_DEVICE) + returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal network handler error"); + } + + //Attention: if you want to use camera stream view function, please uncomment it. + returnCode = DjiPlatform_RegSocketHandler(&socketHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("register osal socket handler error"); + } #endif returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler); @@ -236,8 +254,10 @@ void Application::DjiUser_ApplicationStart() throw std::runtime_error("Get aircraft base info error."); } - if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT) { - throw std::runtime_error("Please run this sample on extension port."); + if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT && + aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE && + aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_SKYPORT_V3) { + throw std::runtime_error("Please run this sample on extension port or skyport v3."); } returnCode = DjiCore_SetAlias("PSDK_APPALIAS"); @@ -313,7 +333,7 @@ T_DjiReturnCode Application::DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo) !strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") || !strcmp(USER_BAUD_RATE, "your_baud_rate")) { USER_LOG_ERROR( - "Please fill in correct user information to 'samples/sample_c++/platform/linux/manifold2/application/dji_sdk_app_info.h' file."); + "Please fill in correct user information to 'samples/sample_c++/platform/linux/nvidia_jetson/application/dji_sdk_app_info.h' file."); return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/application/dji_sdk_config.h b/samples/sample_c++/platform/linux/nvidia_jetson/application/dji_sdk_config.h index 39fd3d0..a579361 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/application/dji_sdk_config.h +++ b/samples/sample_c++/platform/linux/nvidia_jetson/application/dji_sdk_config.h @@ -37,10 +37,12 @@ extern "C" { #define DJI_USE_ONLY_UART (0) #define DJI_USE_UART_AND_USB_BULK_DEVICE (1) #define DJI_USE_UART_AND_NETWORK_DEVICE (2) +#define DJI_USE_ONLY_USB_BULK_DEVICE (3) +#define DJI_USE_ONLY_NETWORK_DEVICE (4) /*!< Attention: Select your hardware connection mode here. * */ -#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_UART +#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_USB_BULK_DEVICE /* Exported types ------------------------------------------------------------*/ diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/application/main.cpp b/samples/sample_c++/platform/linux/nvidia_jetson/application/main.cpp index 8b8e8cd..60a644b 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/application/main.cpp +++ b/samples/sample_c++/platform/linux/nvidia_jetson/application/main.cpp @@ -25,6 +25,8 @@ /* Includes ------------------------------------------------------------------*/ #include #include +#include +#include #include #include #include "application.hpp" @@ -42,8 +44,6 @@ #include #include "camera_manager/test_camera_manager_entry.h" #include -#include "waypoint_v2/test_waypoint_v2.h" -#include "waypoint_v3/test_waypoint_v3.h" /* Private constants ---------------------------------------------------------*/ @@ -74,6 +74,8 @@ start: << "| [d] Stereo vision view sample - display the stereo image |\n" << "| [e] Run camera manager sample - you can test camera's functions interactively |\n" << "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n" + << "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n" + << "| [h] Request Radar data sample - Request radar data |\n" << std::endl; std::cin >> inputChar; @@ -103,10 +105,10 @@ start: DjiUser_RunHmsManagerSample(); break; case '8': - DjiTest_WaypointV2RunSample(); + // DjiTest_WaypointV2RunSample(); break; case '9': - DjiTest_WaypointV3RunSample(); + // DjiTest_WaypointV3RunSample(); break; case 'a': DjiUser_RunGimbalManagerSample(); @@ -129,6 +131,12 @@ start: USER_LOG_INFO("Start rtk positioning sample successfully"); break; + case 'g': + DjiUser_RunLidarDataSubscriptionSample(); + break; + case 'h': + DjiUser_RunRadarDataSubscriptionSample(); + break; default: break; } diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_uart.c b/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_uart.c index b558c5e..5fae883 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_uart.c +++ b/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_uart.c @@ -255,6 +255,18 @@ T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *stat return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo) +{ + if (deviceInfo == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + deviceInfo->vid = USB_UART_CONNECTED_TO_UAV_VID; + deviceInfo->pid = USB_UART_CONNECTED_TO_UAV_PID; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + /* Private functions definition-----------------------------------------------*/ /****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_uart.h b/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_uart.h index f30a661..1be208e 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_uart.h +++ b/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_uart.h @@ -48,6 +48,15 @@ extern "C" { #define LINUX_UART_DEV1 "/dev/ttyUSB0" #define LINUX_UART_DEV2 "/dev/ttyACM0" +/** + * Use for Eport 2.0, specify the VID and PID of the USB serial port closest to the aircraft. + * FT232 0x0403:0x6001 + * CP2102 0x10C4:0xEA60 + * VCOM 0x2CA3:0xF002 + */ +#define USB_UART_CONNECTED_TO_UAV_VID (0x0403) +#define USB_UART_CONNECTED_TO_UAV_PID (0x6001) + /* Exported types ------------------------------------------------------------*/ /* Exported functions --------------------------------------------------------*/ @@ -56,6 +65,7 @@ T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle); T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status); +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo); #ifdef __cplusplus } diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_usb_bulk.c b/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_usb_bulk.c index 287d61e..85c5d72 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_usb_bulk.c +++ b/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_usb_bulk.c @@ -107,6 +107,16 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } } } @@ -230,6 +240,10 @@ T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo) deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN; deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT; + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_usb_bulk.h b/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_usb_bulk.h index a227c8a..056b1d4 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_usb_bulk.h +++ b/samples/sample_c++/platform/linux/nvidia_jetson/hal/hal_usb_bulk.h @@ -66,12 +66,19 @@ extern "C" { #define LINUX_USB_BULK2_END_POINT_IN (0x82) #define LINUX_USB_BULK2_END_POINT_OUT (0x02) +#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep1" +#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep2" + +#define LINUX_USB_BULK3_INTERFACE_NUM (2) +#define LINUX_USB_BULK3_END_POINT_IN (0x83) +#define LINUX_USB_BULK3_END_POINT_OUT (0x03) + #ifdef PLATFORM_ARCH_x86_64 #define LINUX_USB_VID (0x0B95) #define LINUX_USB_PID (0x1790) #else -#define LINUX_USB_VID (0x0955) -#define LINUX_USB_PID (0x7020) +#define LINUX_USB_VID (0x2CA3) +#define LINUX_USB_PID (0xF001) #endif /* Exported types ------------------------------------------------------------*/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/CMakeLists.txt b/samples/sample_c++/platform/linux/raspberry_pi/CMakeLists.txt new file mode 100644 index 0000000..792f9a9 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/CMakeLists.txt @@ -0,0 +1,132 @@ +cmake_minimum_required(VERSION 3.5) +project(dji_sdk_demo_on_rpi_cxx CXX) + +set(CMAKE_C_FLAGS "-pthread -std=gnu99") +set(CMAKE_CXX_FLAGS "-std=c++11 -pthread") +set(CMAKE_EXE_LINKER_FLAGS "-pthread") +set(CMAKE_C_COMPILER "aarch64-linux-gnu-gcc") +set(CMAKE_CXX_COMPILER "aarch64-linux-gnu-g++") +add_definitions(-D_GNU_SOURCE) + +if (MEMORY_LEAK_CHECK_ON MATCHES TRUE) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fsanitize=leak") + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fsanitize=leak") + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -lasan") +endif () + +if (BUILD_TEST_CASES_ON MATCHES TRUE) + set(COMMON_CXX_FLAGS "-std=c++11 -pthread") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fprofile-arcs -ftest-coverage -Wno-deprecated-declarations") + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage") + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fprofile-arcs -ftest-coverage -lgcov") +endif () + +include_directories(../../../module_sample) +include_directories(../../../../sample_c/module_sample) +include_directories(../common) +include_directories(application) + +file(GLOB_RECURSE MODULE_SAMPLE_SRC + ../../../module_sample/liveview/*.c* + ../../../module_sample/camera_manager/*.c* + ../../../module_sample/perception/*.c* + ../../../module_sample/gimbal/*.c* + ../../../module_sample/flight_controller/*.c* + ../../../module_sample/hms_manager/*.c* + ../../../../sample_c/module_sample/*.c + ../../../module_sample/widget_manager/*.c* + ) +file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*) +file(GLOB_RECURSE MODULE_HAL_SRC hal/*.c*) +file(GLOB_RECURSE MODULE_APP_SRC application/*.c*) + +set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../common/3rdparty) + +link_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/aarch64-linux-gnu-gcc) +link_libraries(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/aarch64-linux-gnu-gcc/libpayloadsdk.a -lstdc++) + +add_executable(${PROJECT_NAME} + ${MODULE_APP_SRC} + ${MODULE_SAMPLE_SRC} + ${MODULE_COMMON_SRC} + ${MODULE_HAL_SRC}) + +include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include) + +if (BUILD_CROSS_COMPILE MATCHES TRUE) + # Try to see if user has OpenCV installed + # if yes, default callback will display the image + find_package(OpenCV QUIET) + if (OpenCV_FOUND) + message("\n${PROJECT_NAME}...") + message(STATUS "Found OpenCV installed in the system, will use it to display image in AdvancedSensing APIs") + message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}") + message(STATUS " - Libraries: ${OpenCV_LIBRARIES}") + add_definitions(-DOPEN_CV_INSTALLED) + else () + message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data") + endif () + + find_package(FFMPEG REQUIRED) + if (FFMPEG_FOUND) + message(STATUS "Found FFMPEG installed in the system") + message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIR}") + message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}") + + EXECUTE_PROCESS(COMMAND ffmpeg -version + OUTPUT_VARIABLE ffmpeg_version_output + OUTPUT_STRIP_TRAILING_WHITESPACE + ) + string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output}) + string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line}) + string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version}) + + if (HEAD${ffmpeg_major_version} STREQUAL "HEAD") + message(STATUS " - Version: ${ffmpeg_version}") + else () + message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.") + endif () + + target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES}) + include_directories(${FFMPEG_INCLUDE_DIR}) + add_definitions(-DFFMPEG_INSTALLED) + else () + message(STATUS "Cannot Find FFMPEG") + endif (FFMPEG_FOUND) + + find_package(OPUS REQUIRED) + if (OPUS_FOUND) + message(STATUS "Found OPUS installed in the system") + message(STATUS " - Includes: ${OPUS_INCLUDE_DIR}") + message(STATUS " - Libraries: ${OPUS_LIBRARY}") + + add_definitions(-DOPUS_INSTALLED) + target_link_libraries(${PROJECT_NAME} /usr/local/lib/libopus.a) + else () + message(STATUS "Cannot Find OPUS") + endif (OPUS_FOUND) + + find_package(LIBUSB REQUIRED) + if (LIBUSB_FOUND) + message(STATUS "Found LIBUSB installed in the system") + message(STATUS " - Includes: ${LIBUSB_INCLUDE_DIR}") + message(STATUS " - Libraries: ${LIBUSB_LIBRARY}") + + add_definitions(-DLIBUSB_INSTALLED) + target_link_libraries(${PROJECT_NAME} usb-1.0) + else () + message(STATUS "Cannot Find LIBUSB") + endif (LIBUSB_FOUND) +endif() + +if (NOT EXECUTABLE_OUTPUT_PATH) + set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin) +endif () + +target_link_libraries(${PROJECT_NAME} m dl) + +target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS}) +if (OpenCV_FOUND) + target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS}) +endif () + diff --git a/samples/sample_c++/platform/linux/raspberry_pi/application/application.cpp b/samples/sample_c++/platform/linux/raspberry_pi/application/application.cpp new file mode 100644 index 0000000..555d823 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/application/application.cpp @@ -0,0 +1,542 @@ +/** + ******************************************************************** + * @file application.cpp + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "application.hpp" +#include "dji_sdk_app_info.h" +#include +#include +#include +#include +#include +#include "dji_sdk_config.h" + +#include "../common/osal/osal.h" +#include "../common/osal/osal_fs.h" +#include "../common/osal/osal_socket.h" +#include "../hal/hal_usb_bulk.h" +#include "../hal/hal_uart.h" +#include "../hal/hal_network.h" +#include "../hal/hal_i2c.h" + +#include +#include +#include +#include "widget/test_widget.h" +#include "widget/test_widget_speaker.h" +#include +#include "data_transmission/test_data_transmission.h" + +/* Private constants ---------------------------------------------------------*/ +#define DJI_LOG_PATH "Logs/DJI" +#define DJI_LOG_INDEX_FILE_NAME "Logs/index" +#define DJI_LOG_FOLDER_NAME "Logs" +#define DJI_LOG_PATH_MAX_SIZE (128) +#define DJI_LOG_FOLDER_NAME_MAX_SIZE (32) +#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64) +#define DJI_LOG_MAX_COUNT (10) + +#define USER_UTIL_UNUSED(x) ((x) = (x)) +#define USER_UTIL_MIN(a, b) (((a) < (b)) ? (a) : (b)) +#define USER_UTIL_MAX(a, b) (((a) > (b)) ? (a) : (b)) + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static FILE *s_djiLogFile; +static FILE *s_djiLogFileCnt; + +/* Private functions declaration ---------------------------------------------*/ +static void DjiUser_NormalExitHandler(int signalNum); +static T_DjiReturnCode DjiTest_HighPowerApplyPinInit(); +static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState); + +/* Exported functions definition ---------------------------------------------*/ +Application::Application(int argc, char **argv) +{ + Application::DjiUser_SetupEnvironment(); + Application::DjiUser_ApplicationStart(); + + Osal_TaskSleepMs(3000); +} + +Application::~Application() += default; + +/* Private functions definition-----------------------------------------------*/ +void Application::DjiUser_SetupEnvironment() +{ + T_DjiReturnCode returnCode; + T_DjiOsalHandler osalHandler = {0}; + T_DjiHalUartHandler uartHandler = {0}; + T_DjiHalUsbBulkHandler usbBulkHandler = {0}; + T_DjiLoggerConsole printConsole; + T_DjiLoggerConsole localRecordConsole; + T_DjiFileSystemHandler fileSystemHandler = {0}; + T_DjiSocketHandler socketHandler{0}; + T_DjiHalNetworkHandler networkHandler = {0}; + T_DjiHalI2cHandler i2CHandler = {0}; + + networkHandler.NetworkInit = HalNetWork_Init; + networkHandler.NetworkDeInit = HalNetWork_DeInit; + networkHandler.NetworkGetDeviceInfo = HalNetWork_GetDeviceInfo; + + socketHandler.Socket = Osal_Socket; + socketHandler.Bind = Osal_Bind; + socketHandler.Close = Osal_Close; + socketHandler.UdpSendData = Osal_UdpSendData; + socketHandler.UdpRecvData = Osal_UdpRecvData; + socketHandler.TcpListen = Osal_TcpListen; + socketHandler.TcpAccept = Osal_TcpAccept; + socketHandler.TcpConnect = Osal_TcpConnect; + socketHandler.TcpSendData = Osal_TcpSendData; + socketHandler.TcpRecvData = Osal_TcpRecvData; + + osalHandler.TaskCreate = Osal_TaskCreate; + osalHandler.TaskDestroy = Osal_TaskDestroy; + osalHandler.TaskSleepMs = Osal_TaskSleepMs; + osalHandler.MutexCreate = Osal_MutexCreate; + osalHandler.MutexDestroy = Osal_MutexDestroy; + osalHandler.MutexLock = Osal_MutexLock; + osalHandler.MutexUnlock = Osal_MutexUnlock; + osalHandler.SemaphoreCreate = Osal_SemaphoreCreate; + osalHandler.SemaphoreDestroy = Osal_SemaphoreDestroy; + osalHandler.SemaphoreWait = Osal_SemaphoreWait; + osalHandler.SemaphoreTimedWait = Osal_SemaphoreTimedWait; + osalHandler.SemaphorePost = Osal_SemaphorePost; + osalHandler.Malloc = Osal_Malloc; + osalHandler.Free = Osal_Free; + osalHandler.GetTimeMs = Osal_GetTimeMs; + osalHandler.GetTimeUs = Osal_GetTimeUs; + osalHandler.GetRandomNum = Osal_GetRandomNum; + + printConsole.func = DjiUser_PrintConsole; + printConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO; + printConsole.isSupportColor = true; + + localRecordConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG; + localRecordConsole.func = DjiUser_LocalWrite; + localRecordConsole.isSupportColor = false; + + uartHandler.UartInit = HalUart_Init; + uartHandler.UartDeInit = HalUart_DeInit; + uartHandler.UartWriteData = HalUart_WriteData; + uartHandler.UartReadData = HalUart_ReadData; + uartHandler.UartGetStatus = HalUart_GetStatus; + uartHandler.UartGetDeviceInfo = HalUart_GetDeviceInfo; + + i2CHandler.I2cInit = HalI2c_Init; + i2CHandler.I2cDeInit = HalI2c_DeInit; + i2CHandler.I2cWriteData = HalI2c_WriteData; + i2CHandler.I2cReadData = HalI2c_ReadData; + + usbBulkHandler.UsbBulkInit = HalUsbBulk_Init; + usbBulkHandler.UsbBulkDeInit = HalUsbBulk_DeInit; + usbBulkHandler.UsbBulkWriteData = HalUsbBulk_WriteData; + usbBulkHandler.UsbBulkReadData = HalUsbBulk_ReadData; + usbBulkHandler.UsbBulkGetDeviceInfo = HalUsbBulk_GetDeviceInfo; + + fileSystemHandler.FileOpen = Osal_FileOpen, + fileSystemHandler.FileClose = Osal_FileClose, + fileSystemHandler.FileWrite = Osal_FileWrite, + fileSystemHandler.FileRead = Osal_FileRead, + fileSystemHandler.FileSync = Osal_FileSync, + fileSystemHandler.FileSeek = Osal_FileSeek, + fileSystemHandler.DirOpen = Osal_DirOpen, + fileSystemHandler.DirClose = Osal_DirClose, + fileSystemHandler.DirRead = Osal_DirRead, + fileSystemHandler.Mkdir = Osal_Mkdir, + fileSystemHandler.Unlink = Osal_Unlink, + fileSystemHandler.Rename = Osal_Rename, + fileSystemHandler.Stat = Osal_Stat, + + returnCode = DjiPlatform_RegOsalHandler(&osalHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register osal handler error."); + } + + returnCode = DjiPlatform_RegHalI2cHandler(&i2CHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("register hal i2c handler error"); + } + +#if (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_USB_BULK_DEVICE) + returnCode = DjiPlatform_RegHalUartHandler(&uartHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal uart handler error."); + } + + returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal usb bulk handler error."); + } +#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_NETWORK_DEVICE) + returnCode = DjiPlatform_RegHalUartHandler(&uartHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal uart handler error."); + } + + returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal network handler error"); + } +#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_USB_BULK_DEVICE) + returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal network handler error"); + } + +#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_NETWORK_DEVICE) + returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal network handler error"); + } + + //Attention: if you want to use camera stream view function, please uncomment it. + returnCode = DjiPlatform_RegSocketHandler(&socketHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("register osal socket handler error"); + } +#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_UART) + /*!< Attention: Only use uart hardware connection. + */ + returnCode = DjiPlatform_RegHalUartHandler(&uartHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register hal uart handler error."); + } +#endif + + //Attention: if you want to use camera stream view function, please uncomment it. + returnCode = DjiPlatform_RegSocketHandler(&socketHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("register osal socket handler error"); + } + + returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Register osal filesystem handler error."); + } + + if (DjiUser_LocalWriteFsInit(DJI_LOG_PATH) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("File system init error."); + } + + returnCode = DjiLogger_AddConsole(&printConsole); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Add printf console error."); + } + + returnCode = DjiLogger_AddConsole(&localRecordConsole); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Add printf console error."); + } +} + +void Application::DjiUser_ApplicationStart() +{ + T_DjiUserInfo userInfo; + T_DjiReturnCode returnCode; + T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo; + T_DjiFirmwareVersion firmwareVersion = { + .majorVersion = 1, + .minorVersion = 0, + .modifyVersion = 0, + .debugVersion = 0, + }; + + // attention: when the program is hand up ctrl-c will generate the coredump file + signal(SIGTERM, DjiUser_NormalExitHandler); + + returnCode = DjiUser_FillInUserInfo(&userInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Fill user info error, please check user info config."); + } + + returnCode = DjiCore_SetFirmwareVersion(firmwareVersion); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Set firmware version error."); + } + + returnCode = DjiCore_SetSerialNumber("PSDK12345678XX"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Set serial number error"); + } + + returnCode = DjiCore_Init(&userInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + sleep(1); + throw std::runtime_error("Core init error."); + } + + returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Get aircraft base info error."); + } + + if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT && + aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE && + aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_SKYPORT_V3) { + throw std::runtime_error("Please run this sample on extension port or skyport v3."); + } + + returnCode = DjiCore_SetAlias("PSDK_APPALIAS"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Set alias error."); + } + +#ifdef CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON + returnCode = DjiTest_CameraEmuBaseStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("camera emu common init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON + returnCode = DjiTest_CameraEmuMediaStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("camera emu media init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON + returnCode = DjiTest_GimbalStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk gimbal init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_WIDGET_ON + returnCode = DjiTest_WidgetStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget sample init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON + returnCode = DjiTest_WidgetSpeakerStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget speaker test init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON + T_DjiTestApplyHighPowerHandler applyHighPowerHandler = { + .pinInit = DjiTest_HighPowerApplyPinInit, + .pinWrite = DjiTest_WriteHighPowerApplyPin, + }; + + returnCode = DjiTest_RegApplyHighPowerHandler(&applyHighPowerHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("regsiter apply high power handler error"); + } + + returnCode = DjiTest_PowerManagementStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("power management init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON + returnCode = DjiTest_DataTransmissionStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget sample init error"); + } +#endif + + returnCode = DjiCore_ApplicationStart(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + throw std::runtime_error("Start sdk application error."); + } + + USER_LOG_INFO("Application start."); +} + +T_DjiReturnCode Application::DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen) +{ + printf("%s", data); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode Application::DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen) +{ + int32_t realLen; + + if (s_djiLogFile == nullptr) { + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } + + realLen = fwrite(data, 1, dataLen, s_djiLogFile); + fflush(s_djiLogFile); + if (realLen == dataLen) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else { + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } +} + +T_DjiReturnCode Application::DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo) +{ + memset(userInfo->appName, 0, sizeof(userInfo->appName)); + memset(userInfo->appId, 0, sizeof(userInfo->appId)); + memset(userInfo->appKey, 0, sizeof(userInfo->appKey)); + memset(userInfo->appLicense, 0, sizeof(userInfo->appLicense)); + memset(userInfo->developerAccount, 0, sizeof(userInfo->developerAccount)); + memset(userInfo->baudRate, 0, sizeof(userInfo->baudRate)); + + if (strlen(USER_APP_NAME) >= sizeof(userInfo->appName) || + strlen(USER_APP_ID) > sizeof(userInfo->appId) || + strlen(USER_APP_KEY) > sizeof(userInfo->appKey) || + strlen(USER_APP_LICENSE) > sizeof(userInfo->appLicense) || + strlen(USER_DEVELOPER_ACCOUNT) >= sizeof(userInfo->developerAccount) || + strlen(USER_BAUD_RATE) > sizeof(userInfo->baudRate)) { + USER_LOG_ERROR("Length of user information string is beyond limit. Please check."); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + if (!strcmp(USER_APP_NAME, "your_app_name") || + !strcmp(USER_APP_ID, "your_app_id") || + !strcmp(USER_APP_KEY, "your_app_key") || + !strcmp(USER_BAUD_RATE, "your_app_license") || + !strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") || + !strcmp(USER_BAUD_RATE, "your_baud_rate")) { + USER_LOG_ERROR( + "Please fill in correct user information to 'samples/sample_c++/platform/linux/manifold2/application/dji_sdk_app_info.h' file."); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + strncpy(userInfo->appName, USER_APP_NAME, sizeof(userInfo->appName) - 1); + memcpy(userInfo->appId, USER_APP_ID, USER_UTIL_MIN(sizeof(userInfo->appId), strlen(USER_APP_ID))); + memcpy(userInfo->appKey, USER_APP_KEY, USER_UTIL_MIN(sizeof(userInfo->appKey), strlen(USER_APP_KEY))); + memcpy(userInfo->appLicense, USER_APP_LICENSE, + USER_UTIL_MIN(sizeof(userInfo->appLicense), strlen(USER_APP_LICENSE))); + memcpy(userInfo->baudRate, USER_BAUD_RATE, USER_UTIL_MIN(sizeof(userInfo->baudRate), strlen(USER_BAUD_RATE))); + strncpy(userInfo->developerAccount, USER_DEVELOPER_ACCOUNT, sizeof(userInfo->developerAccount) - 1); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode Application::DjiUser_LocalWriteFsInit(const char *path) +{ + T_DjiReturnCode djiReturnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + char filePath[DJI_LOG_PATH_MAX_SIZE]; + char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE]; + char folderName[DJI_LOG_FOLDER_NAME_MAX_SIZE]; + time_t currentTime = time(nullptr); + struct tm *localTime = localtime(¤tTime); + uint16_t logFileIndex = 0; + uint16_t currentLogFileIndex; + uint8_t ret; + + if (localTime == nullptr) { + printf("Get local time error.\r\n"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (access(DJI_LOG_FOLDER_NAME, F_OK) != 0) { + sprintf(folderName, "mkdir %s", DJI_LOG_FOLDER_NAME); + ret = system(folderName); + if (ret != 0) { + printf("Create new log folder error, ret:%d.\r\n", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + + s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "rb+"); + if (s_djiLogFileCnt == nullptr) { + s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "wb+"); + if (s_djiLogFileCnt == nullptr) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else { + ret = fseek(s_djiLogFileCnt, 0, SEEK_SET); + if (ret != 0) { + printf("Seek log count file error, ret: %d, errno: %d.\r\n", ret, errno); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = fread((uint16_t *) &logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt); + if (ret != sizeof(uint16_t)) { + printf("Read log file index error.\r\n"); + } + } + + currentLogFileIndex = logFileIndex; + logFileIndex++; + + ret = fseek(s_djiLogFileCnt, 0, SEEK_SET); + if (ret != 0) { + printf("Seek log file error, ret: %d, errno: %d.\r\n", ret, errno); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = fwrite((uint16_t *) &logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt); + if (ret != sizeof(uint16_t)) { + printf("Write log file index error.\r\n"); + fclose(s_djiLogFileCnt); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + fclose(s_djiLogFileCnt); + + sprintf(filePath, "%s_%04d_%04d%02d%02d_%02d-%02d-%02d.log", path, currentLogFileIndex, + localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday, + localTime->tm_hour, localTime->tm_min, localTime->tm_sec); + + s_djiLogFile = fopen(filePath, "wb+"); + if (s_djiLogFile == nullptr) { + USER_LOG_ERROR("Open filepath time error."); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (logFileIndex >= DJI_LOG_MAX_COUNT) { + sprintf(systemCmd, "rm -rf %s_%04d*.log", path, currentLogFileIndex - DJI_LOG_MAX_COUNT); + ret = system(systemCmd); + if (ret != 0) { + printf("Remove file error, ret:%d.\r\n", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + + return djiReturnCode; +} + +static void DjiUser_NormalExitHandler(int signalNum) +{ + USER_UTIL_UNUSED(signalNum); + exit(0); +} + +static T_DjiReturnCode DjiTest_HighPowerApplyPinInit() +{ + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState) +{ + //attention: please pull up the HWPR pin state by hardware. + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/application/application.hpp b/samples/sample_c++/platform/linux/raspberry_pi/application/application.hpp new file mode 100644 index 0000000..987abf0 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/application/application.hpp @@ -0,0 +1,67 @@ +/** + ******************************************************************** + * @file dji_application.hpp + * @brief This is the header file for "dji_application.cpp", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef APPLICATION_H +#define APPLICATION_H + +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include "dji_typedef.h" +#include "dji_core.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +using namespace std; + +class Application { +public: + Application(int argc, char **argv); + ~Application(); + +private: + static void DjiUser_SetupEnvironment(); + static void DjiUser_ApplicationStart(); + static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen); + static T_DjiReturnCode DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen); + static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo); + static T_DjiReturnCode DjiUser_LocalWriteFsInit(const char *path); +}; + +/* Exported functions --------------------------------------------------------*/ + + +#ifdef __cplusplus +} +#endif + +#endif // APPLICATION_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/application/dji_sdk_app_info.h b/samples/sample_c++/platform/linux/raspberry_pi/application/dji_sdk_app_info.h new file mode 100644 index 0000000..7330d8d --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/application/dji_sdk_app_info.h @@ -0,0 +1,55 @@ +/** + ******************************************************************** + * @file dji_sdk_app_info.h + * @brief This is the header file for defining the structure and (exported) function prototypes. + * + * @copyright (c) 2018 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_SDK_APP_INFO_H +#define DJI_SDK_APP_INFO_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +// ATTENTION: User must goto https://developer.dji.com/user/apps/#all to create your own dji sdk application, get dji sdk application +// information then fill in the application information here. +#define USER_APP_NAME "your_app_name" +#define USER_APP_ID "your_app_id" +#define USER_APP_KEY "your_app_key" +#define USER_APP_LICENSE "your_app_license" +#define USER_DEVELOPER_ACCOUNT "your_developer_account" +#define USER_BAUD_RATE "460800" + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + + +#ifdef __cplusplus +} +#endif + +#endif // DJI_SDK_APP_INFO_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/application/dji_sdk_config.h b/samples/sample_c++/platform/linux/raspberry_pi/application/dji_sdk_config.h new file mode 100644 index 0000000..69aaf98 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/application/dji_sdk_config.h @@ -0,0 +1,70 @@ +/** + ******************************************************************** + * @file dji_sdk_config.h + * @brief This is the header file for "dji_config.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_SDK_CONFIG_H +#define DJI_SDK_CONFIG_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define DJI_USE_ONLY_UART (0) +#define DJI_USE_UART_AND_USB_BULK_DEVICE (1) +#define DJI_USE_UART_AND_NETWORK_DEVICE (2) +#define DJI_USE_ONLY_USB_BULK_DEVICE (3) +#define DJI_USE_ONLY_NETWORK_DEVICE (4) + +/*!< Attention: Select your hardware connection mode here. +* */ +#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_UART + +#define CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON true + +#define CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON true + +#define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON true + +#define CONFIG_MODULE_SAMPLE_WIDGET_ON true + +#define CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON true + +#define CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON true + +#define CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON true + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + +#ifdef __cplusplus +} +#endif + +#endif // DJI_SDK_CONFIG_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/application/main.cpp b/samples/sample_c++/platform/linux/raspberry_pi/application/main.cpp new file mode 100644 index 0000000..1a9090c --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/application/main.cpp @@ -0,0 +1,133 @@ +/** + ******************************************************************** + * @file main.cpp + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include +#include +#include +#include +#include "application.hpp" +#include "fc_subscription/test_fc_subscription.h" +#include +#include +#include +#include +#include "widget/test_widget.h" +#include "widget/test_widget_speaker.h" +#include +#include "data_transmission/test_data_transmission.h" +#include +#include +#include +#include "camera_manager/test_camera_manager_entry.h" +#include +/* Private constants ---------------------------------------------------------*/ + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +int main(int argc, char **argv) +{ + Application application(argc, argv); + char inputChar; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + T_DjiReturnCode returnCode; + T_DjiTestApplyHighPowerHandler applyHighPowerHandler; + +start: + std::cout + << "\n" + << "| Available commands: |\n" + << "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n" + << "| [1] Flight controller sample - you can control flying by PSDK |\n" + << "| [2] Hms info manager sample - get health manger system info by language |\n" + << "| [a] Gimbal manager sample - you can control gimbal by PSDK |\n" + << "| [c] Camera stream view sample - display the camera video stream |\n" + << "| [d] Stereo vision view sample - display the stereo image |\n" + << "| [e] Run camera manager sample - you can test camera's functions interactively |\n" + << "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n" + << "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n" + << "| [h] Request Radar data sample - Request radar data |\n" + << "| [l] Run widget states manager sample, control widget states on other payload |\n" + << std::endl; + + std::cin >> inputChar; + switch (inputChar) { + case '0': + DjiTest_FcSubscriptionRunSample(); + break; + case '1': + DjiUser_RunFlightControllerSample(); + break; + case '2': + DjiUser_RunHmsManagerSample(); + break; + case 'a': + DjiUser_RunGimbalManagerSample(); + break; + case 'c': + DjiUser_RunCameraStreamViewSample(); + break; + case 'd': + DjiUser_RunStereoVisionViewSample(); + break; + case 'e': + DjiUser_RunCameraManagerSample(); + break; + case 'f': + returnCode = DjiTest_PositioningStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("rtk positioning sample init error"); + break; + } + + USER_LOG_INFO("Start rtk positioning sample successfully"); + break; + case 'g': + DjiUser_RunLidarDataSubscriptionSample(); + break; + case 'h': + DjiUser_RunRadarDataSubscriptionSample(); + break; + case 'l': + DjiTest_WidgetMannagerStart(); + break; + default: + break; + } + + osalHandler->TaskSleepMs(2000); + + goto start; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.c b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.c new file mode 100644 index 0000000..2c60b77 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.c @@ -0,0 +1,176 @@ +/** + ******************************************************************** + * @file hal_i2c.c + * @brief + * + * @copyright (c) 2018 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "hal_i2c.h" +#include +#include +#include +#include +#include +#include + +/* Private constants ---------------------------------------------------------*/ +#define I2C_DEVICE_RESET_TIME_US (25 * 1000) +#define I2C_DEVICE_RESET_GPIO_NUM (4) +#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64) + +/* Private types -------------------------------------------------------------*/ +typedef struct { + int32_t i2cFd; +} T_I2cHandleStruct; + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ +static void HalI2c_ResetDevice(void); + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode HalI2c_Init(T_DjiHalI2cConfig i2cConfig, T_DjiI2cHandle *i2cHandle) +{ + T_I2cHandleStruct *i2CHandleStruct = NULL; + + //attention: suggest reset the i2c device before init it. + HalI2c_ResetDevice(); + + i2CHandleStruct = malloc(sizeof(T_I2cHandleStruct)); + if (i2CHandleStruct == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED; + } + + i2CHandleStruct->i2cFd = open(LINUX_I2C_DEV1, O_RDWR); + if (i2CHandleStruct->i2cFd < 0) { + printf("Open i2c device failed, fd: %d\r\n", i2CHandleStruct->i2cFd); + return -1; + } + + *i2cHandle = i2CHandleStruct; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalI2c_DeInit(T_DjiI2cHandle i2cHandle) +{ + T_I2cHandleStruct *i2CHandleStruct = (T_I2cHandleStruct *) i2cHandle; + + close(i2CHandleStruct->i2cFd); + free(i2CHandleStruct); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalI2c_WriteData(T_DjiI2cHandle i2cHandle, uint16_t devAddress, const uint8_t *buf, + uint32_t len, uint32_t *realLen) +{ + struct i2c_rdwr_ioctl_data data; + struct i2c_msg messages; + int32_t ret = 0; + T_I2cHandleStruct *i2CHandleStruct = (T_I2cHandleStruct *) i2cHandle; + + messages.addr = devAddress; + messages.flags = 0; + messages.len = len; + messages.buf = (uint8_t *) buf; + + data.msgs = &messages; + data.nmsgs = 1; + + ret = ioctl(i2CHandleStruct->i2cFd, I2C_RDWR, &data); + if (ret < 0) { + *realLen = 0; + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + *realLen = ret; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalI2c_ReadData(T_DjiI2cHandle i2cHandle, uint16_t devAddress, uint8_t *buf, + uint32_t len, uint32_t *realLen) +{ + struct i2c_rdwr_ioctl_data data; + struct i2c_msg messages; + int32_t ret = 0; + T_I2cHandleStruct *i2CHandleStruct = (T_I2cHandleStruct *) i2cHandle; + + messages.addr = devAddress; + messages.flags = I2C_M_RD; + messages.len = len; + messages.buf = buf; + + data.msgs = &messages; + data.nmsgs = 1; + + ret = ioctl(i2CHandleStruct->i2cFd, I2C_RDWR, &data); + if (ret < 0) { + *realLen = 0; + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + *realLen = ret; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ +static void HalI2c_ResetDevice(void) +{ + char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE] = {0}; + int32_t ret; + + sprintf(systemCmd, "echo %d > /sys/class/gpio/export", I2C_DEVICE_RESET_GPIO_NUM); + ret = system(systemCmd); + if (ret != 0) { + printf("Export reset gpio failed, %d\r\n", ret); + } + + sprintf(systemCmd, "echo out > /sys/class/gpio/gpio4/direction"); + ret = system(systemCmd); + if (ret != 0) { + printf("Set gpio direction failed, %d\r\n", ret); + } + + sprintf(systemCmd, "echo 0 > /sys/class/gpio/gpio4/value"); + ret = system(systemCmd); + if (ret != 0) { + printf("Set gpio value failed, %d\r\n", ret); + } + + usleep(I2C_DEVICE_RESET_TIME_US); + + sprintf(systemCmd, "echo 1 > /sys/class/gpio/gpio4/value"); + ret = system(systemCmd); + if (ret != 0) { + printf("Set gpio value failed, %d\r\n", ret); + } + + sprintf(systemCmd, "echo %d > /sys/class/gpio/unexport", I2C_DEVICE_RESET_GPIO_NUM); + ret = system(systemCmd); + if (ret != 0) { + printf("Unexport reset gpio failed, %d\r\n", ret); + } +} + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.h b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.h new file mode 100644 index 0000000..1552e7f --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.h @@ -0,0 +1,55 @@ +/** + ******************************************************************** + * @file hal_i2c.h + * @brief This is the header file for "hal_i2c.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2018 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef HAL_I2C_H +#define HAL_I2C_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_platform.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define LINUX_I2C_DEV1 "/dev/i2c-1" + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode HalI2c_Init(T_DjiHalI2cConfig i2cConfig, T_DjiI2cHandle *i2cHandle); +T_DjiReturnCode HalI2c_DeInit(T_DjiI2cHandle i2cHandle); +T_DjiReturnCode HalI2c_WriteData(T_DjiI2cHandle i2cHandle, uint16_t devAddress, + const uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode HalI2c_ReadData(T_DjiI2cHandle i2cHandle, uint16_t devAddress, + uint8_t *buf, uint32_t len, uint32_t *realLen); + +#ifdef __cplusplus +} +#endif + +#endif // HAL_I2C_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_network.c b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_network.c new file mode 100644 index 0000000..7d57482 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_network.c @@ -0,0 +1,92 @@ +/** + ******************************************************************** + * @file hal_network.c + * @version V2.0.0 + * @date 3/27/20 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "string.h" +#include "stdlib.h" +#include "stdio.h" +#include "hal_network.h" +#include "dji_logger.h" + +/* Private constants ---------------------------------------------------------*/ + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNetworkHandle *halObj) +{ + int32_t ret; + char cmdStr[LINUX_CMD_STR_MAX_SIZE]; + + if (ipAddr == NULL || netMask == NULL) { + USER_LOG_ERROR("hal network config param error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + //Attention: need root permission to config ip addr and netmask. + memset(cmdStr, 0, sizeof(cmdStr)); + + snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s up", LINUX_NETWORK_DEV); + ret = system(cmdStr); + if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Can't open the network." + "Probably the program not execute with root permission." + "Please use the root permission to execute the program."); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s %s netmask %s", LINUX_NETWORK_DEV, ipAddr, netMask); + ret = system(cmdStr); + if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Can't config the ip address of network." + "Probably the program not execute with root permission." + "Please use the root permission to execute the program."); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalNetWork_DeInit(T_DjiNetworkHandle halObj) +{ + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalNetWork_GetDeviceInfo(T_DjiHalNetworkDeviceInfo *deviceInfo) +{ + deviceInfo->usbNetAdapter.vid = USB_NET_ADAPTER_VID; + deviceInfo->usbNetAdapter.pid = USB_NET_ADAPTER_PID; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_network.h b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_network.h new file mode 100644 index 0000000..6f8ea22 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_network.h @@ -0,0 +1,73 @@ +/** + ******************************************************************** + * @file hal_network.h + * @brief This is the header file for "hal_network.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef HAL_NETWORK_H +#define HAL_NETWORK_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_platform.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/** @attention User can config network card name here, if your device is not MF2C/G, please comment below and add your + * NIC name micro define as #define 'LINUX_NETWORK_DEV "your NIC name"'. + */ +#ifdef PLATFORM_ARCH_x86_64 +#define LINUX_NETWORK_DEV "enp0s31f6" +#else +#define LINUX_NETWORK_DEV "pi4br0" +#endif +/** + * @attention + */ + +#ifdef PLATFORM_ARCH_x86_64 +#define USB_NET_ADAPTER_VID (0x0B95) +#define USB_NET_ADAPTER_PID (0x1790) +#else +#define USB_NET_ADAPTER_VID (0x0955) +#define USB_NET_ADAPTER_PID (0x7020) +#endif + +#define LINUX_CMD_STR_MAX_SIZE (128) + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNetworkHandle *halObj); +T_DjiReturnCode HalNetWork_DeInit(T_DjiNetworkHandle halObj); +T_DjiReturnCode HalNetWork_GetDeviceInfo(T_DjiHalNetworkDeviceInfo *deviceInfo); + +#ifdef __cplusplus +} +#endif + +#endif // HAL_NETWORK_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_uart.c b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_uart.c new file mode 100644 index 0000000..5fae883 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_uart.c @@ -0,0 +1,272 @@ +/** + ******************************************************************** + * @file hal_uart.c + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include +#include "hal_uart.h" + +/* Private constants ---------------------------------------------------------*/ +#define UART_DEV_NAME_STR_SIZE (128) +#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64) +#define DJI_SYSTEM_RESULT_STR_MAX_SIZE (128) + +/* Private types -------------------------------------------------------------*/ +typedef struct { + int uartFd; +} T_UartHandleStruct; + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle) +{ + T_UartHandleStruct *uartHandleStruct; + struct termios options; + struct flock lock; + T_DjiReturnCode returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + char uartName[UART_DEV_NAME_STR_SIZE]; + char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE]; + char *ret = NULL; + char lineBuf[DJI_SYSTEM_RESULT_STR_MAX_SIZE] = {0}; + FILE *fp; + + uartHandleStruct = malloc(sizeof(T_UartHandleStruct)); + if (uartHandleStruct == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED; + } + + if (uartNum == DJI_HAL_UART_NUM_0) { + strcpy(uartName, LINUX_UART_DEV1); + } else if (uartNum == DJI_HAL_UART_NUM_1) { + strcpy(uartName, LINUX_UART_DEV2); + } else { + goto free_uart_handle; + } + +#ifdef USE_CLION_DEBUG + sprintf(systemCmd, "ls -l %s", uartName); + fp = popen(systemCmd, "r"); + if (fp == NULL) { + goto free_uart_handle; + } + + ret = fgets(lineBuf, sizeof(lineBuf), fp); + if (ret == NULL) { + goto close_fp; + } + + if (strstr(lineBuf, "crwxrwxrwx") == NULL) { + USER_LOG_ERROR("Can't operation the device. " + "Probably the device has not operation permission. " + "Please execute command 'sudo chmod 777 %s' to add permission. ", uartName); + goto close_fp; + } +#else + sprintf(systemCmd, "chmod 777 %s", uartName); + fp = popen(systemCmd, "r"); + if (fp == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } +#endif + + uartHandleStruct->uartFd = open(uartName, (unsigned) O_RDWR | (unsigned) O_NOCTTY | (unsigned) O_NDELAY); + if (uartHandleStruct->uartFd == -1) { + goto close_fp; + } + + // Forbid multiple psdk programs to access the serial port + lock.l_type = F_WRLCK; + lock.l_pid = getpid(); + lock.l_whence = SEEK_SET; + lock.l_start = 0; + lock.l_len = 0; + + if (fcntl(uartHandleStruct->uartFd, F_GETLK, &lock) < 0) { + goto close_uart_fd; + } + if (lock.l_type != F_UNLCK) { + goto close_uart_fd; + } + lock.l_type = F_WRLCK; + lock.l_pid = getpid(); + lock.l_whence = SEEK_SET; + lock.l_start = 0; + lock.l_len = 0; + if (fcntl(uartHandleStruct->uartFd, F_SETLKW, &lock) < 0) { + goto close_uart_fd; + } + + if (tcgetattr(uartHandleStruct->uartFd, &options) != 0) { + goto close_uart_fd; + } + + switch (baudRate) { + case 115200: + cfsetispeed(&options, B115200); + cfsetospeed(&options, B115200); + break; + case 230400: + cfsetispeed(&options, B230400); + cfsetospeed(&options, B230400); + break; + case 460800: + cfsetispeed(&options, B460800); + cfsetospeed(&options, B460800); + break; + case 921600: + cfsetispeed(&options, B921600); + cfsetospeed(&options, B921600); + break; + case 1000000: + cfsetispeed(&options, B1000000); + cfsetospeed(&options, B1000000); + break; + default: + goto close_uart_fd; + } + + options.c_cflag |= (unsigned) CLOCAL; + options.c_cflag |= (unsigned) CREAD; + options.c_cflag &= ~(unsigned) CRTSCTS; + options.c_cflag &= ~(unsigned) CSIZE; + options.c_cflag |= (unsigned) CS8; + options.c_cflag &= ~(unsigned) PARENB; + options.c_iflag &= ~(unsigned) INPCK; + options.c_cflag &= ~(unsigned) CSTOPB; + options.c_oflag &= ~(unsigned) OPOST; + options.c_lflag &= ~((unsigned) ICANON | (unsigned) ECHO | (unsigned) ECHOE | (unsigned) ISIG); + options.c_iflag &= ~((unsigned) BRKINT | (unsigned) ICRNL | (unsigned) INPCK | (unsigned) ISTRIP | (unsigned) IXON); + options.c_cc[VTIME] = 0; + options.c_cc[VMIN] = 0; + + tcflush(uartHandleStruct->uartFd, TCIFLUSH); + + if (tcsetattr(uartHandleStruct->uartFd, TCSANOW, &options) != 0) { + goto close_uart_fd; + } + + *uartHandle = uartHandleStruct; + pclose(fp); + + return returnCode; + +close_uart_fd: + close(uartHandleStruct->uartFd); + +close_fp: + pclose(fp); + +free_uart_handle: + free(uartHandleStruct); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; +} + +T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle) +{ + int32_t ret; + T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle; + + if (uartHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } + + ret = close(uartHandleStruct->uartFd); + if (ret < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + free(uartHandleStruct); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen) +{ + int32_t ret; + T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle; + + if (uartHandle == NULL || buf == NULL || len == 0 || realLen == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + ret = write(uartHandleStruct->uartFd, buf, len); + if (ret >= 0) { + *realLen = ret; + } else { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen) +{ + int32_t ret; + T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle; + + if (uartHandle == NULL || buf == NULL || len == 0 || realLen == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + ret = read(uartHandleStruct->uartFd, buf, len); + if (ret >= 0) { + *realLen = ret; + } else { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status) +{ + if (uartNum == DJI_HAL_UART_NUM_0) { + status->isConnect = true; + } else if (uartNum == DJI_HAL_UART_NUM_1) { + status->isConnect = true; + } else { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo) +{ + if (deviceInfo == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + deviceInfo->vid = USB_UART_CONNECTED_TO_UAV_VID; + deviceInfo->pid = USB_UART_CONNECTED_TO_UAV_PID; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_uart.h b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_uart.h new file mode 100644 index 0000000..d732538 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_uart.h @@ -0,0 +1,75 @@ +/** + ******************************************************************** + * @file hal_uart.h + * @brief This is the header file for "hal_uart.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef HAL_UART_H +#define HAL_UART_H + +/* Includes ------------------------------------------------------------------*/ +#include "stdint.h" +#include +#include +#include +#include +#include +#include +#include "stdlib.h" + +#include "dji_platform.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +//User can config dev based on there environmental conditions +#define LINUX_UART_DEV1 "/dev/ttyAMA1" +#define LINUX_UART_DEV2 "/dev/ttyAMA2" + +/** + * Use for Eport 2.0, specify the VID and PID of the USB serial port closest to the aircraft. + * FT232 0x0403:0x6001 + * CP2102 0x10C4:0xEA60 + * VCOM 0x2CA3:0xF002 + */ +#define USB_UART_CONNECTED_TO_UAV_VID (0x0403) +#define USB_UART_CONNECTED_TO_UAV_PID (0x6001) + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle); +T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle); +T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status); +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo); + +#ifdef __cplusplus +} +#endif + +#endif // HAL_UART_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_usb_bulk.c b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_usb_bulk.c new file mode 100644 index 0000000..33a6811 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_usb_bulk.c @@ -0,0 +1,253 @@ +/** + ******************************************************************** + * @file hal_usb_bulk.c + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "hal_usb_bulk.h" +#include "dji_logger.h" +#include + +/* Private constants ---------------------------------------------------------*/ +#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50) +#define LINUX_USB_BULK_TRANSFER_WAIT_FOREVER (-1) + +/* Private types -------------------------------------------------------------*/ +typedef struct { +#ifdef LIBUSB_INSTALLED + libusb_device_handle *handle; +#else + void *handle; +#endif + int32_t ep1; + int32_t ep2; + uint32_t interfaceNum; + T_DjiHalUsbBulkInfo usbBulkInfo; +} T_HalUsbBulkObj; + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle) +{ + int32_t ret; + struct libusb_device_handle *handle = NULL; + + *usbBulkHandle = malloc(sizeof(T_HalUsbBulkObj)); + if (*usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_init(NULL); + if (ret < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid); + if (handle == NULL) { + USER_LOG_ERROR("libusb open device error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = libusb_claim_interface(handle, usbBulkInfo.channelInfo.interfaceNum); + if (ret != LIBUSB_SUCCESS) { + USER_LOG_ERROR("libusb claim interface error"); + libusb_close(handle); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle; + memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo)); +#endif + } else { + ((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle; + memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo)); + ((T_HalUsbBulkObj *) *usbBulkHandle)->interfaceNum = usbBulkInfo.channelInfo.interfaceNum; + + if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK1_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK1_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK1_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK2_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK2_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK2_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle) +{ + struct libusb_device_handle *handle = NULL; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum); + osalHandler->TaskSleepMs(100); + libusb_exit(NULL); +#endif + } else { + close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1); + close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2); + } + + free(usbBulkHandle); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len, + uint32_t *realLen) +{ + int32_t ret; + int32_t actualLen; + struct libusb_device_handle *handle = NULL; + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut, + (uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS); + if (ret < 0) { + USER_LOG_ERROR("Write usb bulk data failed, errno = %d", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + *realLen = actualLen; +#endif + } else { + ret = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len); + if (ret < 0) { + USER_LOG_ERROR("write ret %d %d %s\n", ret, errno, strerror(errno)); + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else { + *realLen = ret; + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, + uint32_t *realLen) +{ + int32_t ret; + struct libusb_device_handle *handle = NULL; + int32_t actualLen; + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn, + buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER); + if (ret < 0) { + USER_LOG_ERROR("Read usb bulk data failed, errno = %d", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + *realLen = actualLen; +#endif + } else { + ret = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len); + if (ret < 0) { + USER_LOG_ERROR("read ret %d %d %s\n", ret, errno, strerror(errno)); + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else { + *realLen = ret; + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo) +{ + //attention: this interface only be called in usb device mode. + deviceInfo->vid = LINUX_USB_VID; + deviceInfo->pid = LINUX_USB_PID; + + // This bulk channel is used to obtain DJI camera video stream and push 3rd-party camera video stream. + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].interfaceNum = LINUX_USB_BULK1_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointIn = LINUX_USB_BULK1_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointOut = LINUX_USB_BULK1_END_POINT_OUT; + + // This bulk channel is used to obtain DJI perception image and download camera media file. + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].interfaceNum = LINUX_USB_BULK2_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT; + + // This bulk channel is used to obtain DJI perception data. + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_usb_bulk.h b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_usb_bulk.h new file mode 100644 index 0000000..8ed42a8 --- /dev/null +++ b/samples/sample_c++/platform/linux/raspberry_pi/hal/hal_usb_bulk.h @@ -0,0 +1,95 @@ +/** + ******************************************************************** + * @file hal_usb_bulk.h + * @brief This is the header file for "hal_usb_bulk.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef HAL_USB_BULK_H +#define HAL_USB_BULK_H + +/* Includes ------------------------------------------------------------------*/ +#include "stdint.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef LIBUSB_INSTALLED + +#include + +#endif + +#include "dji_platform.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define LINUX_USB_BULK1_EP_IN_FD "/dev/usb-ffs/bulk1/ep1" +#define LINUX_USB_BULK1_EP_OUT_FD "/dev/usb-ffs/bulk1/ep2" + +#define LINUX_USB_BULK1_INTERFACE_NUM (0) +#define LINUX_USB_BULK1_END_POINT_IN (0x81) +#define LINUX_USB_BULK1_END_POINT_OUT (0x01) + +#define LINUX_USB_BULK2_EP_IN_FD "/dev/usb-ffs/bulk2/ep1" +#define LINUX_USB_BULK2_EP_OUT_FD "/dev/usb-ffs/bulk2/ep2" + +#define LINUX_USB_BULK2_INTERFACE_NUM (1) +#define LINUX_USB_BULK2_END_POINT_IN (0x82) +#define LINUX_USB_BULK2_END_POINT_OUT (0x02) + +#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep1" +#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep2" + +#define LINUX_USB_BULK3_INTERFACE_NUM (2) +#define LINUX_USB_BULK3_END_POINT_IN (0x83) +#define LINUX_USB_BULK3_END_POINT_OUT (0x03) + +#define LINUX_USB_VID (0x2CA3) +#define LINUX_USB_PID (0xF001) + + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle); +T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle); +T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len, + uint32_t *realLen); +T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo); + +#ifdef __cplusplus +} +#endif + +#endif // HAL_USB_BULK_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_base.c b/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_base.c index 6605234..8a796ad 100644 --- a/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_base.c +++ b/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_base.c @@ -33,6 +33,7 @@ #include "dji_gimbal.h" #include "dji_xport.h" #include "gimbal_emu/test_payload_gimbal_emu.h" +#include /* Private constants ---------------------------------------------------------*/ #define PAYLOAD_CAMERA_EMU_TASK_FREQ (100) @@ -118,6 +119,7 @@ static T_TestCameraGimbalRotationArgument s_tapZoomNewestGimbalRotationArgument static uint32_t s_tapZoomNewestTargetHybridFocalLength = 0; // unit: 0.1mm static T_DjiMutexHandle s_tapZoomMutex = NULL; static E_DjiCameraVideoStreamType s_cameraVideoStreamType; +static uint32_t s_currentVideoRecordTimeInSeconds = 0; /* Private functions declaration ---------------------------------------------*/ static T_DjiReturnCode GetSystemState(T_DjiCameraSystemState *systemState); @@ -205,6 +207,7 @@ static T_DjiReturnCode SetMode(E_DjiCameraMode mode) s_cameraState.cameraMode = mode; USER_LOG_INFO("set camera mode:%d", mode); + DjiTest_WidgetLogAppend("set cam mode %d", mode); returnCode = osalHandler->MutexUnlock(s_commonMutex); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { @@ -235,6 +238,7 @@ static T_DjiReturnCode StartRecordVideo(void) s_cameraState.isRecording = true; USER_LOG_INFO("start record video"); + DjiTest_WidgetLogAppend("start record video"); out: djiStat = osalHandler->MutexUnlock(s_commonMutex); @@ -267,6 +271,7 @@ static T_DjiReturnCode StopRecordVideo(void) s_cameraState.isRecording = false; s_cameraState.currentVideoRecordingTimeInSeconds = 0; USER_LOG_INFO("stop record video"); + DjiTest_WidgetLogAppend("stop record video"); out: djiStat = osalHandler->MutexUnlock(s_commonMutex); @@ -290,6 +295,7 @@ static T_DjiReturnCode StartShootPhoto(void) } USER_LOG_INFO("start shoot photo"); + DjiTest_WidgetLogAppend("start shoot photo"); s_cameraState.isStoring = true; if (s_cameraShootPhotoMode == DJI_CAMERA_SHOOT_PHOTO_MODE_SINGLE) { @@ -300,6 +306,7 @@ static T_DjiReturnCode StartShootPhoto(void) s_cameraState.shootingState = DJI_CAMERA_SHOOTING_INTERVAL_PHOTO; s_cameraState.isShootingIntervalStart = true; s_cameraState.currentPhotoShootingIntervalTimeInSeconds = s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds; + s_cameraState.currentPhotoShootingIntervalTimeInMs = s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds; } returnCode = osalHandler->MutexUnlock(s_commonMutex); @@ -323,6 +330,7 @@ static T_DjiReturnCode StopShootPhoto(void) } USER_LOG_INFO("stop shoot photo"); + DjiTest_WidgetLogAppend("stop shoot photo"); s_cameraState.shootingState = DJI_CAMERA_SHOOTING_PHOTO_IDLE; s_cameraState.isStoring = false; s_cameraState.isShootingIntervalStart = false; @@ -439,8 +447,9 @@ static T_DjiReturnCode SetPhotoTimeIntervalSettings(T_DjiCameraPhotoTimeInterval s_cameraPhotoTimeIntervalSettings.captureCount = settings.captureCount; s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds = settings.timeIntervalSeconds; - USER_LOG_INFO("set photo interval settings count:%d seconds:%d", settings.captureCount, - settings.timeIntervalSeconds); + s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds = settings.timeIntervalMilliseconds; + USER_LOG_INFO("set photo interval settings count:%d seconds:%d.%d", settings.captureCount, + settings.timeIntervalSeconds, settings.timeIntervalMilliseconds / 100); s_cameraState.currentPhotoShootingIntervalCount = settings.captureCount; returnCode = osalHandler->MutexUnlock(s_commonMutex); @@ -907,7 +916,17 @@ static T_DjiReturnCode DjiTest_CameraRotationGimbal(T_TestCameraGimbalRotationAr return returnCode; } - if (aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) { + if (aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 || + aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 || + aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE || + aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) { + returnCode = DjiTest_GimbalRotate(gimbalRotationArgument.rotationMode, gimbalRotationArgument.rotationProperty, + gimbalRotationArgument.rotationValue); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("rotate gimbal error: 0x%08llX.", returnCode); + return returnCode; + } + } else if (aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) { returnCode = DjiXPort_RotateSync(gimbalRotationArgument.rotationMode, gimbalRotationArgument.rotationProperty, gimbalRotationArgument.rotationValue); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { @@ -938,6 +957,7 @@ static void *UserCamera_Task(void *arg) uint32_t currentTime = 0; bool isStartIntervalPhotoAction = false; T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + uint32_t intervalFreq = 10; USER_UTIL_UNUSED(arg); @@ -1130,8 +1150,7 @@ out: } } - // 1Hz - if (USER_UTIL_IS_WORK_TURN(step, 1, PAYLOAD_CAMERA_EMU_TASK_FREQ)) { + if (USER_UTIL_IS_WORK_TURN(step, intervalFreq, PAYLOAD_CAMERA_EMU_TASK_FREQ)) { returnCode = osalHandler->MutexLock(s_commonMutex); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("lock mutex error: 0x%08llX.", returnCode); @@ -1139,13 +1158,21 @@ out: } if (s_cameraState.isRecording) { - s_cameraState.currentVideoRecordingTimeInSeconds++; - s_cameraSDCardState.remainSpaceInMB = - s_cameraSDCardState.remainSpaceInMB - SDCARD_PER_SECONDS_RECORD_SPACE_IN_MB; - if (s_cameraSDCardState.remainSpaceInMB > SDCARD_TOTAL_SPACE_IN_MB) { - s_cameraSDCardState.remainSpaceInMB = 0; - s_cameraSDCardState.isFull = true; + uint16_t preTimeInSeconds = s_cameraState.currentVideoRecordingTimeInSeconds; + + s_currentVideoRecordTimeInSeconds++; + + s_cameraState.currentVideoRecordingTimeInSeconds = s_currentVideoRecordTimeInSeconds / intervalFreq; + if (s_cameraState.currentVideoRecordingTimeInSeconds > preTimeInSeconds) { + s_cameraSDCardState.remainSpaceInMB = + s_cameraSDCardState.remainSpaceInMB - SDCARD_PER_SECONDS_RECORD_SPACE_IN_MB; + if (s_cameraSDCardState.remainSpaceInMB > SDCARD_TOTAL_SPACE_IN_MB) { + s_cameraSDCardState.remainSpaceInMB = 0; + s_cameraSDCardState.isFull = true; + } } + } else { + s_currentVideoRecordTimeInSeconds = 0; } if (s_cameraState.isShootingIntervalStart == false) { @@ -1154,10 +1181,16 @@ out: if (s_cameraShootPhotoMode == DJI_CAMERA_SHOOT_PHOTO_MODE_INTERVAL && s_cameraState.isShootingIntervalStart == true && s_cameraPhotoTimeIntervalSettings.captureCount > 0 - && s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds > 0) { - s_cameraState.currentPhotoShootingIntervalTimeInSeconds--; + && (s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds > 0 || s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds > 0)) { + uint16_t currentPhotoShootingIntervalTimeInMs = s_cameraState.currentPhotoShootingIntervalTimeInSeconds * 1000 + + s_cameraState.currentPhotoShootingIntervalTimeInMs; - if ((s_cameraState.currentPhotoShootingIntervalTimeInSeconds == 0 && + currentPhotoShootingIntervalTimeInMs -= 1000 / intervalFreq; + + s_cameraState.currentPhotoShootingIntervalTimeInSeconds = currentPhotoShootingIntervalTimeInMs / 1000; + s_cameraState.currentPhotoShootingIntervalTimeInMs = currentPhotoShootingIntervalTimeInMs % 1000; + + if ((currentPhotoShootingIntervalTimeInMs == 0 && s_cameraState.currentPhotoShootingIntervalCount > 0) || (s_cameraState.isShootingIntervalStart == true && isStartIntervalPhotoAction == false)) { @@ -1165,13 +1198,14 @@ out: s_cameraState.shootingState = DJI_CAMERA_SHOOTING_INTERVAL_PHOTO; s_cameraState.isStoring = true; - s_cameraState.currentPhotoShootingIntervalTimeInSeconds - = s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds; + s_cameraState.currentPhotoShootingIntervalTimeInSeconds = s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds; + s_cameraState.currentPhotoShootingIntervalTimeInMs = s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds; if (s_cameraState.currentPhotoShootingIntervalCount < INTERVAL_PHOTOGRAPH_ALWAYS_COUNT) { - USER_LOG_INFO("interval taking photograph count:%d interval_time:%ds", + USER_LOG_INFO("interval taking photograph count:%d interval_time:%d.%ds", (s_cameraPhotoTimeIntervalSettings.captureCount - s_cameraState.currentPhotoShootingIntervalCount + 1), - s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds); + s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds, + s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds / 100); s_cameraState.currentPhotoShootingIntervalCount--; if (s_cameraState.currentPhotoShootingIntervalCount == 0) { s_cameraState.shootingState = DJI_CAMERA_SHOOTING_PHOTO_IDLE; @@ -1179,8 +1213,9 @@ out: s_cameraState.isShootingIntervalStart = false; } } else { - USER_LOG_INFO("interval taking photograph always, interval_time:%ds", - s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds); + USER_LOG_INFO("interval taking photograph always, interval_time:%d.%ds", + s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds, + s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds / 100); s_cameraState.currentPhotoShootingIntervalCount--; } } diff --git a/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_media.c b/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_media.c index 7982ca9..c2ea521 100644 --- a/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_media.c +++ b/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_media.c @@ -194,7 +194,8 @@ T_DjiReturnCode DjiTest_CameraEmuMediaStartService(void) UtilBuffer_Init(&s_mediaPlayCommandBufferHandler, s_mediaPlayCommandBuffer, sizeof(s_mediaPlayCommandBuffer)); if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK || - aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) { + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK || + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M400) { returnCode = DjiPayloadCamera_RegMediaDownloadPlaybackHandler(&s_psdkCameraMedia); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("psdk camera media function init error."); diff --git a/samples/sample_c/module_sample/camera_manager/test_camera_manager.c b/samples/sample_c/module_sample/camera_manager/test_camera_manager.c index 20fe47e..7356620 100644 --- a/samples/sample_c/module_sample/camera_manager/test_camera_manager.c +++ b/samples/sample_c/module_sample/camera_manager/test_camera_manager.c @@ -855,6 +855,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, || DJI_CAMERA_TYPE_M30 == cameraType || DJI_CAMERA_TYPE_M30T == cameraType || DJI_CAMERA_TYPE_M3E == cameraType || DJI_CAMERA_TYPE_M3T == cameraType || DJI_CAMERA_TYPE_M3D == cameraType || DJI_CAMERA_TYPE_M3TD == cameraType + || DJI_CAMERA_TYPE_M4T == cameraType || DJI_CAMERA_TYPE_M4TD == cameraType + || DJI_CAMERA_TYPE_H30 == cameraType || DJI_CAMERA_TYPE_H30T == cameraType || DJI_CAMERA_TYPE_M4T == cameraType || DJI_CAMERA_TYPE_M4E == cameraType || DJI_CAMERA_TYPE_H30 == cameraType || DJI_CAMERA_TYPE_H30T == cameraType || DJI_CAMERA_TYPE_M4TD == cameraType || DJI_CAMERA_TYPE_M4D == cameraType @@ -899,9 +901,10 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, || DJI_CAMERA_TYPE_M30 == cameraType || DJI_CAMERA_TYPE_M30T == cameraType || DJI_CAMERA_TYPE_M3E == cameraType || DJI_CAMERA_TYPE_M3T == cameraType || DJI_CAMERA_TYPE_M3D == cameraType || DJI_CAMERA_TYPE_M3TD == cameraType - || DJI_CAMERA_TYPE_M4T == cameraType || DJI_CAMERA_TYPE_M4E == cameraType - || DJI_CAMERA_TYPE_H30 == cameraType || DJI_CAMERA_TYPE_H30T == cameraType - || DJI_CAMERA_TYPE_M4TD == cameraType || DJI_CAMERA_TYPE_M4D == cameraType + || DJI_CAMERA_TYPE_M4T == cameraType || DJI_CAMERA_TYPE_M4TD == cameraType + || DJI_CAMERA_TYPE_M4E == cameraType || DJI_CAMERA_TYPE_H30 == cameraType + || DJI_CAMERA_TYPE_H30T == cameraType|| DJI_CAMERA_TYPE_M4TD == cameraType + || DJI_CAMERA_TYPE_M4D == cameraType ) { USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.", mountPosition); @@ -1938,7 +1941,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_M30 || cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3D || cameraType == DJI_CAMERA_TYPE_L2 || cameraType == DJI_CAMERA_TYPE_H30 || - cameraType == DJI_CAMERA_TYPE_M4T || cameraType == DJI_CAMERA_TYPE_M4TD) { + cameraType == DJI_CAMERA_TYPE_M4TD || cameraType == DJI_CAMERA_TYPE_M4D || + cameraType == DJI_CAMERA_TYPE_M4T) { USER_LOG_WARN("Camera type %s don't support FFC function.", s_cameraTypeStrList[DjiTest_CameraManagerGetCameraTypeIndex(cameraType)].cameraTypeStr); goto exitCameraModule; @@ -1985,7 +1989,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_M30 || cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3D || cameraType == DJI_CAMERA_TYPE_L2 || cameraType == DJI_CAMERA_TYPE_H30 || - cameraType == DJI_CAMERA_TYPE_M4T || cameraType == DJI_CAMERA_TYPE_M4TD) { + cameraType == DJI_CAMERA_TYPE_M4TD || cameraType == DJI_CAMERA_TYPE_M4D || + cameraType == DJI_CAMERA_TYPE_M4T) { USER_LOG_WARN("Camera type %s don't support infrared function.", s_cameraTypeStrList[DjiTest_CameraManagerGetCameraTypeIndex(cameraType)].cameraTypeStr); goto exitCameraModule; @@ -2133,6 +2138,7 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj return returnCode; } + USER_LOG_INFO("obtain downloader rights of pos %d", position); returnCode = DjiCameraManager_ObtainDownloaderRights(position); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Obtain downloader rights failed, error code: 0x%08X.", returnCode); @@ -2215,10 +2221,10 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj } if (s_meidaFileList.fileListInfo[0].type == DJI_CAMERA_FILE_TYPE_JPEG) { + USER_LOG_INFO("delete camera file of index %d", s_meidaFileList.fileListInfo[0].fileIndex); returnCode = DjiCameraManager_DeleteFileByIndex(position, s_meidaFileList.fileListInfo[0].fileIndex); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Delete media file by index failed, error code: 0x%08X.", returnCode); - return returnCode; } } @@ -2227,6 +2233,7 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj USER_LOG_WARN("Media file is not existed in sdcard.\r\n"); } +ReleaseDownloaderRights: returnCode = DjiCameraManager_ReleaseDownloaderRights(position); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Release downloader rights failed, error code: 0x%08X.", returnCode); @@ -2575,6 +2582,7 @@ T_DjiReturnCode DjiTest_CameraManagerSubscribePointCloud(E_DjiMountPosition posi uint32_t colorPointCloudDataByte = 0; uint32_t colorPointsNum = 0; static bool isMopInit = false; + E_DjiChannelAddress mopChannelAddress = 0; returnCode = DjiCameraManager_StartRecordPointCloud(position); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { @@ -2613,7 +2621,10 @@ T_DjiReturnCode DjiTest_CameraManagerSubscribePointCloud(E_DjiMountPosition posi RECONNECT: osalHandler->TaskSleepMs(TEST_CAMERA_MOP_CHANNEL_WAIT_TIME_MS); - returnCode = DjiMopChannel_Connect(s_mopChannelHandle, DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1, + mopChannelAddress = position - DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 + DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1; + USER_LOG_INFO("connect to mop channel addr %d, channel id %d", + mopChannelAddress, TEST_CAMERA_MOP_CHANNEL_SUBSCRIBE_POINT_CLOUD_CHANNEL_ID); + returnCode = DjiMopChannel_Connect(s_mopChannelHandle, mopChannelAddress, TEST_CAMERA_MOP_CHANNEL_SUBSCRIBE_POINT_CLOUD_CHANNEL_ID); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Connect point cloud mop channel error, stat:0x%08llX.", returnCode); diff --git a/samples/sample_c/module_sample/cloud_api/test_cloud_api_by_web_socket.c b/samples/sample_c/module_sample/cloud_api/test_cloud_api_by_web_socket.c new file mode 100644 index 0000000..8fe6ebb --- /dev/null +++ b/samples/sample_c/module_sample/cloud_api/test_cloud_api_by_web_socket.c @@ -0,0 +1,99 @@ +/** + ******************************************************************** + * @file test_cloud_api_by_web_socket.c + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ + +#include +#include +#include +#include "dji_cloud_api_by_websockt.h" +#include "dji_logger.h" +#include "dji_platform.h" +#include "test_cloud_api_by_web_socket.h" + +/* Private constants ---------------------------------------------------------*/ +#define TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER (64 * 1024) + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ +static T_DjiTaskHandle s_testCloudApiByWebSocketSendTask; + +/* Private functions definition-----------------------------------------------*/ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wmissing-noreturn" +#pragma GCC diagnostic ignored "-Wreturn-type" + +static void *DjiTest_CloudApiByWebSocketSendTask(void *arg) +{ + uint8_t *sendBuf = NULL; + uint32_t realLen = 0; + T_DjiReturnCode returnCode; + uint32_t sendDataCount = 0; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + USER_UTIL_UNUSED(arg); + + sendBuf = osalHandler->Malloc(TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER); + if (sendBuf == NULL) { + USER_LOG_ERROR("cloud_api over mop malloc send buffer error"); + return NULL; + } + + while (1) { + sendDataCount++; + memset(sendBuf, 'A' - 1 + (sendDataCount % 26), TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER); + returnCode = DjiCloudApi_SendDataByWebSocket(sendBuf, TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER, &realLen); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_WARN("cloud_api over mop send data to channel error,stat:0x%08llX", returnCode); + } else { + USER_LOG_INFO("cloud_api over mop send data to channel length:%d count:%d", realLen, sendDataCount); + } + + osalHandler->TaskSleepMs(1000); + } +} + +#pragma GCC diagnostic pop + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode DjiTest_CloudApiByWebSocketStartService(void) +{ + T_DjiReturnCode returnCode; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + USER_LOG_INFO("cloud_api over mop send task create error, stat:0x%08llX.", returnCode); + returnCode = osalHandler->TaskCreate("CloudApiByWebSocket", DjiTest_CloudApiByWebSocketSendTask, + 2048, NULL, &s_testCloudApiByWebSocketSendTask); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("cloud_api over mop send task create error, stat:0x%08llX.", returnCode); + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/module_sample/cloud_api/test_cloud_api_by_web_socket.h b/samples/sample_c/module_sample/cloud_api/test_cloud_api_by_web_socket.h new file mode 100644 index 0000000..a16ebc5 --- /dev/null +++ b/samples/sample_c/module_sample/cloud_api/test_cloud_api_by_web_socket.h @@ -0,0 +1,49 @@ +/** + ******************************************************************** + * @file test_mop_channel.h + * @brief This is the header file for "test_mop_channel.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef TEST_CLOUD_API_BY_WEEBSOCKET_H +#define TEST_CLOUD_API_BY_WEEBSOCKET_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode DjiTest_CloudApiByWebSocketStartService(void); + +#ifdef __cplusplus +} +#endif + +#endif // TEST_CLOUD_API_BY_WEEBSOCKET_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/module_sample/data_transmission/test_data_transmission.c b/samples/sample_c/module_sample/data_transmission/test_data_transmission.c index ea07337..29921fa 100644 --- a/samples/sample_c/module_sample/data_transmission/test_data_transmission.c +++ b/samples/sample_c/module_sample/data_transmission/test_data_transmission.c @@ -87,7 +87,7 @@ T_DjiReturnCode DjiTest_DataTransmissionStartService(void) s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T || s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3D || s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3TD || - s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M4D || + s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M4D || s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M4TD) { channelAddress = DJI_CHANNEL_ADDRESS_CLOUD_API; djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromCloud); @@ -97,7 +97,10 @@ T_DjiReturnCode DjiTest_DataTransmissionStartService(void) } } - if (s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 || + if (s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M400) { + USER_LOG_INFO("M400 is not support to use data transmition between PSDK device."); + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else if (s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 || s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2 || s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3) { channelAddress = DJI_CHANNEL_ADDRESS_EXTENSION_PORT; diff --git a/samples/sample_c/module_sample/flight_control/test_flight_control.c b/samples/sample_c/module_sample/flight_control/test_flight_control.c index c71a55e..aed9c46 100644 --- a/samples/sample_c/module_sample/flight_control/test_flight_control.c +++ b/samples/sample_c/module_sample/flight_control/test_flight_control.c @@ -99,6 +99,7 @@ static void DjiTest_FlightControlVelocityControlSample(void); static void DjiTest_FlightControlArrestFlyingSample(void); static void DjiTest_FlightControlSetGetParamSample(void); static void DjiTest_FlightControlPassiveTriggerFtsSample(void); +static void DjiTest_FlightControlSlowRotateMotorSample(void); static T_DjiReturnCode DjiTest_TriggerFtsEventCallback(void); static void DjiTest_FlightControlSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampleSelect); @@ -922,6 +923,63 @@ void DjiTest_FlightControlPassiveTriggerFtsSample(void) } } +static void DjiTest_FlightControlSlowRotateMotorSample(void) +{ + E_DjiFlightControllerElectronicSpeedControllerStatus escStatus; + + T_DjiReturnCode returnCode = 0; + + USER_LOG_INFO("Start rotating."); + returnCode = DjiFlightController_StartSlowRotateMotor(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Start slow rotate blade failed, error code is 0x%08X", returnCode); + return ; + } + + returnCode = DjiFlightController_GetElectronicSpeedControllerStatus(&escStatus); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Fail to get ESC status, error code is 0x%08X", returnCode); + } + + USER_LOG_INFO("The ESC status is: %s motor(s) in rotate mode", + escStatus == DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE ? "no" : + escStatus == DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE ? "some" : + escStatus == DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE ? "all" : "(error)"); + + for (int32_t i = 0; i < 8; i++) { + s_osalHandler->TaskSleepMs(1000); + + returnCode = DjiFlightController_GetElectronicSpeedControllerStatus(&escStatus); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Fail to get ESC status, error code is 0x%08X", returnCode); + } + + USER_LOG_INFO("The ESC status is: %s motor(s) in rotate mode", + escStatus == DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE ? "no" : + escStatus == DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE ? "some" : + escStatus == DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE ? "all" : "(error)"); + } + + USER_LOG_INFO("Stop rotating."); + returnCode = DjiFlightController_StopSlowRotateMotor(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_INFO("Stop slow rotate blade failed, error code is 0x%08X", returnCode); + return ; + } + + s_osalHandler->TaskSleepMs(1000); + + returnCode = DjiFlightController_GetElectronicSpeedControllerStatus(&escStatus); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Fail to get ESC status, error code is 0x%08X", returnCode); + } + + USER_LOG_INFO("The ESC status is: %s motor(s) in rotate mode", + escStatus == DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE ? "no" : + escStatus == DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE ? "some" : + escStatus == DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE ? "all" : "(error)"); +} + void DjiTest_FlightControlSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampleSelect) { switch (flightCtrlSampleSelect) { @@ -953,6 +1011,10 @@ void DjiTest_FlightControlSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampl DjiTest_FlightControlPassiveTriggerFtsSample(); break; } + case E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SLOW_ROTATE_BLADE: { + DjiTest_FlightControlSlowRotateMotorSample(); + break; + } default: break; } @@ -1305,6 +1367,8 @@ bool DjiTest_FlightControlGoHomeAndConfirmLanding(void) if (DJI_AIRCRAFT_TYPE_M3E == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3T == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3D == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3TD == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4T == aircraftInfoBaseInfo.aircraftType + || DJI_AIRCRAFT_TYPE_M4TD == aircraftInfoBaseInfo.aircraftType + || DJI_AIRCRAFT_TYPE_M4D == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4E == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4TD == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4D == aircraftInfoBaseInfo.aircraftType @@ -1608,4 +1672,62 @@ DjiTest_FlightControlJoystickCtrlAuthSwitchEventCallback(T_DjiFlightControllerJo return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } +static T_DjiReturnCode DjiTest_FlightControlSetFtsTrigger(E_DjiMountPosition position, char* desc) +{ + T_DjiReturnCode djiStat; + T_DjiFtsPwmEscTriggerStatus esc_status; + + djiStat = DjiFlightController_SelectFtsPwmTrigger(position); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("select fts pwm trigger E-PORT error, error code: 0x%08X", djiStat); + return djiStat; + } + + djiStat = DjiFlightController_GetFtsPwmTriggerStatus(&esc_status); + if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("get pwm trigger status error, error code: 0x%08X", djiStat); + return djiStat; + } + + if (esc_status.ESC[0].fts_select != position || esc_status.ESC[1].fts_select != position) + { + USER_LOG_ERROR("pwm trigger status incorrect"); + return djiStat; + } + + if (esc_status.ESC[0].fts_status == DJI_FLIGHT_CONTROLLER_FTS_NOT_TRIGGERD && esc_status.ESC[1].fts_status == DJI_FLIGHT_CONTROLLER_FTS_NOT_TRIGGERD) + + USER_LOG_INFO("Set fts trigger position %s success", desc); + + return djiStat; +} + +T_DjiReturnCode DjiTest_FlightControlFtsPwmTriggerSample(void) +{ + T_DjiReturnCode returnCode; + + returnCode = DjiTest_FlightControlInit(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Init flight Control sample failed,error code:0x%08llX", returnCode); + return returnCode; + } + returnCode = DjiTest_FlightControlSetFtsTrigger(DJI_MOUNT_POSITION_EXTENSION_PORT, "DJI_MOUNT_POSITION_EXTENSION_PORT"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Test select DJI_MOUNT_POSITION_EXTENSION_PORT fts pwm trigger failed"); + return returnCode; + } + returnCode = DjiTest_FlightControlSetFtsTrigger(DJI_MOUNT_POSITION_EXTENSION_LITE_PORT, "DJI_MOUNT_POSITION_EXTENSION_LITE_PORT"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Test select DJI_MOUNT_POSITION_EXTENSION_LITE_PORT fts pwm trigger failed"); + return returnCode; + } + + returnCode = DjiTest_FlightControlDeInit(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Deinit Flight Control sample failed,error code:0x%08llX", returnCode); + return returnCode; + } + return returnCode; +} + /****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/module_sample/flight_control/test_flight_control.h b/samples/sample_c/module_sample/flight_control/test_flight_control.h index f8c6ba9..26a4da2 100644 --- a/samples/sample_c/module_sample/flight_control/test_flight_control.h +++ b/samples/sample_c/module_sample/flight_control/test_flight_control.h @@ -43,6 +43,7 @@ typedef enum { E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_ARREST_FLYING, E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_GET_PARAM, E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_FTS_TRIGGER, + E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SLOW_ROTATE_BLADE, } E_DjiTestFlightCtrlSampleSelect; #pragma pack(1) @@ -59,6 +60,7 @@ typedef struct { T_DjiReturnCode DjiTest_FlightControlRunSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampleSelect); void DjiTest_FlightControlVelocityAndYawRateCtrl(const T_DjiTestFlightControlVector3f offsetDesired, float yawRate, uint32_t timeMs); +T_DjiReturnCode DjiTest_FlightControlFtsPwmTriggerSample(void); #ifdef __cplusplus } diff --git a/samples/sample_c/module_sample/gimbal_emu/test_payload_gimbal_emu.c b/samples/sample_c/module_sample/gimbal_emu/test_payload_gimbal_emu.c index fb6c7c3..28b4318 100644 --- a/samples/sample_c/module_sample/gimbal_emu/test_payload_gimbal_emu.c +++ b/samples/sample_c/module_sample/gimbal_emu/test_payload_gimbal_emu.c @@ -30,6 +30,7 @@ #include "dji_logger.h" #include "dji_platform.h" #include "utils/util_misc.h" +#include "widget_interaction_test/test_widget_interaction.h" /* Private constants ---------------------------------------------------------*/ #define PAYLOAD_GIMBAL_EMU_TASK_STACK_SIZE (2048) @@ -277,6 +278,7 @@ T_DjiReturnCode DjiTest_GimbalRotate(E_DjiGimbalRotationMode rotationMode, break; case DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE: + DjiTest_WidgetLogAppend("abs mode (%d %d %d)", rotationValue.pitch, rotationValue.roll, rotationValue.yaw); USER_LOG_INFO("gimbal absolute rotate angle: pitch %d, roll %d, yaw %d.", rotationValue.pitch, rotationValue.roll, rotationValue.yaw); USER_LOG_DEBUG("gimbal absolute rotate action time: %d.", @@ -325,6 +327,7 @@ T_DjiReturnCode DjiTest_GimbalRotate(E_DjiGimbalRotationMode rotationMode, break; case DJI_GIMBAL_ROTATION_MODE_SPEED: + DjiTest_WidgetLogAppend("speed mode (%d %d %d)", rotationValue.pitch, rotationValue.roll, rotationValue.yaw); USER_LOG_INFO("gimbal rotate speed: pitch %d, roll %d, yaw %d.", rotationValue.pitch, rotationValue.roll, rotationValue.yaw); diff --git a/samples/sample_c/module_sample/gimbal_manager/test_gimbal_manager.c b/samples/sample_c/module_sample/gimbal_manager/test_gimbal_manager.c index 4abed53..36079c1 100644 --- a/samples/sample_c/module_sample/gimbal_manager/test_gimbal_manager.c +++ b/samples/sample_c/module_sample/gimbal_manager/test_gimbal_manager.c @@ -77,6 +77,7 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition, T_DjiGimbalManagerRotation rotation; T_DjiAircraftInfoBaseInfo baseInfo; E_DjiAircraftSeries aircraftSeries; + bool gimbalAnglesSubscribedFlag = false; returnCode = DjiAircraftInfo_GetBaseInfo(&baseInfo); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { @@ -89,10 +90,17 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition, USER_LOG_INFO("Gimbal manager sample start"); DjiTest_WidgetLogAppend("Gimbal manager sample start"); - returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ, NULL); - if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("Failed to subscribe topic %d, 0x%08X", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode); - goto out; + if (DJI_AIRCRAFT_SERIES_M30 == aircraftSeries || + DJI_AIRCRAFT_SERIES_M3 == aircraftSeries || + DJI_AIRCRAFT_SERIES_M3D == aircraftSeries || + DJI_AIRCRAFT_SERIES_M4 == aircraftSeries || + DJI_AIRCRAFT_SERIES_M4D == aircraftSeries) { + returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ, NULL); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Failed to subscribe topic %d, 0x%08X", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode); + goto out; + } + gimbalAnglesSubscribedFlag = true; } USER_LOG_INFO("--> Step 1: Init gimbal manager module"); @@ -170,9 +178,12 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition, } } - returnCode = DjiFcSubscription_UnSubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES); - if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("Failed to unsubscribe topic %d, 0x%08X", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode); + if (gimbalAnglesSubscribedFlag) { + returnCode = DjiFcSubscription_UnSubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Failed to unsubscribe topic %d, 0x%08X", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode); + } + gimbalAnglesSubscribedFlag = false; } USER_LOG_INFO("--> Step 5: Deinit gimbal manager module"); diff --git a/samples/sample_c/module_sample/hms/test_hms.c b/samples/sample_c/module_sample/hms/test_hms.c index fa18191..0d07c8b 100644 --- a/samples/sample_c/module_sample/hms/test_hms.c +++ b/samples/sample_c/module_sample/hms/test_hms.c @@ -43,7 +43,11 @@ #define MAX_HMS_ERROR_LEVEL (6) #define HMS_DIR_PATH_LEN_MAX (256) +#ifdef SYSTEM_ARCH_LINUX #define DJI_CUSTOM_HMS_CODE_INJECT_ON (0) +#else +#define DJI_CUSTOM_HMS_CODE_INJECT_ON (1) +#endif /* Private types -------------------------------------------------------------*/ diff --git a/samples/sample_c/module_sample/interest_point/test_interest_point.c b/samples/sample_c/module_sample/interest_point/test_interest_point.c index b9caace..6446500 100644 --- a/samples/sample_c/module_sample/interest_point/test_interest_point.c +++ b/samples/sample_c/module_sample/interest_point/test_interest_point.c @@ -28,6 +28,7 @@ #include "dji_logger.h" #include "dji_flight_controller.h" #include "flight_control/test_flight_control.h" +#include "dji_aircraft_info.h" /* Private constants ---------------------------------------------------------*/ @@ -45,11 +46,18 @@ T_DjiReturnCode DjiTest_InterestPointRunSample(void) T_DjiInterestPointSettings interestPointSettings = {0}; T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); T_DjiFlightControllerRidInfo ridInfo = {0}; + T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo = {0}; ridInfo.latitude = 22.542812; ridInfo.longitude = 113.958902; ridInfo.altitude = 10; + returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("get aircraft base info error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + returnCode = DjiFlightController_Init(ridInfo); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Flight control init failed, errno=%lld", returnCode); @@ -74,8 +82,8 @@ T_DjiReturnCode DjiTest_InterestPointRunSample(void) osalHandler->TaskSleepMs(1000); DjiTest_FlightControlVelocityAndYawRateCtrl((T_DjiTestFlightControlVector3f) {3, 0, 0}, 0, 5000); - interestPointSettings.latitude = 22.542812; - interestPointSettings.longitude = 113.958902; + interestPointSettings.latitude = 22.57775; + interestPointSettings.longitude = 113.94265; returnCode = DjiInterestPoint_RegMissionStateCallback(DjiUser_InterestPointMissionStateCallback); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { @@ -83,25 +91,37 @@ T_DjiReturnCode DjiTest_InterestPointRunSample(void) return returnCode; } + if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400) { + interestPointSettings.payloadCameraIndex = 1; + USER_LOG_INFO("The sample try to use payload camera on position %d for poi, please make sure that DJI camera mounted on this position.", + interestPointSettings.payloadCameraIndex); + } + + USER_LOG_INFO("Start interest point circle, circumcenter(%f, %f)", interestPointSettings.latitude, interestPointSettings.longitude); returnCode = DjiInterestPoint_Start(interestPointSettings); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Point interest start failed, errno=%lld", returnCode); return returnCode; } - DjiInterestPoint_SetSpeed(5.0f); + osalHandler->TaskSleepMs(1000); + + USER_LOG_INFO("set speed to 15"); + DjiInterestPoint_SetSpeed(15.0f); for (int i = 0; i < 60; ++i) { USER_LOG_INFO("Interest point mission running %d.", i); osalHandler->TaskSleepMs(1000); } + USER_LOG_INFO("Stop interest point circle"); returnCode = DjiInterestPoint_Stop(); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Point interest stop failed, errno=%lld", returnCode); return returnCode; } + USER_LOG_INFO("Force landing"); DjiFlightController_StartForceLanding(); returnCode = DjiInterestPoint_DeInit(); @@ -122,7 +142,11 @@ T_DjiReturnCode DjiTest_InterestPointRunSample(void) /* Private functions definition-----------------------------------------------*/ static T_DjiReturnCode DjiUser_InterestPointMissionStateCallback(T_DjiInterestPointMissionState missionState) { - USER_LOG_INFO("Interest point state: %d, radius: %.2f m, speed: %.2f m/s", missionState.state, missionState.radius, + USER_LOG_INFO("Interest point state: %s, radius: %.2f m, speed: %.2f m/s", + missionState.state == DJI_INTEREST_POINT_MISSION_ACTION_STATE_NOT_STARTED ? "not started" : + missionState.state == DJI_INTEREST_POINT_MISSION_ACTION_STATE_PAUSE ? "pause" : + missionState.state == DJI_INTEREST_POINT_MISSION_ACTION_STATE_RUNNING ? "running" : "unknown", + missionState.radius, missionState.curSpeed); return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; diff --git a/samples/sample_c/module_sample/liveview/test_liveview.c b/samples/sample_c/module_sample/liveview/test_liveview.c index 7654302..39206e7 100644 --- a/samples/sample_c/module_sample/liveview/test_liveview.c +++ b/samples/sample_c/module_sample/liveview/test_liveview.c @@ -77,12 +77,13 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition) goto out; } - USER_LOG_INFO("--> Step 2: Start h264 stream of the fpv and selected payload\r\n"); + USER_LOG_INFO("--> Step 2: Start h264 stream of the fpv and default of selected payload\r\n"); DjiTest_WidgetLogAppend("--> Step 2: Start h264 stream of the fpv and selected payload\r\n"); if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M300 || aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M350 || - aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30) { + aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || + aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400) { localTime = localtime(¤tTime); sprintf(s_fpvCameraStreamFilePath, "fpv_stream_%04d%02d%02d_%02d-%02d-%02d.h264", @@ -98,7 +99,7 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition) } localTime = localtime(¤tTime); - sprintf(s_payloadCameraStreamFilePath, "payload%d_vis_stream_%04d%02d%02d_%02d-%02d-%02d.h264", + sprintf(s_payloadCameraStreamFilePath, "payload%d_default_stream_%04d%02d%02d_%02d-%02d-%02d.h264", mountPosition, localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday, localTime->tm_hour, localTime->tm_min, localTime->tm_sec); @@ -128,7 +129,8 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition) DjiTest_WidgetLogAppend("--> Step 3: Stop h264 stream of the fpv and selected payload"); if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M300 || aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M350 || - aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30) { + aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || + aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400) { returnCode = DjiLiveview_StopH264Stream(DJI_LIVEVIEW_CAMERA_POSITION_FPV, DJI_LIVEVIEW_CAMERA_SOURCE_DEFAULT); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Request to stop h264 of fpv failed, error code: 0x%08X", returnCode); @@ -143,9 +145,6 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition) goto out; } - USER_LOG_INFO("Fpv stream is saved to file: %s", s_fpvCameraStreamFilePath); - USER_LOG_INFO("Payload%d stream is saved to file: %s\r\n", mountPosition, s_payloadCameraStreamFilePath); - if (DJI_AIRCRAFT_TYPE_M3T == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3TD == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4T == aircraftInfoBaseInfo.aircraftType diff --git a/samples/sample_c/module_sample/mop_channel/test_mop_channel.c b/samples/sample_c/module_sample/mop_channel/test_mop_channel.c index 57a74f8..cc5c0aa 100644 --- a/samples/sample_c/module_sample/mop_channel/test_mop_channel.c +++ b/samples/sample_c/module_sample/mop_channel/test_mop_channel.c @@ -723,6 +723,8 @@ static void *DjiTest_MopChannelFileServiceRecvTask(void *arg) s_fileServiceContent[clientNum].uploadState = MOP_FILE_SERVICE_UPLOAD_DATA_SENDING; s_fileServiceContent[clientNum].uploadSeqNum = fileTransfor->seqNum; + USER_LOG_INFO("fileTransfor->seqNum %d", fileTransfor->seqNum); + uploadWriteLen = fwrite(&recvBuf[UTIL_OFFSETOF(T_DjiMopChannel_FileTransfor, data)], 1, fileTransfor->dataLen, uploadFile); if (uploadWriteLen < 0) { diff --git a/samples/sample_c/module_sample/positioning/test_positioning.c b/samples/sample_c/module_sample/positioning/test_positioning.c index 7050e6b..0238db6 100644 --- a/samples/sample_c/module_sample/positioning/test_positioning.c +++ b/samples/sample_c/module_sample/positioning/test_positioning.c @@ -39,11 +39,11 @@ #endif /* Private constants ---------------------------------------------------------*/ -#define POSITIONING_TASK_FREQ (1) -#define POSITIONING_TASK_STACK_SIZE (2048) +#define POSITIONING_TASK_FREQ (0.1) +#define POSITIONING_TASK_STACK_SIZE (3 * 1024) #define TEST_RTCM_FILE_PATH_STR_MAX_SIZE (64) -#define DJI_TEST_POSITIONING_EVENT_COUNT (2) +#define DJI_TEST_POSITIONING_EVENT_COUNT (1) #define DJI_TEST_TIME_INTERVAL_AMONG_EVENTS_US (200000) /* Private types -------------------------------------------------------------*/ @@ -168,22 +168,22 @@ static void *DjiTest_PositioningTask(void *arg) continue; } - USER_LOG_DEBUG("request position of target points success."); - USER_LOG_DEBUG("detail position information:"); + USER_LOG_INFO("request position of target points success."); + USER_LOG_INFO("detail position information:"); for (i = 0; i < DJI_TEST_POSITIONING_EVENT_COUNT; ++i) { - USER_LOG_DEBUG("position solution property: %d.", positionInfo[i].positionSolutionProperty); - USER_LOG_DEBUG("pitchAttitudeAngle: %d\trollAttitudeAngle: %d\tyawAttitudeAngle: %d", + USER_LOG_INFO("position solution property: %d.", positionInfo[i].positionSolutionProperty); + USER_LOG_INFO("pitchAttitudeAngle: %d\trollAttitudeAngle: %d\tyawAttitudeAngle: %d", positionInfo[i].uavAttitude.pitch, positionInfo[i].uavAttitude.roll, positionInfo[i].uavAttitude.yaw); - USER_LOG_DEBUG("northPositionOffset: %d\tearthPositionOffset: %d\tdownPositionOffset: %d", + USER_LOG_INFO("northPositionOffset: %d\tearthPositionOffset: %d\tdownPositionOffset: %d", positionInfo[i].offsetBetweenMainAntennaAndTargetPoint.x, positionInfo[i].offsetBetweenMainAntennaAndTargetPoint.y, positionInfo[i].offsetBetweenMainAntennaAndTargetPoint.z); - USER_LOG_DEBUG("longitude: %.8f\tlatitude: %.8f\theight: %.8f", + USER_LOG_INFO("longitude: %.8f\tlatitude: %.8f\theight: %.8f", positionInfo[i].targetPointPosition.longitude, positionInfo[i].targetPointPosition.latitude, positionInfo[i].targetPointPosition.height); - USER_LOG_DEBUG( + USER_LOG_INFO( "longStandardDeviation: %.8f\tlatStandardDeviation: %.8f\thgtStandardDeviation: %.8f", positionInfo[i].targetPointPositionStandardDeviation.longitude, positionInfo[i].targetPointPositionStandardDeviation.latitude, diff --git a/samples/sample_c/module_sample/power_management/test_power_management.c b/samples/sample_c/module_sample/power_management/test_power_management.c index d3b9212..3c6c524 100644 --- a/samples/sample_c/module_sample/power_management/test_power_management.c +++ b/samples/sample_c/module_sample/power_management/test_power_management.c @@ -89,7 +89,9 @@ T_DjiReturnCode DjiTest_PowerManagementStartService(void) if (baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 || baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT || - baseInfo.aircraftType == DJI_AIRCRAFT_TYPE_FC30) { + baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 || + baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE || + baseInfo.aircraftType == DJI_AIRCRAFT_TYPE_FC30) { // apply high power if (s_applyHighPowerHandler.pinInit == NULL) { USER_LOG_ERROR("apply high power pin init interface is NULL error"); @@ -113,15 +115,31 @@ T_DjiReturnCode DjiTest_PowerManagementStartService(void) return returnCode; } + if (baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 || + baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE) { + E_DjiHighPowerVoltage voltage = E_DJI_HIGH_POWER_VOLTAGE_17V; - USER_LOG_INFO("Start to apply high power."); + USER_LOG_INFO("Start to apply high power."); - returnCode = DjiPowerManagement_ApplyHighPowerSync(); - if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("apply high power error"); - return returnCode; + returnCode = DjiPowerManagement_ApplyHighPowerSyncV2(voltage); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("apply high power error"); + return returnCode; + } + USER_LOG_INFO("Success to apply high power %s.", + voltage == E_DJI_HIGH_POWER_VOLTAGE_13V6 ? "13V6" : + voltage == E_DJI_HIGH_POWER_VOLTAGE_17V ? "17V" : + voltage == E_DJI_HIGH_POWER_VOLTAGE_24V ? "24V" : "???"); + } else { + USER_LOG_INFO("Start to apply high power."); + + returnCode = DjiPowerManagement_ApplyHighPowerSync(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("apply high power error"); + return returnCode; + } + USER_LOG_INFO("Success to apply high power."); } - USER_LOG_INFO("Success to apply high power."); } // register power off notification callback function diff --git a/samples/sample_c/module_sample/tethered_battery/test_tethered_battery.c b/samples/sample_c/module_sample/tethered_battery/test_tethered_battery.c new file mode 100644 index 0000000..b99be55 --- /dev/null +++ b/samples/sample_c/module_sample/tethered_battery/test_tethered_battery.c @@ -0,0 +1,108 @@ +/** + ******************************************************************** + * @file test_tethered_battery.c + * @brief + * + * @copyright (c) 2024 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "test_tethered_battery.h" +#include "dji_logger.h" +#include "dji_tethered_battery.h" +#include "utils/util_misc.h" + +/* Private constants ---------------------------------------------------------*/ +#define TETHERED_BATTERY_TASK_STACK_SIZE (2048) +#define TETHERED_BATTERY_TETHER_LINE_MAX_LENGTH (150) + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static T_DjiTaskHandle s_tetheredBatteryTestThread; +static bool s_isTetherRetrieval = false; + +/* Private functions declaration ---------------------------------------------*/ +static void *DjiTest_TetheredBatteryTask(void *arg); + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode DjiTest_TetheredBatteryStartService(void) +{ + T_DjiReturnCode returnCode; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + returnCode = DjiTetheredBattery_Init(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Dji test tethered battery init failed, errno = 0x%08llX", returnCode); + return returnCode; + } + + returnCode = osalHandler->TaskCreate("user_tethered_battery_task", DjiTest_TetheredBatteryTask, + TETHERED_BATTERY_TASK_STACK_SIZE, NULL, + &s_tetheredBatteryTestThread); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Dji tethered battery test task create failed, errno = 0x%08llX", returnCode); + return returnCode; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +static void *DjiTest_TetheredBatteryTask(void *arg) +{ + uint32_t sysTimeMs = 0; + T_DjiReturnCode returnCode; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + T_DjiTetherLineStatus tetherLineStatus = {0}; + + USER_UTIL_UNUSED(arg); + + tetherLineStatus.usedLength = 0; + tetherLineStatus.totalLength = TETHERED_BATTERY_TETHER_LINE_MAX_LENGTH; + + while (1) { + if (tetherLineStatus.usedLength >= tetherLineStatus.totalLength) { + s_isTetherRetrieval = true; + } + + if (tetherLineStatus.usedLength <= 0.01f) { + s_isTetherRetrieval = false; + } + + if (s_isTetherRetrieval == false) { + tetherLineStatus.usedLength += 1.00f; + } else { + tetherLineStatus.usedLength -= 1.00f; + } + + returnCode = DjiTetheredBattery_PushTetherLineStatus(tetherLineStatus); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Test push tether line status error, stat = 0x%08llX", returnCode); + } + + USER_LOG_DEBUG("Push tether line status, total: %.2f, used: %.2f", tetherLineStatus.totalLength, + tetherLineStatus.usedLength); + + osalHandler->TaskSleepMs(100); + } +} + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/module_sample/tethered_battery/test_tethered_battery.h b/samples/sample_c/module_sample/tethered_battery/test_tethered_battery.h new file mode 100644 index 0000000..8fcc8b8 --- /dev/null +++ b/samples/sample_c/module_sample/tethered_battery/test_tethered_battery.h @@ -0,0 +1,49 @@ +/** + ******************************************************************** + * @file test_tethered_battery.h + * @brief This is the header file for "test_tethered_battery.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2024 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef TEST_TETHERED_BATTERY_H +#define TEST_TETHERED_BATTERY_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode DjiTest_TetheredBatteryStartService(void); + +#ifdef __cplusplus +} +#endif + +#endif // TEST_TETHERED_BATTERY_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/module_sample/time_sync/test_time_sync.c b/samples/sample_c/module_sample/time_sync/test_time_sync.c index 3c010c5..13ce68b 100644 --- a/samples/sample_c/module_sample/time_sync/test_time_sync.c +++ b/samples/sample_c/module_sample/time_sync/test_time_sync.c @@ -160,9 +160,16 @@ static void *DjiTest_TimeSyncTask(void *arg) continue; } - USER_LOG_DEBUG("current aircraft time is %04d-%02d-%02d %02d:%02d:%02d %d.", - aircraftTime.year, aircraftTime.month, aircraftTime.day, - aircraftTime.hour, aircraftTime.minute, aircraftTime.second, aircraftTime.microsecond); + if ((aircraftTime.second % 30) == 0) { + USER_LOG_INFO("current aircraft time is %04d-%02d-%02d %02d:%02d:%02d %d.", + aircraftTime.year, aircraftTime.month, aircraftTime.day, + aircraftTime.hour, aircraftTime.minute, aircraftTime.second, aircraftTime.microsecond); + } else { + USER_LOG_DEBUG("current aircraft time is %04d-%02d-%02d %02d:%02d:%02d %d.", + aircraftTime.year, aircraftTime.month, aircraftTime.day, + aircraftTime.hour, aircraftTime.minute, aircraftTime.second, aircraftTime.microsecond); + } + } } diff --git a/samples/sample_c/module_sample/utils/dji_config_manager.c b/samples/sample_c/module_sample/utils/dji_config_manager.c index 4c91ece..e72b72a 100644 --- a/samples/sample_c/module_sample/utils/dji_config_manager.c +++ b/samples/sample_c/module_sample/utils/dji_config_manager.c @@ -240,6 +240,10 @@ static T_DjiReturnCode DjiUserConfigManager_GetLinkConfigInner(const char *path, linkConfig->type = DJI_USER_LINK_CONFIG_USE_UART_AND_NETWORK_DEVICE; } else if (strcmp(jsonValue->valuestring, "use_uart_and_usb_bulk_device") == 0) { linkConfig->type = DJI_USER_LINK_CONFIG_USE_UART_AND_USB_BULK_DEVICE; + } else if (strcmp(jsonValue->valuestring, "use_only_usb_bulk_device") == 0) { + linkConfig->type = DJI_USER_LINK_CONFIG_USE_ONLY_USB_BULK_DEVICE; + } else if (strcmp(jsonValue->valuestring, "use_only_network_device") == 0) { + linkConfig->type = DJI_USER_LINK_CONFIG_USE_ONLY_NETWORK_DEVICE; } } @@ -326,6 +330,23 @@ static T_DjiReturnCode DjiUserConfigManager_GetLinkConfigInner(const char *path, jsonConfig = cJSON_GetObjectItem(jsonValue, "usb_bulk2_endpoint_out"); printf("Config usb bulk2 endpoint out: %s\r\n", jsonConfig->valuestring); linkConfig->usbBulkConfig.usbBulk2EndpointOut = configValue; + + jsonConfig = cJSON_GetObjectItem(jsonValue, "usb_bulk3_device_name"); + printf("Config usb bulk2 device name: %s\r\n", jsonConfig->valuestring); + strcpy(linkConfig->usbBulkConfig.usbBulk3DeviceName, jsonConfig->valuestring); + + jsonConfig = cJSON_GetObjectItem(jsonValue, "usb_bulk3_interface_num"); + printf("Config usb bulk2 interface num: %s\r\n", jsonConfig->valuestring); + sscanf(jsonConfig->valuestring, "%X", &configValue); + linkConfig->usbBulkConfig.usbBulk3InterfaceNum = configValue; + + jsonConfig = cJSON_GetObjectItem(jsonValue, "usb_bulk3_endpoint_in"); + printf("Config usb bulk2 endpoint in: %s\r\n", jsonConfig->valuestring); + linkConfig->usbBulkConfig.usbBulk3EndpointIn = configValue; + + jsonConfig = cJSON_GetObjectItem(jsonValue, "usb_bulk3_endpoint_out"); + printf("Config usb bulk2 endpoint out: %s\r\n", jsonConfig->valuestring); + linkConfig->usbBulkConfig.usbBulk3EndpointOut = configValue; } } diff --git a/samples/sample_c/module_sample/utils/dji_config_manager.h b/samples/sample_c/module_sample/utils/dji_config_manager.h index 8dd3ec4..dc24e72 100644 --- a/samples/sample_c/module_sample/utils/dji_config_manager.h +++ b/samples/sample_c/module_sample/utils/dji_config_manager.h @@ -43,6 +43,8 @@ typedef enum { DJI_USER_LINK_CONFIG_USE_ONLY_UART, DJI_USER_LINK_CONFIG_USE_UART_AND_NETWORK_DEVICE, DJI_USER_LINK_CONFIG_USE_UART_AND_USB_BULK_DEVICE, + DJI_USER_LINK_CONFIG_USE_ONLY_USB_BULK_DEVICE, + DJI_USER_LINK_CONFIG_USE_ONLY_NETWORK_DEVICE, } E_DjiUserLinkConfigType; typedef struct { @@ -72,6 +74,10 @@ typedef struct { uint8_t usbBulk2EndpointIn; uint8_t usbBulk2EndpointOut; + char usbBulk3DeviceName[USER_DEVICE_NAME_STR_MAX_SIZE]; + uint8_t usbBulk3InterfaceNum; + uint8_t usbBulk3EndpointIn; + uint8_t usbBulk3EndpointOut; } usbBulkConfig; } T_DjiUserLinkConfig; diff --git a/samples/sample_c/module_sample/widget/test_widget.c b/samples/sample_c/module_sample/widget/test_widget.c index f51895a..4457e34 100644 --- a/samples/sample_c/module_sample/widget/test_widget.c +++ b/samples/sample_c/module_sample/widget/test_widget.c @@ -104,6 +104,7 @@ T_DjiReturnCode DjiTest_WidgetStartService(void) } //set default ui config path + USER_LOG_INFO("widget file: %s", tempPath); djiStat = DjiWidget_RegDefaultUiConfigByDirPath(tempPath); if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Add default widget ui config error, stat = 0x%08llX", djiStat); diff --git a/samples/sample_c/module_sample/widget/test_widget_speaker.c b/samples/sample_c/module_sample/widget/test_widget_speaker.c index 940ef5b..a4812f1 100644 --- a/samples/sample_c/module_sample/widget/test_widget_speaker.c +++ b/samples/sample_c/module_sample/widget/test_widget_speaker.c @@ -324,6 +324,8 @@ static T_DjiReturnCode DjiTest_PlayTtsData(void) if (DJI_AIRCRAFT_TYPE_M3E == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3T == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3D == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3TD == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4T == aircraftInfoBaseInfo.aircraftType + || DJI_AIRCRAFT_TYPE_M4TD == aircraftInfoBaseInfo.aircraftType + || DJI_AIRCRAFT_TYPE_M4D == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4E == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4TD == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M4D == aircraftInfoBaseInfo.aircraftType diff --git a/samples/sample_c/module_sample/widget/widget_file/cn_big_screen/widget_config.json b/samples/sample_c/module_sample/widget/widget_file/cn_big_screen/widget_config.json index da4ad2e..5110179 100644 --- a/samples/sample_c/module_sample/widget/widget_file/cn_big_screen/widget_config.json +++ b/samples/sample_c/module_sample/widget/widget_file/cn_big_screen/widget_config.json @@ -1,148 +1,612 @@ { - "version": { - "major": 1, - "minor": 0 - }, - "main_interface": { - "floating_window": { - "is_enable": true + "version": { + "major": 1, + "minor": 0 }, - "speaker": { - "is_enable_tts": true, - "is_enable_voice": true - }, - "widget_list": [ - { - "widget_index": 0, - "widget_type": "button", - "widget_name": "按钮", - "icon_file_set": { - "icon_file_name_selected": "icon_button1.png", - "icon_file_name_unselected": "icon_button1.png" - }, - "customize_rc_buttons_config": { - "is_enable": true, - "mapping_config_display_order": 0 - } - }, - { - "widget_index": 1, - "widget_type": "list", - "widget_name": "列表", - "list_item": [ - { - "item_name": "选项_1", - "icon_file_set": { - "icon_file_name_selected": "icon_list_item1.png", - "icon_file_name_unselected": "icon_list_item1.png" + "ar_config": { + "circleStyleList": [ + { + "face": { + "bottom": { + "backColor": -256, + "faceColor": -65536 + }, + "distAlpha": { + "maxAlpha": 0.4, + "maxDist": 100, + "minAlpha": 0, + "minDist": 50 + }, + "side": { + "backColor": -256, + "faceColor": -65536 + }, + "top": { + "backColor": -256, + "faceColor": -65536 + } + }, + "stroke": { + "bottom": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "side": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "top": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + } + }, + "styleId": 10 + }, + { + "face": { + "bottom": { + "backColor": -256, + "faceColor": -65536 + }, + "distAlpha": { + "maxAlpha": 0.4, + "maxDist": 100, + "minAlpha": 0, + "minDist": 50 + }, + "side": { + "backColor": -256, + "faceColor": -65536 + }, + "top": { + "backColor": -256, + "faceColor": -65536 + } + }, + "stroke": { + "bottom": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "side": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "top": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + } + }, + "styleId": 11 } - }, - { - "item_name": "选项_2", - "icon_file_set": { - "icon_file_name_selected": "icon_list_item2.png", - "icon_file_name_unselected": "icon_list_item2.png" + ], + "commonPointStyleList": [ + { + "alwaysInEdge": false, + "arTextAttribute": { + "color": -65536 + }, + "isIgnoreBorder": true, + "styleId": 10 + }, + { + "alwaysInEdge": false, + "arTextAttribute": { + "color": -65536 + }, + "isIgnoreBorder": true, + "styleId": 11 } - } ], - "customize_rc_buttons_config": { - "is_enable": true, - "mapping_config_display_order": 1 - } - }, - { - "widget_index": 2, - "widget_type": "switch", - "widget_name": "开关", - "icon_file_set": { - "icon_file_name_selected": "icon_switch_select.png", - "icon_file_name_unselected": "icon_switch_unselect.png" - }, - "customize_rc_buttons_config": { - "is_enable": true, - "mapping_config_display_order": 2 - } - }, - { - "widget_index": 3, - "widget_type": "scale", - "widget_name": "范围条", - "icon_file_set": { - "icon_file_name_selected": "icon_scale.png", - "icon_file_name_unselected": "icon_scale.png" - }, - "customize_rc_buttons_config": { - "is_enable": true, - "mapping_config_display_order": 3, - "button_value_step_length": 5 - } - } - ] - }, - "config_interface": { - "text_input_box": { - "widget_name": "文本输入框", - "placeholder_text": "请输入消息", - "is_enable": true + "lineStyleList": [ + { + "color": -256, + "stokeInfo": { + "color": -65536, + "dash": false, + "width": { + "maxStrokeWidth": 2, + "maxWidthDist": 2, + "minStrokeWidth": 2, + "minWidthDist": 2 + } + }, + "styleId": 10, + "useDepth": false + }, + { + "color": -256, + "stokeInfo": { + "color": -65536, + "dash": false, + "width": { + "maxStrokeWidth": 2, + "maxWidthDist": 2, + "minStrokeWidth": 2, + "minWidthDist": 2 + } + }, + "styleId": 11, + "useDepth": false + } + ], + "pointStyleList": [ + { + "keyName": 0, + "pointConfig": { + "arrowConfig": { + "customIcon": false, + "defaultDeg": 0, + "img": "", + "imgHeight": 0, + "imgWidth": 0, + "showMode": 0, + "translate": 0, + "type": 0 + }, + "needFont": true, + "needOrthographic": true, + "needPerspective": false, + "oConfig": { + "displayHeight": 20.0, + "displayWidth": 20.0, + "img": "\n \n \n \n\n", + "imgHeight": 20.0, + "imgWidth": 20.0 + }, + "pConfig": { + "maxSVG": "", + "maxSize": 0, + "minSVG": "", + "minSize": 0, + "realSize": 0, + "strokeWidthRadio": 0 + }, + "textConfig": { + "backgroundColor": 1427379220, + "cornerRadius": 5, + "paddingB": 5, + "paddingL": 10, + "paddingR": 10, + "paddingT": 5, + "shadow": false, + "textGravity": 1, + "textSize": 20 + } + } + }, + { + "keyName": 1, + "pointConfig": { + "arrowConfig": { + "customIcon": false, + "defaultDeg": 0, + "img": "", + "imgHeight": 0, + "imgWidth": 0, + "showMode": 0, + "translate": 0, + "type": 0 + }, + "needFont": true, + "needOrthographic": true, + "needPerspective": false, + "oConfig": { + "displayHeight": 20.0, + "displayWidth": 20.0, + "img": "\n \n \n \n\n", + "imgHeight": 20.0, + "imgWidth": 20.0 + }, + "pConfig": { + "maxSVG": "", + "maxSize": 0, + "minSVG": "", + "minSize": 0, + "realSize": 0, + "strokeWidthRadio": 0 + }, + "textConfig": { + "backgroundColor": 1427379220, + "cornerRadius": 5, + "paddingB": 5, + "paddingL": 10, + "paddingR": 10, + "paddingT": 5, + "shadow": false, + "textGravity": 1, + "textSize": 20 + } + } + } + ], + "polygonStyleList": [ + { + "face": { + "bottom": { + "backColor": -256, + "faceColor": -65536 + }, + "distAlpha": { + "maxAlpha": 0.4, + "maxDist": 100, + "minAlpha": 0, + "minDist": 50 + }, + "side": { + "backColor": -256, + "faceColor": -65536 + }, + "top": { + "backColor": -256, + "faceColor": -65536 + } + }, + "is3DMesh": false, + "stroke": { + "bottom": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "side": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "top": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + } + }, + "styleId": 10 + }, + { + "face": { + "bottom": { + "backColor": -256, + "faceColor": -65536 + }, + "distAlpha": { + "maxAlpha": 0.4, + "maxDist": 100, + "minAlpha": 0, + "minDist": 50 + }, + "side": { + "backColor": -256, + "faceColor": -65536 + }, + "top": { + "backColor": -256, + "faceColor": -65536 + } + }, + "is3DMesh": false, + "stroke": { + "bottom": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "side": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "top": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + } + }, + "styleId": 11 + } + ] }, - "widget_list": [ - { - "widget_index": 4, - "widget_type": "button", - "widget_name": "按钮 4", - "customize_rc_buttons_config": { - "is_enable": true, - "mapping_config_display_order": 4 - } - }, - { - "widget_index": 5, - "widget_type": "scale", - "widget_name": "范围条 5", - "customize_rc_buttons_config": { - "is_enable": true, - "mapping_config_display_order": 5, - "button_value_step_length": 5 - } - }, - { - "widget_index": 6, - "widget_type": "int_input_box", - "widget_name": "整形值输入框 6", - "int_input_box_hint": "unit:s" - }, - { - "widget_index": 7, - "widget_type": "switch", - "widget_name": "开关 7", - "customize_rc_buttons_config": { - "is_enable": true, - "mapping_config_display_order": 7 - } - }, - { - "widget_index": 8, - "widget_type": "list", - "widget_name": "列表 8", - "list_item": [ - { - "item_name": "选项 1" - }, - { - "item_name": "选项 2" - }, - { - "item_name": "选项 3" - }, - { - "item_name": "选项 4" - } - ], - "customize_rc_buttons_config": { - "is_enable": true, - "mapping_config_display_order": 8 - } - } - ] - } -} + "main_interface": { + "floating_window": { + "is_enable": true + }, + "speaker": { + "is_enable_tts": true, + "is_enable_voice": true + }, + "widget_list": [ + { + "widget_index": 0, + "widget_type": "button", + "widget_name": "按钮", + "icon_file_set": { + "icon_file_name_selected": "icon_button1.png", + "icon_file_name_unselected": "icon_button1.png" + }, + "customize_rc_buttons_config": { + "is_enable": true, + "mapping_config_display_order": 0 + } + }, + { + "widget_index": 1, + "widget_type": "list", + "widget_name": "列表", + "list_item": [ + { + "item_name": "选项_1", + "icon_file_set": { + "icon_file_name_selected": "icon_list_item1.png", + "icon_file_name_unselected": "icon_list_item1.png" + } + }, + { + "item_name": "选项_2", + "icon_file_set": { + "icon_file_name_selected": "icon_list_item2.png", + "icon_file_name_unselected": "icon_list_item2.png" + } + } + ], + "customize_rc_buttons_config": { + "is_enable": true, + "mapping_config_display_order": 1 + } + }, + { + "widget_index": 2, + "widget_type": "switch", + "widget_name": "开关", + "icon_file_set": { + "icon_file_name_selected": "icon_switch_select.png", + "icon_file_name_unselected": "icon_switch_unselect.png" + }, + "customize_rc_buttons_config": { + "is_enable": true, + "mapping_config_display_order": 2 + } + }, + { + "widget_index": 3, + "widget_type": "scale", + "widget_name": "范围条", + "icon_file_set": { + "icon_file_name_selected": "icon_scale.png", + "icon_file_name_unselected": "icon_scale.png" + }, + "customize_rc_buttons_config": { + "is_enable": true, + "mapping_config_display_order": 3, + "button_value_step_length": 5 + } + } + ] + }, + "config_interface": { + "text_input_box": { + "widget_name": "文本输入框", + "placeholder_text": "请输入消息", + "is_enable": true + }, + "widget_list": [ + { + "widget_index": 4, + "widget_type": "button", + "widget_name": "按钮 4", + "customize_rc_buttons_config": { + "is_enable": true, + "mapping_config_display_order": 4 + } + }, + { + "widget_index": 5, + "widget_type": "scale", + "widget_name": "范围条 5", + "customize_rc_buttons_config": { + "is_enable": true, + "mapping_config_display_order": 5, + "button_value_step_length": 5 + } + }, + { + "widget_index": 6, + "widget_type": "int_input_box", + "widget_name": "整形值输入框 6", + "int_input_box_hint": "unit:s" + }, + { + "widget_index": 7, + "widget_type": "switch", + "widget_name": "开关 7", + "customize_rc_buttons_config": { + "is_enable": true, + "mapping_config_display_order": 7 + } + }, + { + "widget_index": 8, + "widget_type": "list", + "widget_name": "列表 8", + "list_item": [ + { + "item_name": "选项 1" + }, + { + "item_name": "选项 2" + }, + { + "item_name": "选项 3" + }, + { + "item_name": "选项 4" + } + ], + "customize_rc_buttons_config": { + "is_enable": true, + "mapping_config_display_order": 8 + } + } + ] + } +} \ No newline at end of file diff --git a/samples/sample_c/module_sample/widget/widget_file/en_big_screen/widget_config.json b/samples/sample_c/module_sample/widget/widget_file/en_big_screen/widget_config.json index ff8cf68..60f5874 100644 --- a/samples/sample_c/module_sample/widget/widget_file/en_big_screen/widget_config.json +++ b/samples/sample_c/module_sample/widget/widget_file/en_big_screen/widget_config.json @@ -3,6 +3,470 @@ "major": 1, "minor": 0 }, + "ar_config": { + "circleStyleList": [ + { + "face": { + "bottom": { + "backColor": -256, + "faceColor": -65536 + }, + "distAlpha": { + "maxAlpha": 0.4, + "maxDist": 100, + "minAlpha": 0, + "minDist": 50 + }, + "side": { + "backColor": -256, + "faceColor": -65536 + }, + "top": { + "backColor": -256, + "faceColor": -65536 + } + }, + "stroke": { + "bottom": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "side": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "top": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + } + }, + "styleId": 10 + }, + { + "face": { + "bottom": { + "backColor": -256, + "faceColor": -65536 + }, + "distAlpha": { + "maxAlpha": 0.4, + "maxDist": 100, + "minAlpha": 0, + "minDist": 50 + }, + "side": { + "backColor": -256, + "faceColor": -65536 + }, + "top": { + "backColor": -256, + "faceColor": -65536 + } + }, + "stroke": { + "bottom": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "side": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "top": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + } + }, + "styleId": 11 + } + ], + "commonPointStyleList": [ + { + "alwaysInEdge": false, + "arTextAttribute": { + "color": -65536 + }, + "isIgnoreBorder": true, + "styleId": 10 + }, + { + "alwaysInEdge": false, + "arTextAttribute": { + "color": -65536 + }, + "isIgnoreBorder": true, + "styleId": 11 + } + ], + "lineStyleList": [ + { + "color": -256, + "stokeInfo": { + "color": -65536, + "dash": false, + "width": { + "maxStrokeWidth": 2, + "maxWidthDist": 2, + "minStrokeWidth": 2, + "minWidthDist": 2 + } + }, + "styleId": 10, + "useDepth": false + }, + { + "color": -256, + "stokeInfo": { + "color": -65536, + "dash": false, + "width": { + "maxStrokeWidth": 2, + "maxWidthDist": 2, + "minStrokeWidth": 2, + "minWidthDist": 2 + } + }, + "styleId": 11, + "useDepth": false + } + ], + "pointStyleList": [ + { + "keyName": 0, + "pointConfig": { + "arrowConfig": { + "customIcon": false, + "defaultDeg": 0, + "img": "", + "imgHeight": 0, + "imgWidth": 0, + "showMode": 0, + "translate": 0, + "type": 0 + }, + "needFont": true, + "needOrthographic": true, + "needPerspective": false, + "oConfig": { + "displayHeight": 20.0, + "displayWidth": 20.0, + "img": "\n \n \n \n\n", + "imgHeight": 20.0, + "imgWidth": 20.0 + }, + "pConfig": { + "maxSVG": "", + "maxSize": 0, + "minSVG": "", + "minSize": 0, + "realSize": 0, + "strokeWidthRadio": 0 + }, + "textConfig": { + "backgroundColor": 1427379220, + "cornerRadius": 5, + "paddingB": 5, + "paddingL": 10, + "paddingR": 10, + "paddingT": 5, + "shadow": false, + "textGravity": 1, + "textSize": 20 + } + } + }, + { + "keyName": 1, + "pointConfig": { + "arrowConfig": { + "customIcon": false, + "defaultDeg": 0, + "img": "", + "imgHeight": 0, + "imgWidth": 0, + "showMode": 0, + "translate": 0, + "type": 0 + }, + "needFont": true, + "needOrthographic": true, + "needPerspective": false, + "oConfig": { + "displayHeight": 20.0, + "displayWidth": 20.0, + "img": "\n \n \n \n\n", + "imgHeight": 20.0, + "imgWidth": 20.0 + }, + "pConfig": { + "maxSVG": "", + "maxSize": 0, + "minSVG": "", + "minSize": 0, + "realSize": 0, + "strokeWidthRadio": 0 + }, + "textConfig": { + "backgroundColor": 1427379220, + "cornerRadius": 5, + "paddingB": 5, + "paddingL": 10, + "paddingR": 10, + "paddingT": 5, + "shadow": false, + "textGravity": 1, + "textSize": 20 + } + } + } + ], + "polygonStyleList": [ + { + "face": { + "bottom": { + "backColor": -256, + "faceColor": -65536 + }, + "distAlpha": { + "maxAlpha": 0.4, + "maxDist": 100, + "minAlpha": 0, + "minDist": 50 + }, + "side": { + "backColor": -256, + "faceColor": -65536 + }, + "top": { + "backColor": -256, + "faceColor": -65536 + } + }, + "is3DMesh": false, + "stroke": { + "bottom": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "side": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "top": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + } + }, + "styleId": 10 + }, + { + "face": { + "bottom": { + "backColor": -256, + "faceColor": -65536 + }, + "distAlpha": { + "maxAlpha": 0.4, + "maxDist": 100, + "minAlpha": 0, + "minDist": 50 + }, + "side": { + "backColor": -256, + "faceColor": -65536 + }, + "top": { + "backColor": -256, + "faceColor": -65536 + } + }, + "is3DMesh": false, + "stroke": { + "bottom": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "side": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + }, + "top": { + "distAlpha": { + "maxAlpha": 0.6, + "maxDist": 100, + "minAlpha": 1, + "minDist": 50 + }, + "strokeInfo": { + "color": -65536, + "dash": true, + "width": { + "maxStrokeWidth": 20, + "maxWidthDist": 20, + "minStrokeWidth": 2.5, + "minWidthDist": 100 + } + } + } + }, + "styleId": 11 + } + ] + }, "main_interface": { "floating_window": { "is_enable": true diff --git a/samples/sample_c/module_sample/widget_interaction_test/test_widget_interaction.c b/samples/sample_c/module_sample/widget_interaction_test/test_widget_interaction.c index e4214db..279c315 100644 --- a/samples/sample_c/module_sample/widget_interaction_test/test_widget_interaction.c +++ b/samples/sample_c/module_sample/widget_interaction_test/test_widget_interaction.c @@ -228,7 +228,9 @@ T_DjiReturnCode DjiTest_WidgetInteractionStartService(void) snprintf(tempPath, WIDGET_DIR_PATH_LEN_MAX, "%swidget_file/en_big_screen", curFileDirPath); } + USER_LOG_ERROR("Dji test widget set path"); //set default ui config path + USER_LOG_INFO("widget file: %s", tempPath); djiStat = DjiWidget_RegDefaultUiConfigByDirPath(tempPath); if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Add default widget ui config error, stat = 0x%08llX", djiStat); @@ -463,7 +465,9 @@ static void *DjiTest_WidgetInteractionTask(void *arg) DjiTest_WidgetLogAppend("-> Sample Start"); if (s_aircraftInfoBaseInfo.mountPositionType == DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT || - s_aircraftInfoBaseInfo.mountPositionType == DJI_MOUNT_POSITION_TYPE_EXTENSION_LITE_PORT) { + s_aircraftInfoBaseInfo.mountPositionType == DJI_MOUNT_POSITION_TYPE_EXTENSION_LITE_PORT || + s_aircraftInfoBaseInfo.mountPositionType == DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD || + s_aircraftInfoBaseInfo.mountPositionType == DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT_V2) { switch (s_extensionPortSampleIndex) { case E_DJI_SAMPLE_INDEX_WAYPOINT_V2: if (s_isallowRunFlightControlSample == true) { diff --git a/samples/sample_c/platform/linux/common/osal/osal_fs.c b/samples/sample_c/platform/linux/common/osal/osal_fs.c index c2d15e7..f9474c5 100644 --- a/samples/sample_c/platform/linux/common/osal/osal_fs.c +++ b/samples/sample_c/platform/linux/common/osal/osal_fs.c @@ -48,15 +48,10 @@ T_DjiReturnCode Osal_FileOpen(const char *fileName, const char *fileMode, T_DjiF *fileObj = fopen(fileName, fileMode); if (*fileObj == NULL) { - goto out; + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; - -out: - free(*fileObj); - - return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } T_DjiReturnCode Osal_FileClose(T_DjiFileHandle fileObj) diff --git a/samples/sample_c/platform/linux/manifold2/CMakeLists.txt b/samples/sample_c/platform/linux/manifold2/CMakeLists.txt index 3941dcf..3622679 100644 --- a/samples/sample_c/platform/linux/manifold2/CMakeLists.txt +++ b/samples/sample_c/platform/linux/manifold2/CMakeLists.txt @@ -82,7 +82,7 @@ else () message(STATUS "Cannot Find LIBUSB") endif (LIBUSB_FOUND) -target_link_libraries(${PROJECT_NAME} m) +target_link_libraries(${PROJECT_NAME} m dl) add_custom_command(TARGET ${PROJECT_NAME} PRE_LINK COMMAND cmake .. diff --git a/samples/sample_c/platform/linux/manifold3/CMakeLists.txt b/samples/sample_c/platform/linux/manifold3/CMakeLists.txt new file mode 100644 index 0000000..0416a27 --- /dev/null +++ b/samples/sample_c/platform/linux/manifold3/CMakeLists.txt @@ -0,0 +1,70 @@ +cmake_minimum_required(VERSION 3.5) +project(dji_sdk_demo_on_manifold3 C) + +set(CMAKE_C_FLAGS "-pthread -std=gnu99") +set(CMAKE_CXX_FLAGS "-std=c++11 -pthread") +set(CMAKE_EXE_LINKER_FLAGS "-pthread") +set(CMAKE_C_COMPILER "aarch64-linux-gnu-gcc") +set(CMAKE_CXX_COMPILER "aarch64-linux-gnu-g++") +add_definitions(-D_GNU_SOURCE) + +if (NOT USE_SYSTEM_ARCH) + add_definitions(-DSYSTEM_ARCH_LINUX) +endif () + +if (BUILD_TEST_CASES_ON MATCHES TRUE) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fprofile-arcs -ftest-coverage") + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage") + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fprofile-arcs -ftest-coverage -lgcov") +endif () + +set(PACKAGE_NAME payloadsdk) + +set(TOOLCHAIN_NAME aarch64-linux-gnu-gcc) +add_definitions(-DPLATFORM_ARCH_aarch64=1) + +file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c) +file(GLOB_RECURSE MODULE_HAL_SRC hal/*.c) +file(GLOB_RECURSE MODULE_APP_SRC application/*.c) +file(GLOB_RECURSE MODULE_SAMPLE_SRC ../../../module_sample/*.c) + +include_directories(../../../module_sample) +include_directories(../common) +include_directories(application) + +include_directories(../../../../../psdk_lib/include) +link_directories(../../../../../psdk_lib/lib/${TOOLCHAIN_NAME}) +link_libraries(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME}/lib${PACKAGE_NAME}.a) + +if (NOT EXECUTABLE_OUTPUT_PATH) + set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin) +endif () + +add_executable(${PROJECT_NAME} + ${MODULE_APP_SRC} + ${MODULE_SAMPLE_SRC} + ${MODULE_COMMON_SRC} + ${MODULE_HAL_SRC}) + +set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../common/3rdparty) + +target_link_libraries(${PROJECT_NAME} m dl) + +add_custom_command(TARGET ${PROJECT_NAME} + PRE_LINK COMMAND cmake .. + WORKING_DIRECTORY ${CMAKE_BINARY_DIR}) + +# set app.json and build_dpk.sh path +set(JSON_FILE ${CMAKE_CURRENT_SOURCE_DIR}/app_json/app.json) +set(SCRIPT_FILE ${CMAKE_CURRENT_SOURCE_DIR}/../../../../../tools/build_dpk/build_dpk.sh) + +# set psdk_libput dpk path +set(OUTPUT_PACKAGE ${CMAKE_BINARY_DIR}/dpk) + +# generate .dpk app package +add_custom_command(TARGET ${PROJECT_NAME} + POST_BUILD # generate .dpk package after make + COMMAND bash ${SCRIPT_FILE} -i ${JSON_FILE} -o ${OUTPUT_PACKAGE} + DEPENDS ${JSON_FILE} + COMMENT "Running build_dpk.sh, generating .dpk app package from app.json file" +) diff --git a/samples/sample_c/platform/linux/manifold3/app_json/README.md b/samples/sample_c/platform/linux/manifold3/app_json/README.md new file mode 100644 index 0000000..eab7113 --- /dev/null +++ b/samples/sample_c/platform/linux/manifold3/app_json/README.md @@ -0,0 +1,211 @@ +# app.json 1.1 + +app.json is a necessary application configuration file for generating the .dpk application installation packgae. + +# app.json filling specification: + +## Documentation +please visit Related URL, to be filled in, please refer to the following description. + +Description of the tags in the app.json configuration file: + +## user_app_id + * Description: + The APP ID generated by the developer website's user center is the unique identifier for the application. + It is used to ensure the uniqueness of the application, and it must match the generated APP ID. + It must be consistent with the USER_APP_ID in the code (39 line in samples/sample_c/platform/linux/manifold3/application/dji_sdk_app_info.h or 39 line in samples/sample_c++/platform/linux/manifold3/application/dji_sdk_app_info.h), otherwise, the application cannot be installed. + * Data type: + String + * Whether the field is optional? + No, this field is required + +## firmware_version + * Description: + App version, used for displaying application version information to users. + It consists only of numbers and dots, following the four-segment format xx.xx.xx.xx, where each segment can range from 0 to 99. + The firmware_version need to update when app update and it must match the firmwareVersion in the code(99 line in samples/sample_c/platform/linux/manifold3/application/main.c or 183 line in samples/sample_c++/platform/linux/manifold3/application/application.cpp). otherwise, the application cannot be installed. + * Data type: + String + * Whether the field is optional? + No, this field is required + +## is_ai_rendering + * Description: + Indicates whether the application uses AI rendering on the pilot. + If it does, fill in true; if not, fill in false. + If left blank, the default value is true. + * Data type: + string + * Whether the field is optional? + Yes, when the field is optional, its value is the default value, which is true + +## platform + * Description: + Indicates the operating platform of the application. Supported values are: + * manifold3, which means the application will run on the manifold3 device. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## name_cn + * Description: + Indicates the Chinese name of the application, which can be customized and should be a string not exceeding 47 bytes in length. + It is recommended that the application name has a connection to its functionality, and you should try to avoid duplication with other application names. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to Chinese, this field will display the application name. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## name_en + * Description: + Indicates the English name of the application, which can be customized. The filling rules are as follows: + * Maximum length limit is 32 bytes. + * Only allow letters(a-zA-Z), numbers(0-9), hyphens(-), and dots(.), no other characters are permitted, and it must begin with a letter or number. + It is recommended that the application name has a connection to its functionality, and you should try to avoid duplication with other application names. + It is advisable to avoid changing the application name afterward. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to English, or other languages that are not Chinese, Japanese, or French. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## name_jp + * Description: + Indicates the Japanese name of the application, which should be a string not exceeding 47 bytes in length. + It is recommended that the name is relevant to the functionality and that you try to avoid duplication with other application names. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to Japanese, this field will display the application name. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## name_fr + * Description: + Indicates the French name of the application, which should be a string not exceeding 47 bytes in length. + It is recommended that the name is relevant to the functionality and that you try to avoid duplication with other application names. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to French, this field will display the application name. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## description_cn + * Description: + Indicates the Chinese description of the application, which should be a string not exceeding 367 bytes in length, containing a detailed custom description of the application. + The specific filling rules are as follows: + * Each item within the brackets [] represents the content of each line, with the next item representing the content of the next line. If a line break is needed, multiple items can be filled in within the brackets []. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to Chinese, this field will display the application description. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## description_en + * Description: + Indicates the English description of the application, which should be a string not exceeding 367 bytes in length, containing a detailed custom description of the application. + The specific filling rules are as follows: + * Each item within the brackets [] represents the content of each line, with the next item representing the content of the next line. If a line break is needed, multiple items can be filled in within the brackets []. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to English, or other languages that are not Chinese, Japanese, or French, this field will display the application description. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## description_jp + * Description: + Indicates the Japanese description of the application, which should be a string not exceeding 367 bytes in length, containing a detailed custom description of the application. + The specific filling rules are as follows: + * Each item within the brackets [] represents the content of each line, with the next item representing the content of the next line. If a line break is needed, multiple items can be filled in within the brackets []. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to Japanese, this field will display the application description. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## description_fr + * Description: + Indicates the French description of the application, which should be a string not exceeding 367 bytes in length, containing a detailed custom description of the application. + The specific filling rules are as follows: + * Each item within the brackets [] represents the content of each line, with the next item representing the content of the next line. If a line break is needed, multiple items can be filled in within the brackets []. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to French, this field will display the application description. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## maintainer_cn + * Description: + Indicates the developer information of the application in Chinese, which should be a string not exceeding 127 bytes in length. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to Chinese, this field will display the developer information of the application. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## maintainer_en + * Description: + Indicates the developer information of the application in English, which should be a string not exceeding 127 bytes in length. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to English, or other languages that are not Chinese, Japanese, or French, this field will display the developer information of the application. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## maintainer_jp + * Description: + Indicates the developer information of the application in Japanese, which should be a string not exceeding 127 bytes in length. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to Japanese, this field will display the developer information of the application. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## maintainer_fr + * Description: + Indicates the developer information of the application in French, which should be a string not exceeding 127 bytes in length. + This field can be used to display application information, such as in the application management interface, when the PILOT language is set to French, this field will display the developer information of the application. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## ver_min + * Description: + Indicates the minimum version of the Manifold3 device firmware package required for the application to run properly. + If the firmware package version of the Manifold3 device is lower than this version, the application will not be able to install correctly. + The value is in the format of xx.xx.xx.xx, where each segment can range from 0 to 99. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## ver_max + * Description: + Indicates the maximum version of the Manifold3 device firmware package required for the application to run properly. + If the firmware package version of the Manifold3 device is higher than this version, the application will not be able to install correctly. + The value is in the format of xx.xx.xx.xx, where each segment can range from 0 to 99. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## bin + * Description: + The relative path of the executable bin file generated by the compilation, indicating the application executable bin file. + It must be a relative path, specifically the path relative to the app.json file, and there must be a corresponding bin file present at that path. + * Data type: + string + * Whether the field is optional? + No, this field is required + +## userconfig + * Description: + The relative path of the relevant files that need to be read at runtime by the application, which is not integrated into the bin file. + It must be a relative path, specifically the path relative to the app.json file, and there must be corresponding files present at that path. + If there are no relevant files, this field can be left blank. + * Data type: + string + * Whether the field is optional? + yes, this field is optional diff --git a/samples/sample_c/platform/linux/manifold3/app_json/app.json b/samples/sample_c/platform/linux/manifold3/app_json/app.json new file mode 100644 index 0000000..a143cc9 --- /dev/null +++ b/samples/sample_c/platform/linux/manifold3/app_json/app.json @@ -0,0 +1,44 @@ +{ + "user_app_id": "226", + "firmware_version": "01.00.00.00", + "is_ai_rendering": "false", + "platform": "manifold3", + "name":{ + "name_cn": "测试demo", + "name_en": "psdk-demo", + "name_jp": "テストデモ", + "name_fr": "Démo de test" + }, + "description": { + "description_cn": [ + "这是第一行", + "这是第二行", + "这是第三行", + "这是第四行" + ], + "description_en": [ + "This is the first line", + "This is the second line", + "This is the third line" + ], + "description_jp": [ + "これは一行目です", + "これは二行目です" + ], + "description_fr": [ + "Ceci est la première ligne" + ] + }, + "maintainer": { + "maintainer_cn": "大疆创新科技有限公司", + "maintainer_en": "DJI Innovation Technology Co., Ltd.", + "maintainer_jp": "大疆イノベーションテクノロジー有限会社", + "maintainer_fr": "Société à Responsabilité Limitée DJI Innovation Technology" + }, + "ver_min": "00.00.00.00", + "ver_max": "99.99.99.99", + "bin": "../../../../../../build/bin/dji_sdk_demo_on_manifold3", + "userconfig": [ + "../../../../../../samples" + ] +} diff --git a/samples/sample_c/platform/linux/manifold3/application/dji_sdk_app_info.h b/samples/sample_c/platform/linux/manifold3/application/dji_sdk_app_info.h new file mode 100644 index 0000000..7330d8d --- /dev/null +++ b/samples/sample_c/platform/linux/manifold3/application/dji_sdk_app_info.h @@ -0,0 +1,55 @@ +/** + ******************************************************************** + * @file dji_sdk_app_info.h + * @brief This is the header file for defining the structure and (exported) function prototypes. + * + * @copyright (c) 2018 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_SDK_APP_INFO_H +#define DJI_SDK_APP_INFO_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +// ATTENTION: User must goto https://developer.dji.com/user/apps/#all to create your own dji sdk application, get dji sdk application +// information then fill in the application information here. +#define USER_APP_NAME "your_app_name" +#define USER_APP_ID "your_app_id" +#define USER_APP_KEY "your_app_key" +#define USER_APP_LICENSE "your_app_license" +#define USER_DEVELOPER_ACCOUNT "your_developer_account" +#define USER_BAUD_RATE "460800" + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + + +#ifdef __cplusplus +} +#endif + +#endif // DJI_SDK_APP_INFO_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/linux/manifold3/application/dji_sdk_config.h b/samples/sample_c/platform/linux/manifold3/application/dji_sdk_config.h new file mode 100644 index 0000000..abcb9f2 --- /dev/null +++ b/samples/sample_c/platform/linux/manifold3/application/dji_sdk_config.h @@ -0,0 +1,83 @@ +/** + ******************************************************************** + * @file dji_sdk_config.h + * @brief This is the header file for "dji_config.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_SDK_CONFIG_H +#define DJI_SDK_CONFIG_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define DJI_USE_ONLY_UART (0) +#define DJI_USE_UART_AND_USB_BULK_DEVICE (1) +#define DJI_USE_UART_AND_NETWORK_DEVICE (2) +#define DJI_USE_ONLY_USB_BULK_DEVICE (3) +#define DJI_USE_ONLY_NETWORK_DEVICE (4) + +/*!< Attention: Select your hardware connection mode here. +* */ +#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_USB_BULK_DEVICE + +/*!< Attention: Select the sample you want to run here. +* */ +#define CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON + +#define CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON + +#define CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON + +#define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON + +#define CONFIG_MODULE_SAMPLE_XPORT_ON + +#define CONFIG_MODULE_SAMPLE_WIDGET_ON + +#define CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON + +#define CONFIG_MODULE_SAMPLE_UPGRADE_ON + +#define CONFIG_MODULE_SAMPLE_HMS_CUSTOMIZATION_ON + +#define CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON + +/*!< Attention: This function needs to be used together with mobile sdk mop sample. +* */ + +#define CONFIG_MODULE_SAMPLE_CLOUD_API_ON + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + +#ifdef __cplusplus +} +#endif + +#endif // DJI_SDK_CONFIG_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/linux/manifold3/application/main.c b/samples/sample_c/platform/linux/manifold3/application/main.c new file mode 100644 index 0000000..771c653 --- /dev/null +++ b/samples/sample_c/platform/linux/manifold3/application/main.c @@ -0,0 +1,676 @@ +/** + ******************************************************************** + * @file main.c + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "monitor/sys_monitor.h" +#include "osal/osal.h" +#include "osal/osal_fs.h" +#include "osal/osal_socket.h" +#include "../hal/hal_usb_bulk.h" +#include "dji_sdk_app_info.h" +#include "dji_aircraft_info.h" +#include "widget/test_widget.h" +#include "widget/test_widget_speaker.h" +#include "widget_interaction_test/test_widget_interaction.h" +#include "data_transmission/test_data_transmission.h" +#include "dji_sdk_config.h" + +/* Private constants ---------------------------------------------------------*/ +#define DJI_LOG_PATH "logs/DJI" +#define DJI_LOG_INDEX_FILE_NAME "logs/index" +#define DJI_LOG_FOLDER_NAME "logs" +#define DJI_LOG_PATH_MAX_SIZE (128) +#define DJI_LOG_FOLDER_NAME_MAX_SIZE (32) +#define DJI_LOG_MAX_COUNT (10) +#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64) +#define DJI_SYSTEM_RESULT_STR_MAX_SIZE (128) + +#define DJI_USE_WIDGET_INTERACTION 1 + +/* Private types -------------------------------------------------------------*/ +typedef struct { + pid_t tid; + char name[16]; + float pcpu; +} T_ThreadAttribute; + +/* Private values -------------------------------------------------------------*/ +static FILE *s_djiLogFile; +static FILE *s_djiLogFileCnt; +static pthread_t s_monitorThread = 0; + +/* Private functions declaration ---------------------------------------------*/ +static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void); +static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo); +static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen); +static T_DjiReturnCode DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen); +static T_DjiReturnCode DjiUser_LocalWriteFsInit(const char *path); +static void *DjiUser_MonitorTask(void *argument); +static T_DjiReturnCode DjiTest_HighPowerApplyPinInit(); +static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState); +static void DjiUser_NormalExitHandler(int signalNum); + +/* Exported functions definition ---------------------------------------------*/ +int main(int argc, char **argv) +{ + T_DjiReturnCode returnCode; + T_DjiUserInfo userInfo; + T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo; + T_DjiAircraftVersion aircraftInfoVersion; + T_DjiFirmwareVersion firmwareVersion = { + .majorVersion = 1, + .minorVersion = 0, + .modifyVersion = 0, + .debugVersion = 0, + }; + + USER_UTIL_UNUSED(argc); + USER_UTIL_UNUSED(argv); + + // attention: when the program is hand up ctrl-c will generate the coredump file + signal(SIGTERM, DjiUser_NormalExitHandler); + signal(SIGINT, DjiUser_NormalExitHandler); + + /*!< Step 1: Prepare system environment, such as osal, hal uart, console function and so on. */ + returnCode = DjiUser_PrepareSystemEnvironment(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Prepare system environment error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + /*!< Step 2: Fill your application information in dji_sdk_app_info.h and use this interface to fill it. */ + returnCode = DjiUser_FillInUserInfo(&userInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Fill user info error, please check user info config"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + /*!< Step 3: Initialize the Payload SDK core by your application information. */ + returnCode = DjiCore_Init(&userInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Core init error"); + sleep(1); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("get aircraft base info error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + returnCode = DjiAircraftInfo_GetAircraftVersion(&aircraftInfoVersion); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("get aircraft version info error"); + } else { + USER_LOG_INFO("Aircraft version is V%02d.%02d.%02d.%02d", aircraftInfoVersion.majorVersion, + aircraftInfoVersion.minorVersion, aircraftInfoVersion.modifyVersion, + aircraftInfoVersion.debugVersion); + } + + returnCode = DjiCore_SetAlias("PSDK_APPALIAS"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("set alias error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + returnCode = DjiCore_SetFirmwareVersion(firmwareVersion); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("set firmware version error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + returnCode = DjiCore_SetSerialNumber("PSDK12345678XX"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("set serial number error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + /*!< Step 4: Initialize the selected modules by macros in dji_sdk_config.h . */ +#ifdef CONFIG_MODULE_SAMPLE_WIDGET_ON +#if DJI_USE_WIDGET_INTERACTION + returnCode = DjiTest_WidgetInteractionStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget interaction test init error"); + } +#else + returnCode = DjiTest_WidgetStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget sample init error"); + } +#endif +#endif + + returnCode = DjiCore_ApplicationStart(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("start sdk application error"); + } + +#ifdef CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON + T_DjiTestApplyHighPowerHandler applyHighPowerHandler = { + .pinInit = DjiTest_HighPowerApplyPinInit, + .pinWrite = DjiTest_WriteHighPowerApplyPin, + }; + + returnCode = DjiTest_RegApplyHighPowerHandler(&applyHighPowerHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("regsiter apply high power handler error"); + } + + returnCode = DjiTest_PowerManagementStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("power management init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON + returnCode = DjiTest_DataTransmissionStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("data tramsmission sample init error"); + } +#endif + + if (aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_EXTENSION_PORT && + (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK || + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK)) { + returnCode = DjiTest_WidgetInteractionStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget interaction sample init error"); + } + + returnCode = DjiTest_WidgetSpeakerStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget speaker test init error"); + } + } else { +#ifdef CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON + returnCode = DjiTest_CameraEmuBaseStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("camera emu common init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON + returnCode = DjiTest_CameraEmuMediaStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("camera emu media init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON + returnCode = DjiTest_FcSubscriptionStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("data subscription sample init error\n"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON + if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) { + if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk gimbal init error"); + } + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_XPORT_ON + if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) { + if (DjiTest_XPortStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk xport init error"); + } + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_CLOUD_API_ON + returnCode = DjiTest_CloudApiByWebSocketStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("CloudApiByWebSocket send data sample start error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_PAYLOAD_COLLABORATION_ON + if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) { + returnCode = DjiTest_PayloadCollaborationStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Payload collaboration sample init error\n"); + } + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_UPGRADE_ON + T_DjiTestUpgradePlatformOpt linuxUpgradePlatformOpt = { + .rebootSystem = DjiUpgradePlatformLinux_RebootSystem, + .cleanUpgradeProgramFileStoreArea = DjiUpgradePlatformLinux_CleanUpgradeProgramFileStoreArea, + .createUpgradeProgramFile = DjiUpgradePlatformLinux_CreateUpgradeProgramFile, + .writeUpgradeProgramFile = DjiUpgradePlatformLinux_WriteUpgradeProgramFile, + .readUpgradeProgramFile = DjiUpgradePlatformLinux_ReadUpgradeProgramFile, + .closeUpgradeProgramFile = DjiUpgradePlatformLinux_CloseUpgradeProgramFile, + .replaceOldProgram = DjiUpgradePlatformLinux_ReplaceOldProgram, + .setUpgradeRebootState = DjiUpgradePlatformLinux_SetUpgradeRebootState, + .getUpgradeRebootState = DjiUpgradePlatformLinux_GetUpgradeRebootState, + .cleanUpgradeRebootState = DjiUpgradePlatformLinux_CleanUpgradeRebootState, + }; + T_DjiTestUpgradeConfig testUpgradeConfig = { + .firmwareVersion = firmwareVersion, + .transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP, + .needReplaceProgramBeforeReboot = true + }; + if (DjiTest_UpgradeStartService(&linuxUpgradePlatformOpt, testUpgradeConfig) != + DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk upgrade init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_HMS_CUSTOMIZATION_ON + returnCode = DjiTest_HmsCustomizationStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("hms test init error"); + } +#endif + } + + if (pthread_create(&s_monitorThread, NULL, DjiUser_MonitorTask, NULL) != 0) { + USER_LOG_ERROR("create monitor task fail."); + } + + if (pthread_setname_np(s_monitorThread, "monitor task") != 0) { + USER_LOG_ERROR("set name for monitor task fail."); + } + + while (1) { + sleep(1); + } +} + +/* Private functions definition-----------------------------------------------*/ +static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void) +{ + T_DjiReturnCode returnCode; + T_DjiOsalHandler osalHandler = { + .TaskCreate = Osal_TaskCreate, + .TaskDestroy = Osal_TaskDestroy, + .TaskSleepMs = Osal_TaskSleepMs, + .MutexCreate= Osal_MutexCreate, + .MutexDestroy = Osal_MutexDestroy, + .MutexLock = Osal_MutexLock, + .MutexUnlock = Osal_MutexUnlock, + .SemaphoreCreate = Osal_SemaphoreCreate, + .SemaphoreDestroy = Osal_SemaphoreDestroy, + .SemaphoreWait = Osal_SemaphoreWait, + .SemaphoreTimedWait = Osal_SemaphoreTimedWait, + .SemaphorePost = Osal_SemaphorePost, + .Malloc = Osal_Malloc, + .Free = Osal_Free, + .GetRandomNum = Osal_GetRandomNum, + .GetTimeMs = Osal_GetTimeMs, + .GetTimeUs = Osal_GetTimeUs, + }; + + T_DjiLoggerConsole printConsole = { + .func = DjiUser_PrintConsole, + .consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO, + .isSupportColor = true, + }; + + T_DjiLoggerConsole localRecordConsole = { + .consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG, + .func = DjiUser_LocalWrite, + .isSupportColor = true, + }; + + T_DjiHalUsbBulkHandler usbBulkHandler = { + .UsbBulkInit = HalUsbBulk_Init, + .UsbBulkDeInit = HalUsbBulk_DeInit, + .UsbBulkWriteData = HalUsbBulk_WriteData, + .UsbBulkReadData = HalUsbBulk_ReadData, + .UsbBulkGetDeviceInfo = HalUsbBulk_GetDeviceInfo, + }; + + T_DjiFileSystemHandler fileSystemHandler = { + .FileOpen = Osal_FileOpen, + .FileClose = Osal_FileClose, + .FileWrite = Osal_FileWrite, + .FileRead = Osal_FileRead, + .FileSync = Osal_FileSync, + .FileSeek = Osal_FileSeek, + .DirOpen = Osal_DirOpen, + .DirClose = Osal_DirClose, + .DirRead = Osal_DirRead, + .Mkdir = Osal_Mkdir, + .Unlink = Osal_Unlink, + .Rename = Osal_Rename, + .Stat = Osal_Stat, + }; + + T_DjiSocketHandler socketHandler = { + .Socket = Osal_Socket, + .Bind = Osal_Bind, + .Close = Osal_Close, + .UdpSendData = Osal_UdpSendData, + .UdpRecvData = Osal_UdpRecvData, + .TcpListen = Osal_TcpListen, + .TcpAccept = Osal_TcpAccept, + .TcpConnect = Osal_TcpConnect, + .TcpSendData = Osal_TcpSendData, + .TcpRecvData = Osal_TcpRecvData, + }; + + returnCode = DjiPlatform_RegOsalHandler(&osalHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register osal handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (DjiUser_LocalWriteFsInit(DJI_LOG_PATH) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("file system init error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } + + returnCode = DjiLogger_AddConsole(&printConsole); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("add printf console error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + returnCode = DjiLogger_AddConsole(&localRecordConsole); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("add printf console error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register hal usb bulk handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + //Attention: if you want to use camera stream view function, please uncomment it. + returnCode = DjiPlatform_RegSocketHandler(&socketHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register osal socket handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register osal filesystem handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo) +{ + if (userInfo == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + memset(userInfo->appName, 0, sizeof(userInfo->appName)); + memset(userInfo->appId, 0, sizeof(userInfo->appId)); + memset(userInfo->appKey, 0, sizeof(userInfo->appKey)); + memset(userInfo->appLicense, 0, sizeof(userInfo->appLicense)); + memset(userInfo->developerAccount, 0, sizeof(userInfo->developerAccount)); + memset(userInfo->baudRate, 0, sizeof(userInfo->baudRate)); + + if (strlen(USER_APP_NAME) >= sizeof(userInfo->appName) || + strlen(USER_APP_ID) > sizeof(userInfo->appId) || + strlen(USER_APP_KEY) > sizeof(userInfo->appKey) || + strlen(USER_APP_LICENSE) > sizeof(userInfo->appLicense) || + strlen(USER_DEVELOPER_ACCOUNT) >= sizeof(userInfo->developerAccount) || + strlen(USER_BAUD_RATE) > sizeof(userInfo->baudRate)) { + USER_LOG_ERROR("Length of user information string is beyond limit. Please check."); + sleep(1); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + if (!strcmp(USER_APP_NAME, "your_app_name") || + !strcmp(USER_APP_ID, "your_app_id") || + !strcmp(USER_APP_KEY, "your_app_key") || + !strcmp(USER_BAUD_RATE, "your_app_license") || + !strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") || + !strcmp(USER_BAUD_RATE, "your_baud_rate")) { + USER_LOG_ERROR( + "Please fill in correct user information to 'samples/sample_c/platform/linux/nvidia_jetson/application/dji_sdk_app_info.h' file."); + sleep(1); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + strncpy(userInfo->appName, USER_APP_NAME, sizeof(userInfo->appName) - 1); + memcpy(userInfo->appId, USER_APP_ID, USER_UTIL_MIN(sizeof(userInfo->appId), strlen(USER_APP_ID))); + memcpy(userInfo->appKey, USER_APP_KEY, USER_UTIL_MIN(sizeof(userInfo->appKey), strlen(USER_APP_KEY))); + memcpy(userInfo->appLicense, USER_APP_LICENSE, + USER_UTIL_MIN(sizeof(userInfo->appLicense), strlen(USER_APP_LICENSE))); + memcpy(userInfo->baudRate, USER_BAUD_RATE, USER_UTIL_MIN(sizeof(userInfo->baudRate), strlen(USER_BAUD_RATE))); + strncpy(userInfo->developerAccount, USER_DEVELOPER_ACCOUNT, sizeof(userInfo->developerAccount) - 1); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen) +{ + USER_UTIL_UNUSED(dataLen); + + printf("%s", data); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +static T_DjiReturnCode DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen) +{ + uint32_t realLen; + + if (s_djiLogFile == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } + + realLen = fwrite(data, 1, dataLen, s_djiLogFile); + fflush(s_djiLogFile); + if (realLen == dataLen) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else { + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } +} + +static T_DjiReturnCode DjiUser_LocalWriteFsInit(const char *path) +{ + T_DjiReturnCode djiReturnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + char filePath[DJI_LOG_PATH_MAX_SIZE]; + char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE]; + char folderName[DJI_LOG_FOLDER_NAME_MAX_SIZE]; + time_t currentTime = time(NULL); + struct tm *localTime = localtime(¤tTime); + uint16_t logFileIndex = 0; + uint16_t currentLogFileIndex; + uint8_t ret; + + if (localTime == NULL) { + printf("Get local time error.\r\n"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (access(DJI_LOG_FOLDER_NAME, F_OK) != 0) { + sprintf(folderName, "mkdir %s", DJI_LOG_FOLDER_NAME); + ret = system(folderName); + if (ret != 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + + s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "rb+"); + if (s_djiLogFileCnt == NULL) { + s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "wb+"); + if (s_djiLogFileCnt == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else { + ret = fseek(s_djiLogFileCnt, 0, SEEK_SET); + if (ret != 0) { + printf("Seek log count file error, ret: %d, errno: %d.\r\n", ret, errno); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = fread((uint16_t *) &logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt); + if (ret != sizeof(uint16_t)) { + printf("Read log file index error.\r\n"); + } + } + + currentLogFileIndex = logFileIndex; + logFileIndex++; + + ret = fseek(s_djiLogFileCnt, 0, SEEK_SET); + if (ret != 0) { + printf("Seek log file error, ret: %d, errno: %d.\r\n", ret, errno); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = fwrite((uint16_t *) &logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt); + if (ret != sizeof(uint16_t)) { + printf("Write log file index error.\r\n"); + fclose(s_djiLogFileCnt); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + fclose(s_djiLogFileCnt); + + sprintf(filePath, "%s_%04d_%04d%02d%02d_%02d-%02d-%02d.log", path, currentLogFileIndex, + localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday, + localTime->tm_hour, localTime->tm_min, localTime->tm_sec); + + s_djiLogFile = fopen(filePath, "wb+"); + if (s_djiLogFile == NULL) { + USER_LOG_ERROR("Open filepath time error."); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (logFileIndex >= DJI_LOG_MAX_COUNT) { + sprintf(systemCmd, "rm -rf %s_%04d*.log", path, currentLogFileIndex - DJI_LOG_MAX_COUNT); + ret = system(systemCmd); + if (ret != 0) { + printf("Remove file error, ret:%d.\r\n", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + + sprintf(systemCmd, "ln -sfrv %s " DJI_LOG_FOLDER_NAME "/latest.log", filePath); + system(systemCmd); + return djiReturnCode; +} + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wmissing-noreturn" +#pragma GCC diagnostic ignored "-Wreturn-type" + +static void *DjiUser_MonitorTask(void *argument) +{ + unsigned int i = 0; + unsigned int threadCount = 0; + pid_t *tidList = NULL; + T_ThreadAttribute *threadAttribute = NULL; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + USER_UTIL_UNUSED(argument); + + while (1) { + threadCount = Monitor_GetThreadCountOfProcess(getpid()); + tidList = osalHandler->Malloc(threadCount * sizeof(pid_t)); + if (tidList == NULL) { + USER_LOG_ERROR("malloc fail."); + goto delay; + } + Monitor_GetTidListOfProcess(getpid(), tidList, threadCount); + + threadAttribute = osalHandler->Malloc(threadCount * sizeof(T_ThreadAttribute)); + if (threadAttribute == NULL) { + USER_LOG_ERROR("malloc fail."); + goto freeTidList; + } + for (i = 0; i < threadCount; ++i) { + threadAttribute[i].tid = tidList[i]; + } + + USER_LOG_DEBUG("thread pcpu:"); + USER_LOG_DEBUG("tid\tname\tpcpu"); + for (i = 0; i < threadCount; ++i) { + threadAttribute[i].pcpu = Monitor_GetPcpuOfThread(getpid(), tidList[i]); + Monitor_GetNameOfThread(getpid(), tidList[i], threadAttribute[i].name, sizeof(threadAttribute[i].name)); + USER_LOG_DEBUG("%d\t%15s\t%f %%.", threadAttribute[i].tid, threadAttribute[i].name, + threadAttribute[i].pcpu); + } + + USER_LOG_DEBUG("heap used: %d B.", Monitor_GetHeapUsed(getpid())); + USER_LOG_DEBUG("stack used: %d B.", Monitor_GetStackUsed(getpid())); + + osalHandler->Free(threadAttribute); +freeTidList: + osalHandler->Free(tidList); + +delay: + sleep(10); + } +} + +static T_DjiReturnCode DjiTest_HighPowerApplyPinInit() +{ + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState) +{ + //attention: please pull up the HWPR pin state by hardware. + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +static void DjiUser_NormalExitHandler(int signalNum) +{ + USER_UTIL_UNUSED(signalNum); + exit(0); +} + +#pragma GCC diagnostic pop + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/linux/manifold3/hal/hal_usb_bulk.c b/samples/sample_c/platform/linux/manifold3/hal/hal_usb_bulk.c new file mode 100644 index 0000000..85c5d72 --- /dev/null +++ b/samples/sample_c/platform/linux/manifold3/hal/hal_usb_bulk.c @@ -0,0 +1,252 @@ +/** + ******************************************************************** + * @file hal_usb_bulk.c + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "hal_usb_bulk.h" +#include "dji_logger.h" +#include + +/* Private constants ---------------------------------------------------------*/ +#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50) +#define LINUX_USB_BULK_TRANSFER_WAIT_FOREVER (-1) + +/* Private types -------------------------------------------------------------*/ +typedef struct { +#ifdef LIBUSB_INSTALLED + libusb_device_handle *handle; +#else + void *handle; +#endif + int32_t ep1; + int32_t ep2; + uint32_t interfaceNum; + T_DjiHalUsbBulkInfo usbBulkInfo; +} T_HalUsbBulkObj; + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle) +{ + int32_t ret; + struct libusb_device_handle *handle = NULL; + + *usbBulkHandle = malloc(sizeof(T_HalUsbBulkObj)); + if (*usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + if (usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_init(NULL); + if (ret < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid); + if (handle == NULL) { + USER_LOG_ERROR("libusb open device error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ret = libusb_claim_interface(handle, usbBulkInfo.channelInfo.interfaceNum); + if (ret != LIBUSB_SUCCESS) { + USER_LOG_ERROR("libusb claim interface error"); + libusb_close(handle); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle; + memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo)); +#endif + } else { + ((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle; + memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo)); + ((T_HalUsbBulkObj *) *usbBulkHandle)->interfaceNum = usbBulkInfo.channelInfo.interfaceNum; + + if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK1_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK1_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK1_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK2_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK2_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK2_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle) +{ + struct libusb_device_handle *handle = NULL; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum); + osalHandler->TaskSleepMs(100); + libusb_exit(NULL); +#endif + } else { + close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1); + close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2); + } + + free(usbBulkHandle); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len, + uint32_t *realLen) +{ + int32_t ret; + int32_t actualLen; + struct libusb_device_handle *handle = NULL; + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut, + (uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS); + if (ret < 0) { + USER_LOG_ERROR("Write usb bulk data failed, errno = %d", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + *realLen = actualLen; +#endif + } else { + ret = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len); + if (ret < 0) { + USER_LOG_ERROR("write ret %d %d %s\n", ret, errno, strerror(errno)); + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else { + *realLen = ret; + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, + uint32_t *realLen) +{ + int32_t ret; + struct libusb_device_handle *handle = NULL; + int32_t actualLen; + + if (usbBulkHandle == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle; + + if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) { +#ifdef LIBUSB_INSTALLED + ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn, + buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER); + if (ret < 0) { + USER_LOG_ERROR("Read usb bulk data failed, errno = %d", ret); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + *realLen = actualLen; +#endif + } else { + ret = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len); + if (ret < 0) { + USER_LOG_ERROR("read ret %d %d %s\n", ret, errno, strerror(errno)); + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; + } else { + *realLen = ret; + } + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo) +{ + //attention: this interface only be called in usb device mode. + deviceInfo->vid = LINUX_USB_VID; + deviceInfo->pid = LINUX_USB_PID; + + // This bulk channel is used to obtain DJI camera video stream and push 3rd-party camera video stream. + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].interfaceNum = LINUX_USB_BULK1_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointIn = LINUX_USB_BULK1_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointOut = LINUX_USB_BULK1_END_POINT_OUT; + + // This bulk channel is used to obtain DJI perception image and download camera media file. + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].interfaceNum = LINUX_USB_BULK2_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT; + + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/linux/manifold3/hal/hal_usb_bulk.h b/samples/sample_c/platform/linux/manifold3/hal/hal_usb_bulk.h new file mode 100644 index 0000000..841396b --- /dev/null +++ b/samples/sample_c/platform/linux/manifold3/hal/hal_usb_bulk.h @@ -0,0 +1,95 @@ +/** + ******************************************************************** + * @file hal_usb_bulk.h + * @brief This is the header file for "hal_usb_bulk.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef HAL_USB_BULK_H +#define HAL_USB_BULK_H + +/* Includes ------------------------------------------------------------------*/ +#include "stdint.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef LIBUSB_INSTALLED + +#include + +#endif + +#include "dji_platform.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +#define LINUX_USB_BULK1_EP_IN_FD "/dev/usb-ffs/bulk2/ep2" +#define LINUX_USB_BULK1_EP_OUT_FD "/dev/usb-ffs/bulk2/ep1" + +#define LINUX_USB_BULK1_INTERFACE_NUM (2) +#define LINUX_USB_BULK1_END_POINT_IN (0x83) +#define LINUX_USB_BULK1_END_POINT_OUT (0x02) + +#define LINUX_USB_BULK2_EP_IN_FD "/dev/usb-ffs/bulk6/ep2" +#define LINUX_USB_BULK2_EP_OUT_FD "/dev/usb-ffs/bulk6/ep1" + +#define LINUX_USB_BULK2_INTERFACE_NUM (6) +#define LINUX_USB_BULK2_END_POINT_IN (0x87) +#define LINUX_USB_BULK2_END_POINT_OUT (0x06) + +#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep2" +#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep1" + +#define LINUX_USB_BULK3_INTERFACE_NUM (3) +#define LINUX_USB_BULK3_END_POINT_IN (0x84) +#define LINUX_USB_BULK3_END_POINT_OUT (0x03) + +#define LINUX_USB_VID (0x2CA3) +#define LINUX_USB_PID (0x3181) + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle); +T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle); +T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len, + uint32_t *realLen); +T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo); + +#ifdef __cplusplus +} +#endif + +#endif // HAL_USB_BULK_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/linux/nvidia_jetson/CMakeLists.txt b/samples/sample_c/platform/linux/nvidia_jetson/CMakeLists.txt index cebe385..6d2ff8a 100644 --- a/samples/sample_c/platform/linux/nvidia_jetson/CMakeLists.txt +++ b/samples/sample_c/platform/linux/nvidia_jetson/CMakeLists.txt @@ -82,7 +82,7 @@ else () message(STATUS "Cannot Find LIBUSB") endif (LIBUSB_FOUND) -target_link_libraries(${PROJECT_NAME} m) +target_link_libraries(${PROJECT_NAME} m dl) add_custom_command(TARGET ${PROJECT_NAME} PRE_LINK COMMAND cmake .. diff --git a/samples/sample_c/platform/linux/nvidia_jetson/application/dji_sdk_config.h b/samples/sample_c/platform/linux/nvidia_jetson/application/dji_sdk_config.h index a152f89..04d3848 100644 --- a/samples/sample_c/platform/linux/nvidia_jetson/application/dji_sdk_config.h +++ b/samples/sample_c/platform/linux/nvidia_jetson/application/dji_sdk_config.h @@ -37,10 +37,12 @@ extern "C" { #define DJI_USE_ONLY_UART (0) #define DJI_USE_UART_AND_USB_BULK_DEVICE (1) #define DJI_USE_UART_AND_NETWORK_DEVICE (2) +#define DJI_USE_ONLY_USB_BULK_DEVICE (3) +#define DJI_USE_ONLY_NETWORK_DEVICE (4) /*!< Attention: Select your hardware connection mode here. * */ -#define CONFIG_HARDWARE_CONNECTION DJI_USE_UART_AND_NETWORK_DEVICE +#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_USB_BULK_DEVICE /*!< Attention: Select the sample you want to run here. * */ diff --git a/samples/sample_c/platform/linux/nvidia_jetson/application/main.c b/samples/sample_c/platform/linux/nvidia_jetson/application/main.c index 18ed76f..fd8ec84 100644 --- a/samples/sample_c/platform/linux/nvidia_jetson/application/main.c +++ b/samples/sample_c/platform/linux/nvidia_jetson/application/main.c @@ -227,6 +227,8 @@ int main(int argc, char **argv) #ifdef CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 || aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) { if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("psdk gimbal init error"); @@ -373,6 +375,7 @@ static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void) .UartWriteData = HalUart_WriteData, .UartReadData = HalUart_ReadData, .UartGetStatus = HalUart_GetStatus, + .UartGetDeviceInfo = HalUart_GetDeviceInfo, }; T_DjiHalNetworkHandler networkHandler = { @@ -492,6 +495,26 @@ static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void) return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } +#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_USB_BULK_DEVICE) + returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register hal usb bulk handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + +#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_NETWORK_DEVICE) + returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register hal network handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + //Attention: if you want to use camera stream view function, please uncomment it. + returnCode = DjiPlatform_RegSocketHandler(&socketHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register osal socket handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } #endif returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler); diff --git a/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_uart.c b/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_uart.c index 5cf5727..b5c4118 100644 --- a/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_uart.c +++ b/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_uart.c @@ -255,6 +255,18 @@ T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *stat return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo) +{ + if (deviceInfo == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + deviceInfo->vid = USB_UART_CONNECTED_TO_UAV_VID; + deviceInfo->pid = USB_UART_CONNECTED_TO_UAV_PID; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + /* Private functions definition-----------------------------------------------*/ /****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_uart.h b/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_uart.h index f30a661..1be208e 100644 --- a/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_uart.h +++ b/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_uart.h @@ -48,6 +48,15 @@ extern "C" { #define LINUX_UART_DEV1 "/dev/ttyUSB0" #define LINUX_UART_DEV2 "/dev/ttyACM0" +/** + * Use for Eport 2.0, specify the VID and PID of the USB serial port closest to the aircraft. + * FT232 0x0403:0x6001 + * CP2102 0x10C4:0xEA60 + * VCOM 0x2CA3:0xF002 + */ +#define USB_UART_CONNECTED_TO_UAV_VID (0x0403) +#define USB_UART_CONNECTED_TO_UAV_PID (0x6001) + /* Exported types ------------------------------------------------------------*/ /* Exported functions --------------------------------------------------------*/ @@ -56,6 +65,7 @@ T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle); T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status); +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo); #ifdef __cplusplus } diff --git a/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_usb_bulk.c b/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_usb_bulk.c index 287d61e..85c5d72 100644 --- a/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_usb_bulk.c +++ b/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_usb_bulk.c @@ -107,6 +107,16 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } } } @@ -230,6 +240,10 @@ T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo) deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN; deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT; + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } diff --git a/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_usb_bulk.h b/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_usb_bulk.h index ea41d3e..3626574 100644 --- a/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_usb_bulk.h +++ b/samples/sample_c/platform/linux/nvidia_jetson/hal/hal_usb_bulk.h @@ -66,8 +66,15 @@ extern "C" { #define LINUX_USB_BULK2_END_POINT_IN (0x82) #define LINUX_USB_BULK2_END_POINT_OUT (0x02) -#define LINUX_USB_VID (0x0955) -#define LINUX_USB_PID (0x7020) +#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep1" +#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep2" + +#define LINUX_USB_BULK3_INTERFACE_NUM (2) +#define LINUX_USB_BULK3_END_POINT_IN (0x83) +#define LINUX_USB_BULK3_END_POINT_OUT (0x03) + +#define LINUX_USB_VID (0x2CA3) +#define LINUX_USB_PID (0xF001) /* Exported types ------------------------------------------------------------*/ diff --git a/samples/sample_c/platform/linux/raspberry_pi/CMakeLists.txt b/samples/sample_c/platform/linux/raspberry_pi/CMakeLists.txt index 3941dcf..071ecec 100644 --- a/samples/sample_c/platform/linux/raspberry_pi/CMakeLists.txt +++ b/samples/sample_c/platform/linux/raspberry_pi/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(dji_sdk_demo_linux C) +project(dji_sdk_demo_on_rpi C) set(CMAKE_C_FLAGS "-pthread -std=gnu99") set(CMAKE_CXX_FLAGS "-std=c++11 -pthread") @@ -82,7 +82,7 @@ else () message(STATUS "Cannot Find LIBUSB") endif (LIBUSB_FOUND) -target_link_libraries(${PROJECT_NAME} m) +target_link_libraries(${PROJECT_NAME} m dl) add_custom_command(TARGET ${PROJECT_NAME} PRE_LINK COMMAND cmake .. diff --git a/samples/sample_c/platform/linux/raspberry_pi/application/dji_sdk_config.h b/samples/sample_c/platform/linux/raspberry_pi/application/dji_sdk_config.h index 8a9cf3e..8c99b1f 100644 --- a/samples/sample_c/platform/linux/raspberry_pi/application/dji_sdk_config.h +++ b/samples/sample_c/platform/linux/raspberry_pi/application/dji_sdk_config.h @@ -37,6 +37,8 @@ extern "C" { #define DJI_USE_ONLY_UART (0) #define DJI_USE_UART_AND_USB_BULK_DEVICE (1) #define DJI_USE_UART_AND_NETWORK_DEVICE (2) +#define DJI_USE_ONLY_USB_BULK_DEVICE (3) +#define DJI_USE_ONLY_NETWORK_DEVICE (4) /*!< Attention: Select your hardware connection mode here. * */ @@ -58,11 +60,11 @@ extern "C" { #define CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON true -#define CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON false +#define CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON true #define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON true -#define CONFIG_MODULE_SAMPLE_XPORT_ON false +#define CONFIG_MODULE_SAMPLE_XPORT_ON true #define CONFIG_MODULE_SAMPLE_PAYLOAD_COLLABORATION_ON false @@ -72,6 +74,8 @@ extern "C" { * */ #define CONFIG_MODULE_SAMPLE_MOP_CHANNEL_ON false +#define CONFIG_MODULE_SAMPLE_TETHERED_BATTERY_ON true + /* Exported types ------------------------------------------------------------*/ /* Exported functions --------------------------------------------------------*/ diff --git a/samples/sample_c/platform/linux/raspberry_pi/application/main.c b/samples/sample_c/platform/linux/raspberry_pi/application/main.c index d90fa25..651eb74 100644 --- a/samples/sample_c/platform/linux/raspberry_pi/application/main.c +++ b/samples/sample_c/platform/linux/raspberry_pi/application/main.c @@ -54,6 +54,7 @@ #include "widget/test_widget_speaker.h" #include "widget/test_widget.h" #include "data_transmission/test_data_transmission.h" +#include "tethered_battery/test_tethered_battery.h" #include "dji_sdk_config.h" /* Private constants ---------------------------------------------------------*/ @@ -66,8 +67,6 @@ #define DJI_SYSTEM_CMD_STR_MAX_SIZE (64) #define DJI_SYSTEM_RESULT_STR_MAX_SIZE (128) -#define DJI_USE_WIDGET_INTERACTION 1 - /* Private types -------------------------------------------------------------*/ typedef struct { pid_t tid; @@ -142,6 +141,7 @@ int main(int argc, char **argv) returnCode = DjiCore_Init(&userInfo); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Core init error"); + sleep(1); return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } @@ -157,7 +157,6 @@ int main(int argc, char **argv) return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } - if (aircraftInfoBaseInfo.mountPositionType != DJI_MOUNT_POSITION_TYPE_PAYLOAD_PORT) { returnCode = DjiAircraftInfo_GetAircraftVersion(&aircraftInfoVersion); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("get aircraft version info error"); @@ -165,7 +164,6 @@ int main(int argc, char **argv) USER_LOG_INFO("Aircraft version is V%02d.%02d.%02d.%02d", aircraftInfoVersion.majorVersion, aircraftInfoVersion.minorVersion, aircraftInfoVersion.modifyVersion, aircraftInfoVersion.debugVersion); - } } /*!< Step 4: Initialize the selected modules by macros in dji_sdk_config.h . */ @@ -189,22 +187,15 @@ int main(int argc, char **argv) #if CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON returnCode = DjiTest_DataTransmissionStartService(); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("widget sample init error"); + USER_LOG_ERROR("data tramsmission sample init error"); } #endif #if CONFIG_MODULE_SAMPLE_WIDGET_ON - #if DJI_USE_WIDGET_INTERACTION - returnCode = DjiTest_WidgetInteractionStartService(); - if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("widget interaction test init error"); - } - #else - returnCode = DjiTest_WidgetStartService(); - if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("widget sample init error"); - } - #endif + returnCode = DjiTest_WidgetInteractionStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget sample init error"); + } #endif #if CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON @@ -214,30 +205,6 @@ int main(int argc, char **argv) } #endif - #if CONFIG_MODULE_SAMPLE_UPGRADE_ON - T_DjiTestUpgradePlatformOpt linuxUpgradePlatformOpt = { - .rebootSystem = DjiUpgradePlatformLinux_RebootSystem, - .cleanUpgradeProgramFileStoreArea = DjiUpgradePlatformLinux_CleanUpgradeProgramFileStoreArea, - .createUpgradeProgramFile = DjiUpgradePlatformLinux_CreateUpgradeProgramFile, - .writeUpgradeProgramFile = DjiUpgradePlatformLinux_WriteUpgradeProgramFile, - .readUpgradeProgramFile = DjiUpgradePlatformLinux_ReadUpgradeProgramFile, - .closeUpgradeProgramFile = DjiUpgradePlatformLinux_CloseUpgradeProgramFile, - .replaceOldProgram = DjiUpgradePlatformLinux_ReplaceOldProgram, - .setUpgradeRebootState = DjiUpgradePlatformLinux_SetUpgradeRebootState, - .getUpgradeRebootState = DjiUpgradePlatformLinux_GetUpgradeRebootState, - .cleanUpgradeRebootState = DjiUpgradePlatformLinux_CleanUpgradeRebootState, - }; - T_DjiTestUpgradeConfig testUpgradeConfig = { - .firmwareVersion = firmwareVersion, - .transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP, - .needReplaceProgramBeforeReboot = true - }; - if (DjiTest_UpgradeStartService(&linuxUpgradePlatformOpt, testUpgradeConfig) != - DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("psdk upgrade init error"); - } - #endif - if (aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_EXTENSION_PORT && (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK || aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK)) { @@ -266,6 +233,8 @@ int main(int argc, char **argv) #if CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 || aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) { if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("psdk gimbal init error"); @@ -281,6 +250,13 @@ int main(int argc, char **argv) } #endif + #if CONFIG_MODULE_SAMPLE_MOP_CHANNEL_ON + returnCode = DjiTest_MopChannelStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("mop channel sample init error"); + } + #endif + #if CONFIG_MODULE_SAMPLE_PAYLOAD_COLLABORATION_ON if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 || aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) { @@ -292,6 +268,30 @@ int main(int argc, char **argv) #endif } + #if CONFIG_MODULE_SAMPLE_UPGRADE_ON + T_DjiTestUpgradePlatformOpt linuxUpgradePlatformOpt = { + .rebootSystem = DjiUpgradePlatformLinux_RebootSystem, + .cleanUpgradeProgramFileStoreArea = DjiUpgradePlatformLinux_CleanUpgradeProgramFileStoreArea, + .createUpgradeProgramFile = DjiUpgradePlatformLinux_CreateUpgradeProgramFile, + .writeUpgradeProgramFile = DjiUpgradePlatformLinux_WriteUpgradeProgramFile, + .readUpgradeProgramFile = DjiUpgradePlatformLinux_ReadUpgradeProgramFile, + .closeUpgradeProgramFile = DjiUpgradePlatformLinux_CloseUpgradeProgramFile, + .replaceOldProgram = DjiUpgradePlatformLinux_ReplaceOldProgram, + .setUpgradeRebootState = DjiUpgradePlatformLinux_SetUpgradeRebootState, + .getUpgradeRebootState = DjiUpgradePlatformLinux_GetUpgradeRebootState, + .cleanUpgradeRebootState = DjiUpgradePlatformLinux_CleanUpgradeRebootState, + }; + T_DjiTestUpgradeConfig testUpgradeConfig = { + .firmwareVersion = firmwareVersion, + .transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP, + .needReplaceProgramBeforeReboot = true + }; + if (DjiTest_UpgradeStartService(&linuxUpgradePlatformOpt, testUpgradeConfig) != + DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk upgrade init error"); + } + #endif + #if CONFIG_MODULE_SAMPLE_HMS_CUSTOMIZATION_ON returnCode = DjiTest_HmsCustomizationStartService(); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { @@ -299,10 +299,12 @@ int main(int argc, char **argv) } #endif - #if CONFIG_MODULE_SAMPLE_MOP_CHANNEL_ON - returnCode = DjiTest_MopChannelStartService(); - if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("mop channel sample init error"); + + #if CONFIG_MODULE_SAMPLE_TETHERED_BATTERY_ON + if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE) { + if (DjiTest_TetheredBatteryStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk tethered battery sample init error"); + } } #endif @@ -344,9 +346,9 @@ static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void) .SemaphorePost = Osal_SemaphorePost, .Malloc = Osal_Malloc, .Free = Osal_Free, + .GetRandomNum = Osal_GetRandomNum, .GetTimeMs = Osal_GetTimeMs, .GetTimeUs = Osal_GetTimeUs, - .GetRandomNum = Osal_GetRandomNum, }; T_DjiLoggerConsole printConsole = { @@ -367,6 +369,7 @@ static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void) .UartWriteData = HalUart_WriteData, .UartReadData = HalUart_ReadData, .UartGetStatus = HalUart_GetStatus, + .UartGetDeviceInfo = HalUart_GetDeviceInfo, }; T_DjiHalNetworkHandler networkHandler = { @@ -479,14 +482,34 @@ static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void) printf("register osal socket handler error"); return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } + #elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_UART) - /*!< Attention: Only use uart hardware connection. - */ returnCode = DjiPlatform_RegHalUartHandler(&uartHandler); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { printf("register hal uart handler error"); return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } + + #elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_USB_BULK_DEVICE) + returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register hal usb bulk handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + #elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_NETWORK_DEVICE) + returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register hal network handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + //Attention: if you want to use camera stream view function, please uncomment it. + returnCode = DjiPlatform_RegSocketHandler(&socketHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register osal socket handler error"); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } #endif returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler); diff --git a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_network.c b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_network.c index 15e694b..a2adb2c 100644 --- a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_network.c +++ b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_network.c @@ -42,16 +42,27 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe { int32_t ret; char cmdStr[LINUX_CMD_STR_MAX_SIZE]; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); + int32_t routeIp[4] = {0}; + int32_t genMask[4] = {0}; if (ipAddr == NULL || netMask == NULL) { USER_LOG_ERROR("hal network config param error"); return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } + sscanf(ipAddr, "%d.%d.%d.%d", &routeIp[0], &routeIp[1], &routeIp[2], &routeIp[3]); + sscanf(netMask, "%d.%d.%d.%d", &genMask[0], &genMask[1], &genMask[2], &genMask[3]); + routeIp[0] &= genMask[0]; + routeIp[1] &= genMask[1]; + routeIp[2] &= genMask[2]; + routeIp[3] &= genMask[3]; + //Attention: need root permission to config ip addr and netmask. memset(cmdStr, 0, sizeof(cmdStr)); snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s up", LINUX_NETWORK_DEV); + USER_LOG_DEBUG("%s", cmdStr); ret = system(cmdStr); if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Can't open the network." @@ -61,14 +72,34 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe } snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s %s netmask %s", LINUX_NETWORK_DEV, ipAddr, netMask); + USER_LOG_DEBUG("%s", cmdStr); ret = system(cmdStr); if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - USER_LOG_ERROR("Can't config the ip address of network." - "Probably the program not execute with root permission." - "Please use the root permission to execute the program."); + USER_LOG_ERROR("cmd failed: %s", cmdStr); return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } + osalHandler->TaskSleepMs(50); + + snprintf(cmdStr, sizeof(cmdStr), "ip route flush dev %s", LINUX_NETWORK_DEV); + USER_LOG_DEBUG("%s", cmdStr); + ret = system(cmdStr); + if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("cmd failed: %s", cmdStr); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + snprintf(cmdStr, sizeof(cmdStr), "route add -net %d.%d.%d.%d netmask %s dev %s", + routeIp[0], routeIp[1], routeIp[2], routeIp[3], netMask, LINUX_NETWORK_DEV); + USER_LOG_DEBUG("%s", cmdStr); + ret = system(cmdStr); + if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("cmd failed: %s", cmdStr); + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + osalHandler->TaskSleepMs(50); + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } diff --git a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_uart.c b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_uart.c index 5cf5727..b5c4118 100644 --- a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_uart.c +++ b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_uart.c @@ -255,6 +255,18 @@ T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *stat return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo) +{ + if (deviceInfo == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + deviceInfo->vid = USB_UART_CONNECTED_TO_UAV_VID; + deviceInfo->pid = USB_UART_CONNECTED_TO_UAV_PID; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + /* Private functions definition-----------------------------------------------*/ /****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_uart.h b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_uart.h index a7f4db7..d732538 100644 --- a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_uart.h +++ b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_uart.h @@ -48,6 +48,15 @@ extern "C" { #define LINUX_UART_DEV1 "/dev/ttyAMA1" #define LINUX_UART_DEV2 "/dev/ttyAMA2" +/** + * Use for Eport 2.0, specify the VID and PID of the USB serial port closest to the aircraft. + * FT232 0x0403:0x6001 + * CP2102 0x10C4:0xEA60 + * VCOM 0x2CA3:0xF002 + */ +#define USB_UART_CONNECTED_TO_UAV_VID (0x0403) +#define USB_UART_CONNECTED_TO_UAV_PID (0x6001) + /* Exported types ------------------------------------------------------------*/ /* Exported functions --------------------------------------------------------*/ @@ -56,6 +65,7 @@ T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle); T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status); +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo); #ifdef __cplusplus } diff --git a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_usb_bulk.c b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_usb_bulk.c index 287d61e..85c5d72 100644 --- a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_usb_bulk.c +++ b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_usb_bulk.c @@ -107,6 +107,16 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } + } else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) { + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + ((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR); + if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } } } @@ -230,6 +240,10 @@ T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo) deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN; deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN; + deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT; + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } diff --git a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_usb_bulk.h b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_usb_bulk.h index 48ad1c7..bfc2654 100644 --- a/samples/sample_c/platform/linux/raspberry_pi/hal/hal_usb_bulk.h +++ b/samples/sample_c/platform/linux/raspberry_pi/hal/hal_usb_bulk.h @@ -65,8 +65,15 @@ extern "C" { #define LINUX_USB_BULK2_END_POINT_IN (0x82) #define LINUX_USB_BULK2_END_POINT_OUT (0x02) -#define LINUX_USB_VID (0x0955) -#define LINUX_USB_PID (0x7020) +#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep1" +#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep2" + +#define LINUX_USB_BULK3_INTERFACE_NUM (2) +#define LINUX_USB_BULK3_END_POINT_IN (0x83) +#define LINUX_USB_BULK3_END_POINT_OUT (0x03) + +#define LINUX_USB_VID (0x2CA3) +#define LINUX_USB_PID (0xF001) /* Exported types ------------------------------------------------------------*/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/README.txt b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/README.txt new file mode 100644 index 0000000..a3fad9e --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/README.txt @@ -0,0 +1,19 @@ +Payload SDK RTOS Sample. + +Test Environment: +Hardware: GD32F527ZMT7 (External Crystal Frequency: 12MHz) +IDE: Keil MDK v5.26.2.0 +C Compiler: Armcc.exe V5.06 update 6 (build 750) +Assembler: Armasm.exe V5.06 update 6 (build 750) +Linker/Locator: ArmLink.exe V5.06 update 6 (build 750) +Library Manager: ArmAr.exe V5.06 update 6 (build 750) +Hex Converter: FromElf.exe V5.06 update 6 (build 750) + +Pin Definition: +Console UART: PA9(TX), PA10(RX) +Communication UART: PA2(TX), PA3(RX) +Interactive UART: PD8(TX), PD9(RX) +PPS PIN: PD2 + +Console Configuration: +Baud Rate: 921600 diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/FreeRTOSConfig.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/FreeRTOSConfig.h new file mode 100644 index 0000000..59c42e1 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/FreeRTOSConfig.h @@ -0,0 +1,167 @@ +/* + FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd. + All rights reserved + + VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION. + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception. + + *************************************************************************** + >>! NOTE: The modification to the GPL is included to allow you to !<< + >>! distribute a combined work that includes FreeRTOS without being !<< + >>! obliged to provide the source code for proprietary components !<< + >>! outside of the FreeRTOS kernel. !<< + *************************************************************************** + + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY + WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS + FOR A PARTICULAR PURPOSE. Full license text is available on the following + link: http://www.freertos.org/a00114.html + + *************************************************************************** + * * + * FreeRTOS provides completely free yet professionally developed, * + * robust, strictly quality controlled, supported, and cross * + * platform software that is more than just the market leader, it * + * is the industry's de facto standard. * + * * + * Help yourself get started quickly while simultaneously helping * + * to support the FreeRTOS project by purchasing a FreeRTOS * + * tutorial book, reference manual, or both: * + * http://www.FreeRTOS.org/Documentation * + * * + *************************************************************************** + + http://www.FreeRTOS.org/FAQHelp.html - Having a problem? Start by reading + the FAQ page "My application does not run, what could be wrong?". Have you + defined configASSERT()? + + http://www.FreeRTOS.org/support - In return for receiving this top quality + embedded software for free we request you assist our global community by + participating in the support forum. + + http://www.FreeRTOS.org/training - Investing in training allows your team to + be as productive as possible as early as possible. Now you can receive + FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers + Ltd, and the world's leading authority on the world's leading RTOS. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool, a DOS + compatible FAT file system, and our tiny thread aware UDP/IP stack. + + http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate. + Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS. + + http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High + Integrity Systems ltd. to sell under the OpenRTOS brand. Low cost OpenRTOS + licenses offer ticketed support, indemnification and commercial middleware. + + http://www.SafeRTOS.com - High Integrity Systems also provide a safety + engineered and independently SIL3 certified version for use in safety and + mission critical applications that require provable dependability. + + 1 tab == 4 spaces! +*/ + + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +#if defined(__ICCARM__) || defined(__CC_ARM) || defined(__TASKING__) || defined(__GNUC__) +#include +extern uint32_t SystemCoreClock; +#endif + +/* Cortex M33 port configuration. */ +#define configENABLE_MPU 0 +#define configENABLE_FPU 1 +#define configENABLE_TRUSTZONE 0 + +#define configUSE_PREEMPTION 1 +#define configCPU_CLOCK_HZ ( SystemCoreClock ) +#define configTICK_RATE_HZ ( ( TickType_t ) 1000 ) +#define configMAX_PRIORITIES ( 8 ) +#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 130 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 80 * 1024 ) ) +#define configMAX_TASK_NAME_LEN ( 16 ) +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 1 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 1 +#define configQUEUE_REGISTRY_SIZE 8 +#define configUSE_APPLICATION_TASK_TAG 0 + + +/* hook function related definitions */ +#define configUSE_IDLE_HOOK 0 +#define configUSE_TICK_HOOK 0 +#define configCHECK_FOR_STACK_OVERFLOW 0 +#define configUSE_MALLOC_FAILED_HOOK 0 + +/* run time and task stats gathering related definitions */ +#define configGENERATE_RUN_TIME_STATS 0 +#define configUSE_TRACE_FACILITY 1 + + +/* 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 ( 2 ) +#define configTIMER_QUEUE_LENGTH 10 +#define configTIMER_TASK_STACK_DEPTH ( configMINIMAL_STACK_SIZE * 2 ) + +/* set to 1 to include the API function, or 0 to exclude the API function */ +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 0 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 + + + + +/* Cortex-M specific definitions */ +#ifdef __NVIC_PRIO_BITS + /* __NVIC_PRIO_BITS will be specified when CMSIS is being used. */ + #define configPRIO_BITS __NVIC_PRIO_BITS +#else + #define configPRIO_BITS 4 /* 15 priority levels */ +#endif + +/* the lowest interrupt priority that can be used in a call to a "set priority" function */ +#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 0xf + +/* The highest interrupt priority that can be used by any interrupt service +routine that makes calls to interrupt safe FreeRTOS API functions. Do not call +interrupt safe freertos api functions from any interrupt that has a higher +priority than this! (higher priorities are lower numeric values. */ +#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 2 + +/* interrupt priorities used by the kernel port layer itself */ +#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) +/* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) + + + +/* normal assert() semantics without relying on the provision of an assert.h header file */ +#define configASSERT( x ) if( ( x ) == 0 ) { taskDISABLE_INTERRUPTS(); for( ;; ); } + +/* map the FreeRTOS port interrupt handlers to CMSIS standard names */ +#define vPortSVCHandler SVC_Handler +#define xPortPendSVHandler PendSV_Handler +#define xPortSysTickHandler SysTick_Handler + + + +#endif /* FREERTOS_CONFIG_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/application.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/application.c new file mode 100644 index 0000000..adb6514 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/application.c @@ -0,0 +1,502 @@ +/** + ******************************************************************** + * @file application.c + * @date 2019/8/23 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include "FreeRTOS.h" +#include "FreeRTOSConfig.h" +#include "task.h" +#include "led.h" +#include "pps.h" +#include "apply_high_power.h" +#include "uart.h" +#include "flash_if.h" +#include "upgrade_platform_opt_gd32.h" + +#include "application.h" +#include "hal_uart.h" +#include "osal.h" +#include "dji_sdk_app_info.h" +#include "dji_sdk_config.h" +#include "dji_core.h" +#include "dji_aircraft_info.h" +#include "dji_logger.h" + +#include "utils/util_misc.h" +#include "camera_emu/test_payload_cam_emu_base.h" +#include "fc_subscription/test_fc_subscription.h" +#include "gimbal_emu/test_payload_gimbal_emu.h" +#include "xport/test_payload_xport.h" +#include "payload_collaboration/test_payload_collaboration.h" +#include "widget/test_widget.h" +#include "widget_interaction_test/test_widget_interaction.h" +#include "data_transmission/test_data_transmission.h" +#include "time_sync/test_time_sync.h" +#include "positioning/test_positioning.h" +#include "upgrade/test_upgrade.h" +#include "power_management/test_power_management.h" +#include "tethered_battery/test_tethered_battery.h" + +/* Private constants ---------------------------------------------------------*/ +#define RUN_INDICATE_TASK_FREQ_1HZ 1 +#define RUN_INDICATE_TASK_FREQ_0D1HZ 0.1f + +#define DJI_USE_WIDGET_INTERACTION 0 + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static bool s_isApplicationStart = false; + +/* Private functions declaration ---------------------------------------------*/ +static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen); +static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo); + +/* Exported functions definition ---------------------------------------------*/ +void DjiUser_StartTask(void const *argument) +{ + T_DjiReturnCode returnCode; + T_DjiUserInfo userInfo; + T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo; + T_DjiOsalHandler osalHandler = { + .TaskCreate = Osal_TaskCreate, + .TaskDestroy = Osal_TaskDestroy, + .TaskSleepMs = Osal_TaskSleepMs, + .MutexCreate= Osal_MutexCreate, + .MutexDestroy = Osal_MutexDestroy, + .MutexLock = Osal_MutexLock, + .MutexUnlock = Osal_MutexUnlock, + .SemaphoreCreate = Osal_SemaphoreCreate, + .SemaphoreDestroy = Osal_SemaphoreDestroy, + .SemaphoreWait = Osal_SemaphoreWait, + .SemaphoreTimedWait = Osal_SemaphoreTimedWait, + .SemaphorePost = Osal_SemaphorePost, + .Malloc = Osal_Malloc, + .Free = Osal_Free, + .GetTimeMs = Osal_GetTimeMs, + .GetTimeUs = Osal_GetTimeUs, + .GetRandomNum = Osal_GetRandomNum, + }; + T_DjiLoggerConsole printConsole = { + .func = DjiUser_PrintConsole, + .consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO, + .isSupportColor = true, + }; + T_DjiHalUartHandler uartHandler = { + .UartInit = HalUart_Init, + .UartDeInit = HalUart_DeInit, + .UartWriteData = HalUart_WriteData, + .UartReadData = HalUart_ReadData, + .UartGetStatus = HalUart_GetStatus, + .UartGetDeviceInfo = HalUart_GetDeviceInfo, + }; + T_DjiFirmwareVersion firmwareVersion = { + .majorVersion = USER_FIRMWARE_MAJOR_VERSION, + .minorVersion = USER_FIRMWARE_MINOR_VERSION, + .modifyVersion = USER_FIRMWARE_MODIFY_VERSION, + .debugVersion = USER_FIRMWARE_DEBUG_VERSION, + }; + + returnCode = DjiPlatform_RegOsalHandler(&osalHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register osal handler error"); + goto out; + } + + returnCode = DjiPlatform_RegHalUartHandler(&uartHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("register hal uart handler error"); + goto out; + } + + returnCode = DjiLogger_AddConsole(&printConsole); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("add printf console error"); + goto out; + } + + returnCode = DjiUser_FillInUserInfo(&userInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("fill user info error, please check user info config"); + goto out; + } + + returnCode = DjiCore_Init(&userInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("core init error"); + goto out; + } + + returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("get aircraft base info error"); + goto out; + } + + returnCode = DjiCore_SetAlias("PSDK_APPALIAS"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("set alias error"); + goto out; + } + + returnCode = DjiCore_SetFirmwareVersion(firmwareVersion); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("set firmware version error"); + goto out; + } + + returnCode = DjiCore_SetSerialNumber("PSDK12345678XX"); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("set serial number error"); + goto out; + } + +#ifdef CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON + T_DjiTestApplyHighPowerHandler applyHighPowerHandler = { + .pinInit = DjiTest_HighPowerApplyPinInit, + .pinWrite = DjiTest_WriteHighPowerApplyPin, + }; + + returnCode = DjiTest_RegApplyHighPowerHandler(&applyHighPowerHandler); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("register apply high power handler error"); + } + + returnCode = DjiTest_PowerManagementStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("power management init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_WIDGET_ON + returnCode = DjiTest_WidgetStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget sample init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON + returnCode = DjiTest_WidgetSpeakerStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget speaker sample init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON + returnCode = DjiTest_DataTransmissionStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("widget sample init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON + returnCode = DjiTest_FcSubscriptionStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("data subscription sample init error\n"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_HMS_CUSTOMIZATION_ON + returnCode = DjiTest_HmsCustomizationStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("hms test init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_CAMERA_ON + if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK + && aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) { + USER_LOG_WARN("Not support camera emu sample."); + } else { + returnCode = DjiTest_CameraEmuBaseStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("camera emu common init error"); + } + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON + if ((aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK || + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) + && aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) { + USER_LOG_WARN("Not support gimbal emu sample."); + } else { + if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 || + aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) { + if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk gimbal init error"); + } + } + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_XPORT_ON + if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) { + if (DjiTest_XPortStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk xport init error"); + } + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_PAYLOAD_COLLABORATION_ON + if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT) { + returnCode = DjiTest_PayloadCollaborationStartService(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("Payload collaboration sample init error\n"); + } + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_TIME_SYNC_ON + T_DjiTestTimeSyncHandler testTimeSyncHandler = { + .PpsSignalResponseInit = DjiTest_PpsSignalResponseInit, + .GetNewestPpsTriggerLocalTimeUs = DjiTest_GetNewestPpsTriggerLocalTimeUs, + }; + + if (DjiTest_TimeSyncRegHandler(&testTimeSyncHandler) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("regsiter time sync handler error"); + goto out; + } + + if (DjiTest_TimeSyncStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk time sync init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_POSITIONING_ON + if (aircraftInfoBaseInfo.mountPositionType == DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT || + aircraftInfoBaseInfo.mountPositionType == DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT_V2) { + if (DjiTest_PositioningStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk positioning init error"); + } + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_UPGRADE_ON + T_DjiTestUpgradePlatformOpt Gd32UpgradePlatformOpt = { + .rebootSystem = DjiUpgradePlatformGd32_RebootSystem, + .cleanUpgradeProgramFileStoreArea = DjiUpgradePlatformGd32_CleanUpgradeProgramFileStoreArea, + .createUpgradeProgramFile = DjiUpgradePlatformGd32_CreateUpgradeProgramFile, + .writeUpgradeProgramFile = DjiUpgradePlatformGd32_WriteUpgradeProgramFile, + .readUpgradeProgramFile = DjiUpgradePlatformGd32_ReadUpgradeProgramFile, + .closeUpgradeProgramFile = DjiUpgradePlatformGd32_CloseUpgradeProgramFile, + .replaceOldProgram = DjiUpgradePlatformGd32_ReplaceOldProgram, + .setUpgradeRebootState = DjiUpgradePlatformGd32_SetUpgradeRebootState, + .getUpgradeRebootState = DjiUpgradePlatformGd32_GetUpgradeRebootState, + .cleanUpgradeRebootState = DjiUpgradePlatformGd32_CleanUpgradeRebootState, + }; + T_DjiTestUpgradeConfig testUpgradeConfig = { + .firmwareVersion = { + USER_FIRMWARE_MAJOR_VERSION, + USER_FIRMWARE_MINOR_VERSION, + USER_FIRMWARE_MODIFY_VERSION, + USER_FIRMWARE_DEBUG_VERSION + }, + .transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP, + .needReplaceProgramBeforeReboot = false + }; + if (DjiTest_UpgradeStartService(&Gd32UpgradePlatformOpt, testUpgradeConfig) != + DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + printf("psdk upgrade init error"); + } +#endif + +#ifdef CONFIG_MODULE_SAMPLE_TETHERED_BATTERY_ON + if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE) { + if (DjiTest_TetheredBatteryStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("psdk tethered battery sample init error"); + } + } +#endif + + returnCode = DjiCore_ApplicationStart(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + USER_LOG_ERROR("start sdk application error"); + } + + s_isApplicationStart = true; + + while (1) { + Osal_TaskSleepMs(500); + Led_Trigger(LED_GREEN); + } + +out: + while (1) { + USER_LOG_ERROR("Eport 2.0 Development Board sample init failed."); + Osal_TaskSleepMs(250); + Led_Trigger(LED_RED); + } + vTaskDelete(xTaskGetCurrentTaskHandle()); +} + +#ifndef __CC_ARM +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wmissing-noreturn" +#pragma GCC diagnostic ignored "-Wreturn-type" +#endif + +void DjiUser_MonitorTask(void const *argument) +{ + static uint32_t runIndicateTaskStep = 0; + T_UartBufferState readBufferState = {0}; + T_UartBufferState writeBufferState = {0}; + T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); +#if (configUSE_TRACE_FACILITY == 1) + int32_t i = 0; + int32_t j = 0; + TaskStatus_t *lastTaskStatusArray = NULL; + TaskStatus_t *currentTaskStatusArray = NULL; + uint8_t lastTaskStatusArraySize = 0; + uint8_t currentTaskStatusArraySize; + uint8_t cpuOccupyPercentage; +#endif + + while (1) { + Osal_TaskSleepMs(1000 / RUN_INDICATE_TASK_FREQ_0D1HZ); + + if (s_isApplicationStart == false) { + continue; + } + // report UART buffer state +#ifdef USING_UART_PORT_1 + UART_GetBufferState(UART_NUM_1, &readBufferState, &writeBufferState); + USER_LOG_DEBUG("Uart1 read buffer state: countOfLostData %d, maxUsedCapacityOfBuffer %d.", + readBufferState.countOfLostData, readBufferState.maxUsedCapacityOfBuffer); + USER_LOG_DEBUG("Uart1 write buffer state: countOfLostData %d, maxUsedCapacityOfBuffer %d.", + writeBufferState.countOfLostData, writeBufferState.maxUsedCapacityOfBuffer); +#endif + +#ifdef USING_UART_PORT_2 + UART_GetBufferState(UART_NUM_2, &readBufferState, &writeBufferState); + USER_LOG_DEBUG("Uart2 read buffer state: countOfLostData %d, maxUsedCapacityOfBuffer %d.", + readBufferState.countOfLostData, readBufferState.maxUsedCapacityOfBuffer); + USER_LOG_DEBUG("Uart2 write buffer state: countOfLostData %d, maxUsedCapacityOfBuffer %d.", + writeBufferState.countOfLostData, writeBufferState.maxUsedCapacityOfBuffer); +#endif + +#ifdef USING_UART_PORT_3 + UART_GetBufferState(UART_NUM_3, &readBufferState, &writeBufferState); + USER_LOG_DEBUG("Uart3 read buffer state: countOfLostData %d, maxUsedCapacityOfBuffer %d.", + readBufferState.countOfLostData, readBufferState.maxUsedCapacityOfBuffer); + USER_LOG_DEBUG("Uart3 write buffer state: countOfLostData %d, maxUsedCapacityOfBuffer %d.", + writeBufferState.countOfLostData, writeBufferState.maxUsedCapacityOfBuffer); +#endif + + // report system performance information. + // Attention: report system performance part is not intended for normal application runtime use but as a debug aid. + if (USER_UTIL_IS_WORK_TURN(runIndicateTaskStep++, RUN_INDICATE_TASK_FREQ_0D1HZ, + RUN_INDICATE_TASK_FREQ_1HZ)) { +#if (configUSE_TRACE_FACILITY == 1) + currentTaskStatusArraySize = uxTaskGetNumberOfTasks(); + currentTaskStatusArray = osalHandler->Malloc(currentTaskStatusArraySize * sizeof(TaskStatus_t)); + if (currentTaskStatusArray == NULL) { + continue; + } + + currentTaskStatusArraySize = uxTaskGetSystemState(currentTaskStatusArray, currentTaskStatusArraySize, NULL); + USER_LOG_DEBUG("task information:"); + USER_LOG_DEBUG("task name\trun time (%%)\tstack left (byte)\tnumber"); + for (i = 0; i < currentTaskStatusArraySize; i++) { + cpuOccupyPercentage = 0; + for (j = 0; j < lastTaskStatusArraySize; ++j) { + if (currentTaskStatusArray[i].xTaskNumber == lastTaskStatusArray[j].xTaskNumber) { + cpuOccupyPercentage = + (currentTaskStatusArray[i].ulRunTimeCounter - lastTaskStatusArray[j].ulRunTimeCounter) / + configTICK_RATE_HZ / RUN_INDICATE_TASK_FREQ_0D1HZ; + break; + } + } + USER_LOG_DEBUG("%-16s\t%u\t%u\t%u", currentTaskStatusArray[i].pcTaskName, cpuOccupyPercentage, + (unsigned int) currentTaskStatusArray[i].usStackHighWaterMark * sizeof(StackType_t), + (unsigned int) currentTaskStatusArray[i].xTaskNumber); + } + osalHandler->Free(lastTaskStatusArray); + lastTaskStatusArray = currentTaskStatusArray; + lastTaskStatusArraySize = currentTaskStatusArraySize; +#endif + } + USER_LOG_INFO("Used heap size: %d/%d.\r\n", configTOTAL_HEAP_SIZE - xPortGetFreeHeapSize(), + configTOTAL_HEAP_SIZE); + } +} + +#ifndef __CC_ARM +#pragma GCC diagnostic pop +#endif + +/* Private functions definition-----------------------------------------------*/ +static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo) +{ + memset(userInfo->appName, 0, sizeof(userInfo->appName)); + memset(userInfo->appId, 0, sizeof(userInfo->appId)); + memset(userInfo->appKey, 0, sizeof(userInfo->appKey)); + memset(userInfo->appLicense, 0, sizeof(userInfo->appLicense)); + memset(userInfo->developerAccount, 0, sizeof(userInfo->developerAccount)); + memset(userInfo->baudRate, 0, sizeof(userInfo->baudRate)); + + if (strlen(USER_APP_NAME) >= sizeof(userInfo->appName) || + strlen(USER_APP_ID) > sizeof(userInfo->appId) || + strlen(USER_APP_KEY) > sizeof(userInfo->appKey) || + strlen(USER_APP_LICENSE) > sizeof(userInfo->appLicense) || + strlen(USER_DEVELOPER_ACCOUNT) >= sizeof(userInfo->developerAccount) || + strlen(USER_BAUD_RATE) > sizeof(userInfo->baudRate)) { + USER_LOG_ERROR("Length of user information string is beyond limit. Please check."); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + if (!strcmp(USER_APP_NAME, "your_app_name") || + !strcmp(USER_APP_ID, "your_app_id") || + !strcmp(USER_APP_KEY, "your_app_key") || + !strcmp(USER_APP_LICENSE, "your_app_license") || + !strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") || + !strcmp(USER_BAUD_RATE, "your_baud_rate")) { + USER_LOG_ERROR( + "Please fill in correct user information to 'samples/sample_c/platform/rtos_freertos/Gd32f4_discovery/application/dji_sdk_app_info.h' file."); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + strncpy(userInfo->appName, USER_APP_NAME, sizeof(userInfo->appName) - 1); + memcpy(userInfo->appId, USER_APP_ID, USER_UTIL_MIN(sizeof(userInfo->appId), strlen(USER_APP_ID))); + memcpy(userInfo->appKey, USER_APP_KEY, USER_UTIL_MIN(sizeof(userInfo->appKey), strlen(USER_APP_KEY))); + memcpy(userInfo->appLicense, USER_APP_LICENSE, + USER_UTIL_MIN(sizeof(userInfo->appLicense), strlen(USER_APP_LICENSE))); + memcpy(userInfo->baudRate, USER_BAUD_RATE, USER_UTIL_MIN(sizeof(userInfo->baudRate), strlen(USER_BAUD_RATE))); + strncpy(userInfo->developerAccount, USER_DEVELOPER_ACCOUNT, sizeof(userInfo->developerAccount) - 1); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen) +{ + UART_Write(DJI_CONSOLE_UART_NUM, (uint8_t *) data, dataLen); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +#ifdef __cplusplus +} +#endif +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/application.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/application.h new file mode 100644 index 0000000..ceff174 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/application.h @@ -0,0 +1,50 @@ +/** + ******************************************************************** + * @file application.h + * @date 2019/8/23 + * @brief This is the header file for "application.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef APPLICATION_H +#define APPLICATION_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +void DjiUser_StartTask(void const *argument); +void DjiUser_MonitorTask(void const *argument); + +#ifdef __cplusplus +} +#endif + +#endif // APPLICATION_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/dji_sdk_app_info.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/dji_sdk_app_info.h new file mode 100644 index 0000000..7330d8d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/dji_sdk_app_info.h @@ -0,0 +1,55 @@ +/** + ******************************************************************** + * @file dji_sdk_app_info.h + * @brief This is the header file for defining the structure and (exported) function prototypes. + * + * @copyright (c) 2018 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_SDK_APP_INFO_H +#define DJI_SDK_APP_INFO_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +// ATTENTION: User must goto https://developer.dji.com/user/apps/#all to create your own dji sdk application, get dji sdk application +// information then fill in the application information here. +#define USER_APP_NAME "your_app_name" +#define USER_APP_ID "your_app_id" +#define USER_APP_KEY "your_app_key" +#define USER_APP_LICENSE "your_app_license" +#define USER_DEVELOPER_ACCOUNT "your_developer_account" +#define USER_BAUD_RATE "460800" + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + + +#ifdef __cplusplus +} +#endif + +#endif // DJI_SDK_APP_INFO_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/dji_sdk_config.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/dji_sdk_config.h new file mode 100644 index 0000000..84b0d84 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/dji_sdk_config.h @@ -0,0 +1,80 @@ +/** + ******************************************************************** + * @file dji_sdk_config.h + * @brief This is the header file for "dji_config.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef DJI_SDK_CONFIG_H +#define DJI_SDK_CONFIG_H + +/* Includes ------------------------------------------------------------------*/ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON + +#define CONFIG_MODULE_SAMPLE_WIDGET_ON + +#define CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON + +#define CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON + +// #define CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON + +// #define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON + +// #define CONFIG_MODULE_SAMPLE_CAMERA_ON + +// #define CONFIG_MODULE_SAMPLE_XPORT_ON + +#define CONFIG_MODULE_SAMPLE_UPGRADE_ON + +#define CONFIG_MODULE_SAMPLE_HMS_CUSTOMIZATION_ON + +/*!< Attention: Please uncomment it in gps environment. +* */ +// #define CONFIG_MODULE_SAMPLE_TIME_SYNC_ON + +// #define CONFIG_MODULE_SAMPLE_POSITIONING_ON + +// #define CONFIG_MODULE_SAMPLE_TETHERED_BATTERY_ON + +#define USER_FIRMWARE_MAJOR_VERSION (1) +#define USER_FIRMWARE_MINOR_VERSION (0) +#define USER_FIRMWARE_MODIFY_VERSION (0) +#define USER_FIRMWARE_DEBUG_VERSION (99) + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + + +#ifdef __cplusplus +} +#endif + +#endif // DJI_SDK_CONFIG_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/main.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/main.c new file mode 100644 index 0000000..6cbfb37 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/application/main.c @@ -0,0 +1,128 @@ +/** + ******************************************************************** + * @file main.c + * @version V2.0.0 + * @date 2019/8/23 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ +#include "gd32f5xx.h" +#include "stdio.h" +#include "application.h" +#include "led.h" +#include "button.h" +#include "uart.h" +#include "pwm.h" +#include "pps.h" +#include "apply_high_power.h" +#include "gd32f5xx.h" +#include "stdint.h" +#include "FreeRTOS.h" +#include "task.h" +#include "usb_device.h" +#include "osal.h" + +/* Private constants ---------------------------------------------------------*/ +#define BSP_INIT_TASK_STACK_SIZE 512 +#define BSP_INIT_TASK_PRIORITY 0 +#define USER_START_TASK_STACK_SIZE 2048 +#define USER_START_TASK_PRIORITY 0 +#define USER_RUN_INDICATE_TASK_STACK_SIZE 256 +#define USER_RUN_INDICATE_TASK_PRIORITY 0 + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static TaskHandle_t bspInitTask; +static TaskHandle_t startTask; +static TaskHandle_t runIndicateTask; + +/* Private functions declaration ---------------------------------------------*/ +static void DjiUser_BspInitTask(void const *argument); + +/* Exported functions definition ---------------------------------------------*/ + +int main(void) +{ + /* configure 4 bits pre-emption priority */ + nvic_priority_group_set(NVIC_PRIGROUP_PRE4_SUB0); + + /* init task */ + xTaskCreate((TaskFunction_t)DjiUser_BspInitTask, "bsp_init_task", BSP_INIT_TASK_STACK_SIZE, + NULL, BSP_INIT_TASK_PRIORITY, (TaskHandle_t *)bspInitTask); + + /* Create start task */ + xTaskCreate((TaskFunction_t)DjiUser_StartTask, "start_task", USER_START_TASK_STACK_SIZE, + NULL, USER_START_TASK_PRIORITY, (TaskHandle_t *)startTask); + + /* Create runIndicate task */ + // xTaskCreate((TaskFunction_t)DjiUser_MonitorTask, "monitor_task", USER_RUN_INDICATE_TASK_STACK_SIZE, + // NULL, USER_RUN_INDICATE_TASK_PRIORITY, (TaskHandle_t *)runIndicateTask); + + /* start scheduler */ + vTaskStartScheduler(); + + /*Taken by the scheduler */ + for (;;) + ; +} + +void DjiUser_BspInitTask(void const *argument) +{ + uint32_t cnt = 0; + + // LED Init + Led_Init(LED_RED); + Led_Init(LED_GREEN); + Led_Init(LED_BLUE); + + // Debug UART Init + UART_Init(DJI_CONSOLE_UART_NUM, DJI_CONSOLE_UART_BAUD); + + // Force Loader button Init + Button_Init(BUTTON_KEY1, BUTTON_MODE_GPIO); + + // FTS Pin output Init + Pwm_Init(PWM_FTS, 400, 0); + + // PPS Init + DjiTest_PpsSignalResponseInit(); + + // USBD CDC Init + USBD_CDC_Init(); + + // Flash Option Config Init + FLASH_If_Init(); + + for (;;) + { + Osal_TaskSleepMs(1); + USBD_CDC_Handle(); + } +} + +/* retarget the C library printf function to the USART */ +int fputc(int ch, FILE *f) +{ + usart_data_transmit(UART3, (uint8_t)ch); + while (RESET == usart_flag_get(UART3, USART_FLAG_TBE)); + + return ch; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/common.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/common.c new file mode 100644 index 0000000..6f53006 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/common.c @@ -0,0 +1,178 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Src/common.c + * @author MCD Application Team + * @brief This file provides all the common functions. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ + +/** @addtogroup Gd32F4xx_IAP_Main + * @{ + */ + +/* Includes ------------------------------------------------------------------*/ +#include "common.h" +#include "main.h" +#include "uart.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** + * @brief Convert an Integer to a string + * @param p_str: The string output pointer + * @param intnum: The integer to be converted + * @retval None + */ +void Int2Str(uint8_t *p_str, uint32_t intnum) +{ + uint32_t i, divider = 1000000000, pos = 0, status = 0; + + for (i = 0; i < 10; i++) { + p_str[pos++] = (intnum / divider) + 48; + + intnum = intnum % divider; + divider /= 10; + if ((p_str[pos - 1] == '0') & (status == 0)) { + pos = 0; + } else { + status++; + } + } +} + +/** + * @brief Convert a string to an integer + * @param p_inputstr: The string to be converted + * @param p_intnum: The integer value + * @retval 1: Correct + * 0: Error + */ +uint32_t Str2Int(uint8_t *p_inputstr, uint32_t *p_intnum) +{ + uint32_t i = 0, res = 0; + uint32_t val = 0; + + if ((p_inputstr[0] == '0') && ((p_inputstr[1] == 'x') || (p_inputstr[1] == 'X'))) { + i = 2; + while ((i < 11) && (p_inputstr[i] != '\0')) { + if (ISVALIDHEX(p_inputstr[i])) { + val = (val << 4) + CONVERTHEX(p_inputstr[i]); + } else { + /* Return 0, Invalid input */ + res = 0; + break; + } + i++; + } + + /* valid result */ + if (p_inputstr[i] == '\0') { + *p_intnum = val; + res = 1; + } + } else /* max 10-digit decimal input */ + { + while ((i < 11) && (res != 1)) { + if (p_inputstr[i] == '\0') { + *p_intnum = val; + /* return 1 */ + res = 1; + } else if (((p_inputstr[i] == 'k') || (p_inputstr[i] == 'K')) && (i > 0)) { + val = val << 10; + *p_intnum = val; + res = 1; + } else if (((p_inputstr[i] == 'm') || (p_inputstr[i] == 'M')) && (i > 0)) { + val = val << 20; + *p_intnum = val; + res = 1; + } else if (ISVALIDDEC(p_inputstr[i])) + { + val = val * 10 + CONVERTDEC(p_inputstr[i]); + } + else + { + /* return 0, Invalid input */ + res = 0; + break; + } + i++; + } + } + + return res; +} + +/** + * @brief Print a string on the HyperTerminal + * @param p_string: The string to be printed + * @retval None + */ +void Serial_PutString(uint8_t *p_string) +{ + uint16_t length = 0; + + while (p_string[length] != '\0') + { + length++; + } + UART_Write(PSDK_CONSOLE_UART_NUM, p_string, length); +} + +/** + * @brief Transmit a byte to the HyperTerminal + * @param param The byte to be sent + * @retval HAL_StatusTypeDef HAL_OK if OK + */ +void Serial_PutByte( uint8_t param ) +{ + UART_Write(PSDK_CONSOLE_UART_NUM, ¶m, 1); +} +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/common.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/common.h new file mode 100644 index 0000000..9499db4 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/common.h @@ -0,0 +1,91 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Inc/common.h + * @author MCD Application Team + * @brief This file provides all the headers of the common functions. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __COMMON_H +#define __COMMON_H + +/* Includes ------------------------------------------------------------------*/ +#include "gd32f5xx.h" + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +#define FILE_NAME_LENGTH ((uint32_t)64) +/* Constants used by Serial Command Line Mode */ +#define TX_TIMEOUT ((uint32_t)100) +#define RX_TIMEOUT ((uint32_t)0xFFFFFFFF) + +/* Exported macro ------------------------------------------------------------*/ +#define IS_CAP_LETTER(c) (((c) >= 'A') && ((c) <= 'F')) +#define IS_LC_LETTER(c) (((c) >= 'a') && ((c) <= 'f')) +#define IS_09(c) (((c) >= '0') && ((c) <= '9')) +#define ISVALIDHEX(c) (IS_CAP_LETTER(c) || IS_LC_LETTER(c) || IS_09(c)) +#define ISVALIDDEC(c) IS_09(c) +#define CONVERTDEC(c) (c - '0') + +#define CONVERTHEX_ALPHA(c) (IS_CAP_LETTER(c) ? ((c) - 'A'+10) : ((c) - 'a'+10)) +#define CONVERTHEX(c) (IS_09(c) ? ((c) - '0') : CONVERTHEX_ALPHA(c)) +#define CRC16 ((uint8_t)0x43) /* 'C' == 0x43, request 16-bit CRC */ + +typedef enum +{ + COM_OK = 0x00, + COM_ERROR = 0x01, + COM_ABORT = 0x02, + COM_TIMEOUT = 0x03, + COM_DATA = 0x04, + COM_LIMIT = 0x05 +} COM_StatusTypeDef; + +/* Exported functions ------------------------------------------------------- */ +void Int2Str(uint8_t *p_str, uint32_t intnum); +uint32_t Str2Int(uint8_t *inputstr, uint32_t *intnum); +void Serial_PutString(uint8_t *p_string); +void Serial_PutByte(uint8_t param); + +#endif /* __COMMON_H */ + +/*******************(C)COPYRIGHT 2016 STMicroelectronics *****END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/main.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/main.c new file mode 100644 index 0000000..087a90d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/main.c @@ -0,0 +1,198 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Src/main.c + * @author MCD Application Team + * @brief Main program body + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ +/* Includes ------------------------------------------------------------------*/ +#include +#include +#include "main.h" +#include "menu.h" +#include "FreeRTOS.h" +#include "task.h" +#include +#include "osal.h" +#include "led.h" +#include "stdio.h" +#include "flash_if.h" + +/* Exported variables --------------------------------------------------------*/ +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define USER_START_TASK_STACK_SIZE 1024 +#define USER_START_TASK_PRIORITY 0 +#define USER_LED_TASK_STACK_SIZE 1024 +#define USER_LED_TASK_PRIORITY 0 + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +extern pFunction JumpToApplication; +extern uint32_t JumpAddress; +static T_DjiTaskHandle startTask; +static T_DjiTaskHandle ledTask; + +/* Private function prototypes -----------------------------------------------*/ +static void IAP_Init(void); +static void SystemClock_Config(void); +static void PsdkUser_StartTask(void const *argument); +static void PsdkUser_LedTask(void const *argument); + +/* Private functions ---------------------------------------------------------*/ + +/** + * @brief Main program. + * @param None + * @retval None + */ +int main(void) +{ + /* Configure 4 bits pre-emption priority */ + nvic_priority_group_set(NVIC_PRIGROUP_PRE4_SUB0); + + /* Create start task */ + xTaskCreate((TaskFunction_t) PsdkUser_StartTask, "start_task", USER_START_TASK_STACK_SIZE, + NULL, USER_START_TASK_PRIORITY, startTask); + + xTaskCreate((TaskFunction_t) PsdkUser_LedTask, "led_task", USER_LED_TASK_STACK_SIZE, + NULL, USER_LED_TASK_PRIORITY, ledTask); + + /* Start scheduler */ + vTaskStartScheduler(); + + /*Taken by the scheduler */ + for (;;); +} + +static void PsdkUser_StartTask(void const *argument) +{ + bool isUpgradeReboot; + T_DjiUpgradeEndInfo upgradeEndInfo; + T_DjiReturnCode returnCode; + + /* attention : Delay for power on button state check mistake */ + Osal_TaskSleepMs(50); + + /* Initialize Key Button mounted on Gd324xG-EVAL board */ + Button_Init(BUTTON_KEY1, BUTTON_MODE_GPIO); + + /* Initialize flash option config **/ + FLASH_If_Init(); + + IAP_Init(); + + /* Test if Key push-button1 is pressed */ + if (Button_GetState(BUTTON_KEY1) == 1) { + /* Execute the IAP driver in order to reprogram the Flash */ + /* Display main menu */ + Main_Menu(); + } else { + returnCode = DjiUpgradePlatformGd32_GetUpgradeRebootState(&isUpgradeReboot, &upgradeEndInfo); + printf("Reboot from upgrade flag is %d.\r\n", isUpgradeReboot); + Osal_TaskSleepMs(5); + + if (returnCode == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS && isUpgradeReboot == true && + upgradeEndInfo.upgradeEndState == DJI_UPGRADE_END_STATE_SUCCESS) { + //replace old program + printf("Start to replace the old program.\r\n"); + Osal_TaskSleepMs(5); + + returnCode = DjiUpgradePlatformGd32_ReplaceOldProgram(); + if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + upgradeEndInfo.upgradeEndState = DJI_UPGRADE_END_STATE_UNKNOWN_ERROR; + DjiUpgradePlatformGd32_SetUpgradeRebootState(&upgradeEndInfo); + } + } + + uint32_t addr = ((*(__IO uint32_t *) APPLICATION_ADDRESS) & 0x2FFE0000); + /* Test if user code is programmed starting from address "APPLICATION_ADDRESS" */ + printf("the initial SP of app is %08X\r\n", (*(__IO uint32_t *) APPLICATION_ADDRESS)); + Osal_TaskSleepMs(5); + + if (((*(__IO uint32_t *) APPLICATION_ADDRESS) & 0x2FFE0000) == 0x20020000) { + printf("jump to app at 0x%08X\r\n", APPLICATION_ADDRESS); + Osal_TaskSleepMs(5); + __disable_irq(); + __disable_fiq(); + /* Jump to user application */ + JumpAddress = *(__IO uint32_t *) (APPLICATION_ADDRESS + 4); + JumpToApplication = (pFunction) JumpAddress; + /* Initialize user application's Stack Pointer */ + __set_MSP(*(__IO uint32_t *) APPLICATION_ADDRESS); + JumpToApplication(); + } + } + + while (1) {} +} + +static void PsdkUser_LedTask(void const *argument) +{ + Led_Init(LED_BLUE); + + while (1) + { + Osal_TaskSleepMs(200); + Led_Trigger(LED_BLUE); + } +} +/** + * @brief Initialize the IAP: Configure USART. + * @param None + * @retval None + */ +static void IAP_Init(void) +{ + UART_Init(PSDK_CONSOLE_UART_NUM, PSDK_CONSOLE_UART_BAUD); +} + +/* retarget the C library printf function to the USART */ +int fputc(int ch, FILE *f) +{ + usart_data_transmit(UART3, (uint8_t)ch); + while (RESET == usart_flag_get(UART3, USART_FLAG_TBE)); + + return ch; +} + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/main.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/main.h new file mode 100644 index 0000000..7ad4541 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/main.h @@ -0,0 +1,64 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Inc/main.h + * @author MCD Application Team + * @brief Header for main.c module + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MAIN_H +#define __MAIN_H + +/* Includes ------------------------------------------------------------------*/ +#include "gd32f5xx.h" + +/* Exported variables --------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +#define PSDK_CONSOLE_UART_NUM UART_NUM_3 +#define PSDK_CONSOLE_UART_BAUD 921600 + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +#endif /* __MAIN_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/menu.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/menu.c new file mode 100644 index 0000000..498371a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/menu.c @@ -0,0 +1,228 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Src/menu.c + * @author MCD Application Team + + * @brief This file provides the software which contains the main menu routine. + * The main menu gives the options of: + * - downloading a new binary file, + * - uploading internal flash memory, + * - executing the binary file already loaded + * - configuring the write protection of the Flash sectors where the + * user loads his binary file. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ + +/** @addtogroup Gd32F4xx_IAP_Main + * @{ + */ + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" +#include "common.h" +#include "flash_if.h" +#include "menu.h" +#include "uart.h" +#include +#include + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +pFunction JumpToApplication; +uint32_t JumpAddress; +uint32_t FlashProtection = 0; +uint8_t aFileName[FILE_NAME_LENGTH]; + +/* Private function prototypes -----------------------------------------------*/ +void SerialDownload(void); +void SerialUpload(void); +int32_t Uart_ReadWithTimeOut(E_UartNum uartNum, uint8_t *data, uint16_t len, uint32_t timeOut); +int32_t Uart_WriteWithTimeOut(E_UartNum uartNum, uint8_t *data, uint16_t len, uint32_t timeOut); +extern COM_StatusTypeDef Ymodem_Receive(uint32_t *p_size); +extern COM_StatusTypeDef Ymodem_Transmit(uint8_t *p_buf, const uint8_t *p_file_name, uint32_t file_size); + +/* Private functions ---------------------------------------------------------*/ + +/** + * @brief Download a file via serial port + * @param None + * @retval None + */ +void SerialDownload(void) +{ + uint8_t number[11] = {0}; + uint32_t size = 0; + COM_StatusTypeDef result; + + Serial_PutString((uint8_t *) "Waiting for the file to be sent .f.. (press 'a' to abort)\n\r"); + result = Ymodem_Receive(&size); + if (result == COM_OK) { + Serial_PutString( + (uint8_t *) "\n\n\r Programming Completed Successfully!\n\r--------------------------------\r\n Name: "); + Serial_PutString(aFileName); + Int2Str(number, size); + Serial_PutString((uint8_t *) "\n\r Size: "); + Serial_PutString(number); + Serial_PutString((uint8_t *) " Bytes\r\n"); + Serial_PutString((uint8_t *) "-------------------\n"); + } else if (result == COM_LIMIT) { + Serial_PutString((uint8_t *) "\n\n\rThe image size is higher than the allowed space memory!\n\r"); + } else if (result == COM_DATA) { + Serial_PutString((uint8_t *) "\n\n\rVerification failed!\n\r"); + } else if (result == COM_ABORT) { + Serial_PutString((uint8_t *) "\r\n\nAborted by user.\n\r"); + } else { + Serial_PutString((uint8_t *) "\n\rFailed to receive the file!\n\r"); + } +} + +/** + * @brief Upload a file via serial port. + * @param None + * @retval None + */ +void SerialUpload(void) +{ + uint8_t status = 0; + + Serial_PutString((uint8_t *) "\n\n\rSelect Receive File\n\r"); + + Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &status, 1, RX_TIMEOUT); + if (status == CRC16) { + /* Transmit the flash image through ymodem protocol */ + status = Ymodem_Transmit((uint8_t *) APPLICATION_ADDRESS, (const uint8_t *) "UploadedFlashImage.bin", + APPLICATION_FLASH_SIZE); + + if (status != 0) { + Serial_PutString((uint8_t *) "\n\rError Occurred while Transmitting File\n\r"); + } else { + Serial_PutString((uint8_t *) "\n\rFile uploaded successfully \n\r"); + } + } +} + +/** + * @brief Display the Main Menu on HyperTerminal + * @param None + * @retval None + */ +void Main_Menu(void) +{ + uint8_t key = 0; + + Serial_PutString((uint8_t *) "\r\n======================================================================"); + Serial_PutString((uint8_t *) "\r\n= (C) COPYRIGHT 2016 STMicroelectronics ="); + Serial_PutString((uint8_t *) "\r\n= ="); + Serial_PutString((uint8_t *) "\r\n= Gd32F4xx In-Application Programming Application ="); + Serial_PutString((uint8_t *) "\r\n= ="); + Serial_PutString((uint8_t *) "\r\n= By MCD Application Team ="); + Serial_PutString((uint8_t *) "\r\n======================================================================"); + Serial_PutString((uint8_t *) "\r\n\r\n"); + + while (1) { + + /* Test if any sector of Flash memory where user application will be loaded is write protected */ + FlashProtection = FLASH_If_GetWriteProtectionStatus(); + + Serial_PutString((uint8_t *) "\r\n=================== Main Menu ============================\r\n\n"); + Serial_PutString((uint8_t *) " Download image to the internal Flash ----------------- 1\r\n\n"); + Serial_PutString((uint8_t *) " Upload image from the internal Flash ----------------- 2\r\n\n"); + Serial_PutString((uint8_t *) " Execute the loaded application ----------------------- 3\r\n\n"); + + if (FlashProtection != FLASHIF_PROTECTION_NONE) { + Serial_PutString((uint8_t *) " Disable the write protection ------------------------- 4\r\n\n"); + } else { + Serial_PutString((uint8_t *) " Enable the write protection -------------------------- 4\r\n\n"); + } + Serial_PutString((uint8_t *) "==========================================================\r\n\n"); + + /* Receive key */ + Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &key, 1, RX_TIMEOUT); + + switch (key) { + case '1' : + /* Download user application in the Flash */ + Serial_PutString((uint8_t *) "Start download app in the flash......\r\n\n"); + SerialDownload(); + break; + case '2' : + /* Upload user application from the Flash */ + Serial_PutString((uint8_t *) "Start upload app in the flash......\r\n\n"); + SerialUpload(); + break; + case '3' : + Serial_PutString((uint8_t *) "Reboot and start program execution......\r\n\n"); + Osal_TaskSleepMs(50); + DjiUpgradePlatformGd32_RebootSystem(); + break; + case '4' : + if (FlashProtection != FLASHIF_PROTECTION_NONE) { + /* Disable the write protection */ + if (FLASH_If_WriteProtectionConfig(false) == SUCCESS) { + Serial_PutString((uint8_t *) "Write Protection disabled...\r\n"); + Serial_PutString((uint8_t *) "System will now restart...\r\n"); + } else { + Serial_PutString((uint8_t *) "Error: Flash write un-protection failed...\r\n"); + } + } else { + if (FLASH_If_WriteProtectionConfig(true) == SUCCESS) { + Serial_PutString((uint8_t *) "Write Protection enabled...\r\n"); + Serial_PutString((uint8_t *) "System will now restart...\r\n"); + } else { + Serial_PutString((uint8_t *) "Error: Flash write protection failed...\r\n"); + } + } + break; + default: + Serial_PutString((uint8_t *) "Invalid Number ! ==> The number should be either 1, 2, 3 or 4\r"); + break; + } + } +} + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/menu.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/menu.h new file mode 100644 index 0000000..a9ec277 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/menu.h @@ -0,0 +1,69 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Inc/menu.h + * @author MCD Application Team + * @brief This file provides all the headers of the menu functions. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MENU_H +#define __MENU_H + +/* Includes ------------------------------------------------------------------*/ +#include "flash_if.h" +#include "common.h" + +/* Imported variables --------------------------------------------------------*/ +extern uint8_t aFileName[FILE_NAME_LENGTH]; + +/* Private variables ---------------------------------------------------------*/ +typedef void (*pFunction)(void); + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +void Main_Menu(void); + +#endif /* __MENU_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/ymodem.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/ymodem.c new file mode 100644 index 0000000..11ffeee --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/bootloader/ymodem.c @@ -0,0 +1,686 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Src/ymodem.c + * @author MCD Application Team + * @brief This file provides all the software functions related to the ymodem + * protocol. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ +/** @addtogroup Gd32F4xx_IAP_Main + * @{ + */ + +/* Includes ------------------------------------------------------------------*/ +#include "flash_if.h" +#include "common.h" +#include "string.h" +#include "main.h" +#include "menu.h" +#include "uart.h" +#include "osal.h" +#include "stdio.h" + +/* Private typedef -----------------------------------------------------------*/ +/** + * @brief HAL Status structures definition + */ +typedef enum +{ + HAL_OK = 0x00U, + HAL_ERROR = 0x01U, + HAL_BUSY = 0x02U, + HAL_TIMEOUT = 0x03U +} HAL_StatusTypeDef; + +/* Private define ------------------------------------------------------------*/ +/* Packet structure defines */ +#define PACKET_HEADER_SIZE ((uint32_t)3) +#define PACKET_DATA_INDEX ((uint32_t)4) +#define PACKET_START_INDEX ((uint32_t)1) +#define PACKET_NUMBER_INDEX ((uint32_t)2) +#define PACKET_CNUMBER_INDEX ((uint32_t)3) +#define PACKET_TRAILER_SIZE ((uint32_t)2) +#define PACKET_OVERHEAD_SIZE (PACKET_HEADER_SIZE + PACKET_TRAILER_SIZE - 1) +#define PACKET_SIZE ((uint32_t)128) +#define PACKET_1K_SIZE ((uint32_t)1024) + +/* /-------- Packet in IAP memory ------------------------------------------\ + * | 0 | 1 | 2 | 3 | 4 | ... | n+4 | n+5 | n+6 | + * |------------------------------------------------------------------------| + * | unused | start | number | !num | data[0] | ... | data[n] | crc0 | crc1 | + * \------------------------------------------------------------------------/ + * the first byte is left unused for memory alignment reasons */ +#define FILE_SIZE_LENGTH ((uint32_t)16) + +#define SOH ((uint8_t)0x01) /* start of 128-byte data packet */ +#define STX ((uint8_t)0x02) /* start of 1024-byte data packet */ +#define EOT ((uint8_t)0x04) /* end of transmission */ +#define ACK ((uint8_t)0x06) /* acknowledge */ +#define NAK ((uint8_t)0x15) /* negative acknowledge */ +#define CA ((uint32_t)0x18) /* two of these in succession aborts transfer */ +#define NEGATIVE_BYTE ((uint8_t)0xFF) + +#define ABORT1 ((uint8_t)0x41) /* 'A' == 0x41, abort by user */ +#define ABORT2 ((uint8_t)0x61) /* 'a' == 0x61, abort by user */ + +#define NAK_TIMEOUT ((uint32_t)0x100000) +#define DOWNLOAD_TIMEOUT ((uint32_t)5000) /* Five second retry delay */ +#define MAX_ERRORS ((uint32_t)5) +#define CRC16_F /* activate the CRC16 integrity */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +__IO uint32_t flashdestination; +/* @note ATTENTION - please keep this variable 32bit alligned */ +uint8_t aPacketData[PACKET_1K_SIZE + PACKET_DATA_INDEX + PACKET_TRAILER_SIZE]; + +/* Private function prototypes -----------------------------------------------*/ +static void PrepareIntialPacket(uint8_t *p_data, const uint8_t *p_file_name, uint32_t length); +static void PreparePacket(uint8_t *p_source, uint8_t *p_packet, uint8_t pkt_nr, uint32_t size_blk); +static int32_t ReceivePacket(uint8_t *p_data, uint32_t *p_length, uint32_t timeout); +uint16_t UpdateCRC16(uint16_t crc_in, uint8_t byte); +uint16_t Cal_CRC16(const uint8_t *p_data, uint32_t size); +uint8_t CalcChecksum(const uint8_t *p_data, uint32_t size); + +int32_t Uart_ReadWithTimeOut(E_UartNum uartNum, uint8_t *data, uint16_t len, uint32_t timeOut); +int32_t Uart_WriteWithTimeOut(E_UartNum uartNum, uint8_t *data, uint16_t len, uint32_t timeOut); + +/* Private functions ---------------------------------------------------------*/ + +/** + * @brief Receive a packet from sender + * @param data + * @param length + * 0: end of transmission + * 2: abort by sender + * >0: packet length + * @param timeout + * @retval HAL_OK: normally return + * HAL_BUSY: abort by user + */ +static int32_t ReceivePacket(uint8_t *p_data, uint32_t *p_length, uint32_t timeout) +{ + uint32_t crc; + uint32_t packet_size = 0; + int32_t status; + uint8_t char1; + + *p_length = 0; + status = Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &char1, 1, timeout); + + if (status == 0) { + switch (char1) { + case SOH: + packet_size = PACKET_SIZE; + break; + case STX: + packet_size = PACKET_1K_SIZE; + break; + case EOT: + break; + case CA: + if ((Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &char1, 1, timeout) == HAL_OK) && (char1 == CA)) { + packet_size = 2; + } else { + status = HAL_ERROR; + } + break; + case ABORT1: + case ABORT2: + status = HAL_BUSY; + break; + default: + status = HAL_ERROR; + break; + } + *p_data = char1; + + if (packet_size >= PACKET_SIZE) { + status = Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &p_data[PACKET_NUMBER_INDEX], + packet_size + PACKET_OVERHEAD_SIZE, + timeout); + + /* Simple packet sanity check */ + if (status == HAL_OK) { + if (p_data[PACKET_NUMBER_INDEX] != ((p_data[PACKET_CNUMBER_INDEX]) ^ NEGATIVE_BYTE)) { + packet_size = 0; + status = HAL_ERROR; + } else { + /* Check packet CRC */ + crc = p_data[packet_size + PACKET_DATA_INDEX] << 8; + crc += p_data[packet_size + PACKET_DATA_INDEX + 1]; + if (Cal_CRC16(&p_data[PACKET_DATA_INDEX], packet_size) != crc) { + packet_size = 0; + status = HAL_ERROR; + } + } + } else { + packet_size = 0; + } + } + } + *p_length = packet_size; + return status; +} + +/** + * @brief Prepare the first block + * @param p_data: output buffer + * @param p_file_name: name of the file to be sent + * @param length: length of the file to be sent in bytes + * @retval None + */ +static void PrepareIntialPacket(uint8_t *p_data, const uint8_t *p_file_name, uint32_t length) +{ + uint32_t i, j = 0; + uint8_t astring[10]; + + /* first 3 bytes are constant */ + p_data[PACKET_START_INDEX] = SOH; + p_data[PACKET_NUMBER_INDEX] = 0x00; + p_data[PACKET_CNUMBER_INDEX] = 0xff; + + /* Filename written */ + for (i = 0; (p_file_name[i] != '\0') && (i < FILE_NAME_LENGTH); i++) { + p_data[i + PACKET_DATA_INDEX] = p_file_name[i]; + } + + p_data[i + PACKET_DATA_INDEX] = 0x00; + + /* file size written */ + Int2Str(astring, length); + i = i + PACKET_DATA_INDEX + 1; + while (astring[j] != '\0') { + p_data[i++] = astring[j++]; + } + + /* padding with zeros */ + for (j = i; j < PACKET_SIZE + PACKET_DATA_INDEX; j++) { + p_data[j] = 0; + } +} + +/** + * @brief Prepare the data packet + * @param p_source: pointer to the data to be sent + * @param p_packet: pointer to the output buffer + * @param pkt_nr: number of the packet + * @param size_blk: length of the block to be sent in bytes + * @retval None + */ +static void PreparePacket(uint8_t *p_source, uint8_t *p_packet, uint8_t pkt_nr, uint32_t size_blk) +{ + uint8_t *p_record; + uint32_t i, size, packet_size; + + /* Make first three packet */ + packet_size = size_blk >= PACKET_1K_SIZE ? PACKET_1K_SIZE : PACKET_SIZE; + size = size_blk < packet_size ? size_blk : packet_size; + if (packet_size == PACKET_1K_SIZE) { + p_packet[PACKET_START_INDEX] = STX; + } else { + p_packet[PACKET_START_INDEX] = SOH; + } + p_packet[PACKET_NUMBER_INDEX] = pkt_nr; + p_packet[PACKET_CNUMBER_INDEX] = (~pkt_nr); + p_record = p_source; + + /* Filename packet has valid data */ + for (i = PACKET_DATA_INDEX; i < size + PACKET_DATA_INDEX; i++) { + p_packet[i] = *p_record++; + } + if (size <= packet_size) { + for (i = size + PACKET_DATA_INDEX; i < packet_size + PACKET_DATA_INDEX; i++) { + p_packet[i] = 0x1A; /* EOF (0x1A) or 0x00 */ + } + } +} + +/** + * @brief Update CRC16 for input byte + * @param crc_in input value + * @param input byte + * @retval None + */ +uint16_t UpdateCRC16(uint16_t crc_in, uint8_t byte) +{ + uint32_t crc = crc_in; + uint32_t in = byte | 0x100; + + do { + crc <<= 1; + in <<= 1; + if (in & 0x100) + ++crc; + if (crc & 0x10000) + crc ^= 0x1021; + } while (!(in & 0x10000)); + + return crc & 0xffffu; +} + +/** + * @brief Cal CRC16 for YModem Packet + * @param data + * @param length + * @retval None + */ +uint16_t Cal_CRC16(const uint8_t *p_data, uint32_t size) +{ + uint32_t crc = 0; + const uint8_t *dataEnd = p_data + size; + + while (p_data < dataEnd) + crc = UpdateCRC16(crc, *p_data++); + + crc = UpdateCRC16(crc, 0); + crc = UpdateCRC16(crc, 0); + + return crc & 0xffffu; +} + +/** + * @brief Calculate Check sum for YModem Packet + * @param p_data Pointer to input data + * @param size length of input data + * @retval uint8_t checksum value + */ +uint8_t CalcChecksum(const uint8_t *p_data, uint32_t size) +{ + uint32_t sum = 0; + const uint8_t *p_data_end = p_data + size; + + while (p_data < p_data_end) { + sum += *p_data++; + } + + return (sum & 0xffu); +} + +/* Public functions ---------------------------------------------------------*/ +/** + * @brief Receive a file using the ymodem protocol with CRC16. + * @param p_size The size of the file. + * @retval COM_StatusTypeDef result of reception/programming + */ +COM_StatusTypeDef Ymodem_Receive(uint32_t *p_size) +{ + uint32_t i, packet_length, session_done = 0, file_done, errors = 0, session_begin = 0; + // uint32_t flashdestination; + uint32_t ramsource, filesize, packets_received; + uint8_t *file_ptr; + uint8_t file_size[FILE_SIZE_LENGTH], tmp; + COM_StatusTypeDef result = COM_OK; + + /* Initialize flashdestination variable */ + flashdestination = APPLICATION_ADDRESS; + + while ((session_done == 0) && (result == COM_OK)) { + packets_received = 0; + file_done = 0; + while ((file_done == 0) && (result == COM_OK)) { + switch (ReceivePacket(aPacketData, &packet_length, DOWNLOAD_TIMEOUT)) { + case HAL_OK: + errors = 0; + switch (packet_length) { + case 2: + /* Abort by sender */ + Serial_PutByte(ACK); + result = COM_ABORT; + break; + case 0: + /* End of transmission */ + Serial_PutByte(ACK); + file_done = 1; + break; + default: + /* Normal packet */ + if (aPacketData[PACKET_NUMBER_INDEX] != (uint8_t) packets_received) { + Serial_PutByte(NAK); + } else { + if (packets_received == 0) { + /* File name packet */ + if (aPacketData[PACKET_DATA_INDEX] != 0) { + /* File name extraction */ + i = 0; + file_ptr = aPacketData + PACKET_DATA_INDEX; + while ((*file_ptr != 0) && (i < FILE_NAME_LENGTH)) { + aFileName[i++] = *file_ptr++; + } + + /* File size extraction */ + aFileName[i++] = '\0'; + i = 0; + file_ptr++; + while ((*file_ptr != ' ') && (i < FILE_SIZE_LENGTH)) { + file_size[i++] = *file_ptr++; + } + file_size[i++] = '\0'; + Str2Int(file_size, &filesize); + + /* Test the size of the image to be sent */ + /* Image size is greater than Flash size */ + if (*p_size > (APPLICATION_FLASH_SIZE + 1)) { + /* End session */ + tmp = CA; + Uart_WriteWithTimeOut(PSDK_CONSOLE_UART_NUM, &tmp, 1, NAK_TIMEOUT); + Uart_WriteWithTimeOut(PSDK_CONSOLE_UART_NUM, &tmp, 1, NAK_TIMEOUT); + result = COM_LIMIT; + } + /* erase user application area */ + FLASH_If_Erase(APPLICATION_ADDRESS, APPLICATION_ADDRESS_END); + *p_size = filesize; + + Serial_PutByte(ACK); + Serial_PutByte(CRC16); + } + /* File header packet is empty, end session */ + else { + Serial_PutByte(ACK); + file_done = 1; + session_done = 1; + break; + } + } else /* Data packet */ + { + ramsource = (uint32_t) &aPacketData[PACKET_DATA_INDEX]; + + /* Write received data in Flash */ + if (FLASH_If_Write(flashdestination, (uint8_t *) ramsource, packet_length) == + FLASHIF_OK) { + flashdestination += packet_length; + Serial_PutByte(ACK); + } else /* An error occurred while writing to Flash memory */ + { + /* End session */ + Serial_PutByte(CA); + Serial_PutByte(CA); + result = COM_DATA; + } + } + packets_received++; + session_begin = 1; + } + break; + } + break; + case HAL_BUSY: /* Abort actually */ + Serial_PutByte(CA); + Serial_PutByte(CA); + result = COM_ABORT; + break; + default: + if (session_begin > 0) { + errors++; + } + if (errors > MAX_ERRORS) { + /* Abort communication */ + Serial_PutByte(CA); + Serial_PutByte(CA); + } else { + Serial_PutByte(CRC16); /* Ask for a packet */ + } + break; + } + } + } + return result; +} + +/** + * @brief Transmit a file using the ymodem protocol + * @param p_buf: Address of the first byte + * @param p_file_name: Name of the file sent + * @param file_size: Size of the transmission + * @retval COM_StatusTypeDef result of the communication + */ +COM_StatusTypeDef Ymodem_Transmit(uint8_t *p_buf, const uint8_t *p_file_name, uint32_t file_size) +{ + uint32_t errors = 0, ack_recpt = 0, size = 0, pkt_size; + uint8_t *p_buf_int; + COM_StatusTypeDef result = COM_OK; + uint32_t blk_number = 1; + uint8_t a_rx_ctrl[2]; + uint8_t i; +#ifdef CRC16_F + uint32_t temp_crc; +#else /* CRC16_F */ + uint8_t temp_chksum; +#endif /* CRC16_F */ + + /* Prepare first block - header */ + PrepareIntialPacket(aPacketData, p_file_name, file_size); + + while ((!ack_recpt) && (result == COM_OK)) { + /* Send Packet */ + Uart_WriteWithTimeOut(PSDK_CONSOLE_UART_NUM, &aPacketData[PACKET_START_INDEX], PACKET_SIZE + PACKET_HEADER_SIZE, + NAK_TIMEOUT); + + /* Send CRC or Check Sum based on CRC16_F */ +#ifdef CRC16_F + temp_crc = Cal_CRC16(&aPacketData[PACKET_DATA_INDEX], PACKET_SIZE); + Serial_PutByte(temp_crc >> 8); + Serial_PutByte(temp_crc & 0xFF); +#else /* CRC16_F */ + temp_chksum = CalcChecksum (&aPacketData[PACKET_DATA_INDEX], PACKET_SIZE); + Serial_PutByte(temp_chksum); +#endif /* CRC16_F */ + + /* Wait for Ack and 'C' */ + if (Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &a_rx_ctrl[0], 1, NAK_TIMEOUT) == HAL_OK) { + if (a_rx_ctrl[0] == ACK) { + ack_recpt = 1; + } else if (a_rx_ctrl[0] == CA) { + if ((Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &a_rx_ctrl[0], 1, NAK_TIMEOUT) == HAL_OK) && + (a_rx_ctrl[0] == CA)) { + Osal_TaskSleepMs(2); + result = COM_ABORT; + } + } + } else { + errors++; + } + if (errors >= MAX_ERRORS) { + result = COM_ERROR; + } + } + + p_buf_int = p_buf; + size = file_size; + + /* Here 1024 bytes length is used to send the packets */ + while ((size) && (result == COM_OK)) { + /* Prepare next packet */ + PreparePacket(p_buf_int, aPacketData, blk_number, size); + ack_recpt = 0; + a_rx_ctrl[0] = 0; + errors = 0; + + /* Resend packet if NAK for few times else end of communication */ + while ((!ack_recpt) && (result == COM_OK)) { + /* Send next packet */ + if (size >= PACKET_1K_SIZE) { + pkt_size = PACKET_1K_SIZE; + } else { + pkt_size = PACKET_SIZE; + } + + Uart_WriteWithTimeOut(PSDK_CONSOLE_UART_NUM, &aPacketData[PACKET_START_INDEX], + pkt_size + PACKET_HEADER_SIZE, + NAK_TIMEOUT); + + /* Send CRC or Check Sum based on CRC16_F */ +#ifdef CRC16_F + temp_crc = Cal_CRC16(&aPacketData[PACKET_DATA_INDEX], pkt_size); + Serial_PutByte(temp_crc >> 8); + Serial_PutByte(temp_crc & 0xFF); +#else /* CRC16_F */ + temp_chksum = CalcChecksum (&aPacketData[PACKET_DATA_INDEX], pkt_size); + Serial_PutByte(temp_chksum); +#endif /* CRC16_F */ + + /* Wait for Ack */ + if ((Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &a_rx_ctrl[0], 1, NAK_TIMEOUT) == HAL_OK) && + (a_rx_ctrl[0] == ACK)) { + ack_recpt = 1; + if (size > pkt_size) { + p_buf_int += pkt_size; + size -= pkt_size; + if (blk_number == (APPLICATION_FLASH_SIZE / PACKET_1K_SIZE)) { + result = COM_LIMIT; /* boundary error */ + } else { + blk_number++; + } + } else { + p_buf_int += pkt_size; + size = 0; + } + } else { + errors++; + } + + /* Resend packet if NAK for a count of 10 else end of communication */ + if (errors >= MAX_ERRORS) { + result = COM_ERROR; + } + } + } + + /* Sending End Of Transmission char */ + ack_recpt = 0; + a_rx_ctrl[0] = 0x00; + errors = 0; + while ((!ack_recpt) && (result == COM_OK)) { + Serial_PutByte(EOT); + + /* Wait for Ack */ + if (Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &a_rx_ctrl[0], 1, NAK_TIMEOUT) == HAL_OK) { + if (a_rx_ctrl[0] == ACK) { + ack_recpt = 1; + } else if (a_rx_ctrl[0] == CA) { + if ((Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &a_rx_ctrl[0], 1, NAK_TIMEOUT) == HAL_OK) && + (a_rx_ctrl[0] == CA)) { + Osal_TaskSleepMs(2); + result = COM_ABORT; + } + } + } else { + errors++; + } + + if (errors >= MAX_ERRORS) { + result = COM_ERROR; + } + } + + /* Empty packet sent - some terminal emulators need this to close session */ + if (result == COM_OK) { + /* Preparing an empty packet */ + aPacketData[PACKET_START_INDEX] = SOH; + aPacketData[PACKET_NUMBER_INDEX] = 0; + aPacketData[PACKET_CNUMBER_INDEX] = 0xFF; + for (i = PACKET_DATA_INDEX; i < (PACKET_SIZE + PACKET_DATA_INDEX); i++) { + aPacketData[i] = 0x00; + } + + /* Send Packet */ + Uart_WriteWithTimeOut(PSDK_CONSOLE_UART_NUM, &aPacketData[PACKET_START_INDEX], PACKET_SIZE + PACKET_HEADER_SIZE, + NAK_TIMEOUT); + + /* Send CRC or Check Sum based on CRC16_F */ +#ifdef CRC16_F + temp_crc = Cal_CRC16(&aPacketData[PACKET_DATA_INDEX], PACKET_SIZE); + Serial_PutByte(temp_crc >> 8); + Serial_PutByte(temp_crc & 0xFF); +#else /* CRC16_F */ + temp_chksum = CalcChecksum (&aPacketData[PACKET_DATA_INDEX], PACKET_SIZE); + Serial_PutByte(temp_chksum); +#endif /* CRC16_F */ + + /* Wait for Ack and 'C' */ + if (Uart_ReadWithTimeOut(PSDK_CONSOLE_UART_NUM, &a_rx_ctrl[0], 1, NAK_TIMEOUT) == HAL_OK) { + if (a_rx_ctrl[0] == CA) { + Osal_TaskSleepMs(2); + result = COM_ABORT; + } + } + } + + return result; /* file transmitted successfully */ +} + +int32_t Uart_ReadWithTimeOut(E_UartNum uartNum, uint8_t *data, uint16_t len, uint32_t timeOut) +{ + int res; + uint16_t alreadyReadLen = 0; + uint32_t loop_count = 0; + + while (loop_count <= timeOut) { + res = UART_Read(uartNum, data + alreadyReadLen, len - alreadyReadLen); + if (res > 0) { + alreadyReadLen += res; + } + if (alreadyReadLen == len) { + return HAL_OK; + } + Osal_TaskSleepMs(2); + loop_count++; + } + + return HAL_TIMEOUT; +} + +int32_t Uart_WriteWithTimeOut(E_UartNum uartNum, uint8_t *data, uint16_t len, uint32_t timeOut) +{ + int res; + + res = UART_Write(uartNum, data, len); + if (res == len) { + return HAL_OK; + } else { + return HAL_ERROR; + } +} +/** + * @} + */ + +/*******************(C)COPYRIGHT 2016 STMicroelectronics *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/apply_high_power.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/apply_high_power.c new file mode 100644 index 0000000..51751ab --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/apply_high_power.c @@ -0,0 +1,76 @@ +/** + ******************************************************************** + * @file apply_high_power.c + * @version V2.0.0 + * @date 2019/9/20 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "apply_high_power.h" +#include "gd32f5xx.h" + +/* Private constants ---------------------------------------------------------*/ +#define HIGH_POWER_APPLY_PORT GPIOA +#define HIGH_POWER_APPLY_PIN GPIO_PIN_7 +#define HIGH_POWER_APPLY_CLK RCU_GPIOA + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode DjiTest_HighPowerApplyPinInit(void) +{ + /* Enable the led clock */ + rcu_periph_clock_enable(HIGH_POWER_APPLY_CLK); + + /* Configure led GPIO port */ + gpio_mode_set(HIGH_POWER_APPLY_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, HIGH_POWER_APPLY_PIN); + gpio_output_options_set(HIGH_POWER_APPLY_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, HIGH_POWER_APPLY_PIN); + + GPIO_BOP(HIGH_POWER_APPLY_PORT) = HIGH_POWER_APPLY_PIN; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState) +{ + switch (pinState) { + case DJI_POWER_MANAGEMENT_PIN_STATE_RESET: + GPIO_BC(HIGH_POWER_APPLY_PORT) = HIGH_POWER_APPLY_PIN; + break; + case DJI_POWER_MANAGEMENT_PIN_STATE_SET: + GPIO_BOP(HIGH_POWER_APPLY_PORT) = HIGH_POWER_APPLY_PIN; + break; + default: + USER_LOG_ERROR("pin state unknown: %d.", pinState); + return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/apply_high_power.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/apply_high_power.h new file mode 100644 index 0000000..bfebdb5 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/apply_high_power.h @@ -0,0 +1,54 @@ +/** + ******************************************************************** + * @file apply_high_power.h + * @version V2.0.0 + * @date 2019/9/20 + * @brief This is the header file for "apply_high_power.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef APPLY_HIGH_POWER_H +#define APPLY_HIGH_POWER_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_core.h" +#include "dji_power_management.h" +#include "dji_logger.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode DjiTest_HighPowerApplyPinInit(void); +T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState); + +#ifdef __cplusplus +} +#endif + +#endif // APPLY_HIGH_POWER_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/button.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/button.c new file mode 100644 index 0000000..259e227 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/button.c @@ -0,0 +1,81 @@ +/** + ******************************************************************** + * @file button.c + * @version V1.0.0 + * @date 2019/01/01 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + + +/* Includes ------------------------------------------------------------------*/ +#include "button.h" +#include "gd32f5xx.h" + +/* Private constants ---------------------------------------------------------*/ +#define KEY1_BUTTON_PIN GPIO_PIN_2 +#define KEY1_BUTTON_GPIO_PORT GPIOE +#define KEY1_BUTTON_GPIO_CLK RCU_GPIOE + +#define FORCE_LOADER_PORT GPIOE +#define FORCE_LOADER_PIN GPIO_PIN_3 +#define FORCE_LOADER_CLK RCU_GPIOE + +/* Private types -------------------------------------------------------------*/ +static uint32_t KEY_PORT[BUTTON_NUM] = {KEY1_BUTTON_GPIO_PORT}; +static uint32_t KEY_PIN[BUTTON_NUM] = {KEY1_BUTTON_PIN}; +static rcu_periph_enum KEY_CLK[BUTTON_NUM] = {KEY1_BUTTON_GPIO_CLK}; + +/* Private functions declaration ---------------------------------------------*/ +void ForceLoader_PinInit(void) +{ + /* Enable the led clock */ + rcu_periph_clock_enable(FORCE_LOADER_CLK); + + /* Configure led GPIO port */ + gpio_mode_set(FORCE_LOADER_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, FORCE_LOADER_PIN); + gpio_output_options_set(FORCE_LOADER_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, FORCE_LOADER_PIN); + + GPIO_BOP(FORCE_LOADER_PORT) = FORCE_LOADER_PIN; +} + +/* Exported functions definition ---------------------------------------------*/ +void Button_Init(Button_TypeDef Button, ButtonMode_TypeDef Button_Mode) +{ + /* Configure force loader output pin */ + ForceLoader_PinInit(); + + /* Enable the key clock */ + rcu_periph_clock_enable(KEY_CLK[Button]); + rcu_periph_clock_enable(RCU_SYSCFG); + + /* Configure force loader input pin */ + gpio_mode_set(KEY_PORT[Button], GPIO_MODE_INPUT, GPIO_PUPD_NONE,KEY_PIN[Button]); +} + +uint32_t Button_GetState(Button_TypeDef Button) +{ + return gpio_input_bit_get(KEY_PORT[Button], KEY_PIN[Button]); +} + +/* Private functions definition-----------------------------------------------*/ + + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/button.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/button.h new file mode 100644 index 0000000..e909f44 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/button.h @@ -0,0 +1,64 @@ +/** + ******************************************************************** + * @file button.h + * @version V0.0.0 + * @date 2019/01/01 + * @brief This is the header file for "button.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef BUTTON_H +#define BUTTON_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include + +/* Exported constants --------------------------------------------------------*/ + + +/* Exported types ------------------------------------------------------------*/ +typedef enum +{ + BUTTON_MODE_GPIO = 0, +}ButtonMode_TypeDef; + +typedef enum +{ + BUTTON_KEY1 = 0, + BUTTON_NUM = 1, +}Button_TypeDef; + +/* Exported functions --------------------------------------------------------*/ +void Button_Init(Button_TypeDef Button, ButtonMode_TypeDef Button_Mode); +uint32_t Button_GetState(Button_TypeDef Button); + +#ifdef __cplusplus +} +#endif + +#endif // BUTTON_H + +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/can.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/can.c new file mode 100644 index 0000000..db2c4de --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/can.c @@ -0,0 +1,543 @@ +/** + ****************************************************************************** + * @file can.c + * @version V1.0.0 + * @date 2024/05/22 + * @brief The file define UART interface driver functions. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "can.h" +#include "dji_ringbuffer.h" +#include "FreeRTOS.h" +#include "task.h" +#include "osal.h" +#include "gd32f5xx.h" + +/* Private typedef -----------------------------------------------------------*/ + +/* Private define ------------------------------------------------------------*/ +// uart uart buffer size define +#define CAN0_READ_BUF_SIZE 1024 +#define CAN0_WRITE_BUF_SIZE 4096 +#define CAN1_READ_BUF_SIZE 8192 +#define CAN1_WRITE_BUF_SIZE 8192 + +/* Private macro -------------------------------------------------------------*/ + +/* Private variables ---------------------------------------------------------*/ +#ifdef USING_CAN0 +// CAN0 read ring buffer structure +static T_RingBuffer s_uart1ReadRingBuffer; +// CAN0 read buffer state +static T_CanBufferState s_uart1ReadBufferState; +static T_RingBuffer s_uart1WriteRingBuffer; +// CAN0 write buffer state +static T_CanBufferState s_uart1WriteBufferState; +// CAN0 read buffer +static uint8_t s_uart1ReadBuf[CAN0_READ_BUF_SIZE]; +// CAN0 write buffer +static uint8_t s_uart1WriteBuf[CAN0_WRITE_BUF_SIZE]; +// CAN0 mutex +static T_DjiMutexHandle s_can0Mutex; +#endif + +#ifdef USING_CAN1 +static T_RingBuffer s_can1ReadRingBuffer; +static T_CanBufferState s_can1ReadBufferState; +static T_RingBuffer s_can1WriteRingBuffer; +static T_CanBufferState s_can1WriteBufferState; +static uint8_t s_can1ReadBuf[CAN1_READ_BUF_SIZE]; +static uint8_t s_can1WriteBuf[CAN1_WRITE_BUF_SIZE]; +static T_DjiMutexHandle s_can1Mutex; +#endif + +/* Exported variables --------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** + * @brief UART initialization function. + * @param uartNum UART number to be initialized. + * @param baudRate UART baudrate. + * @return None. + */ +void CAN_Init(E_CanNum canNum) +{ + switch (canNum) + { + +#ifdef USING_CAN0 + case UART_NUM_1: + { + RingBuf_Init(&s_uart1ReadRingBuffer, s_uart1ReadBuf, UART1_READ_BUF_SIZE); + RingBuf_Init(&s_uart1WriteRingBuffer, s_uart1WriteBuf, UART1_WRITE_BUF_SIZE); + + rcu_periph_clock_enable(RCU_GPIOA); + rcu_periph_clock_enable(RCU_USART0); + + gpio_af_set(GPIOA, GPIO_AF_7, GPIO_PIN_9); + gpio_af_set(GPIOA, GPIO_AF_7, GPIO_PIN_10); + + /* configure USART Tx as alternate function push-pull */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_PULLUP, GPIO_PIN_9); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_9); + + /* configure USART Rx as alternate function push-pull */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_PULLUP, GPIO_PIN_10); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_10); + + nvic_irq_enable(USART0_IRQn, 0, 0); + + /* USART configure */ + usart_deinit(USART0); + usart_baudrate_set(USART0, baudRate); + usart_receive_config(USART0, USART_RECEIVE_ENABLE); + usart_transmit_config(USART0, USART_TRANSMIT_ENABLE); + usart_enable(USART0); + usart_interrupt_enable(USART0, USART_INT_RBNE); + + Osal_MutexCreate(&s_uart1Mutex); + } + break; +#endif + +#ifdef USING_CAN1 + case CAN_NUM_1: + { + RingBuf_Init(&s_can1ReadRingBuffer, s_can1ReadBuf, CAN1_READ_BUF_SIZE); + RingBuf_Init(&s_can1WriteRingBuffer, s_can1WriteBuf, CAN1_WRITE_BUF_SIZE); + + /* Enable CAN clock */ + rcu_periph_clock_enable(RCU_CAN0); + rcu_periph_clock_enable(RCU_CAN1); + rcu_periph_clock_enable(RCU_GPIOB); + + /* Configure CAN1 GPIO */ + gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_5); + gpio_mode_set(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_5); + gpio_af_set(GPIOB, GPIO_AF_9, GPIO_PIN_5); + + gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_6); + gpio_mode_set(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_6); + gpio_af_set(GPIOB, GPIO_AF_9, GPIO_PIN_6); + + can_parameter_struct can_parameter; + can_struct_para_init(CAN_INIT_STRUCT, &can_parameter); + can_deinit(CAN1); + + /* Initialize CAN parameters */ + can_parameter.time_triggered = DISABLE; + can_parameter.auto_bus_off_recovery = ENABLE; + can_parameter.auto_wake_up = DISABLE; + can_parameter.auto_retrans = ENABLE; + can_parameter.rec_fifo_overwrite = DISABLE; + can_parameter.trans_fifo_order = DISABLE; + can_parameter.working_mode = CAN_NORMAL_MODE; + /* Configure CAN0/1 baud rate 1MBps, sample point at 80% */ + can_parameter.resync_jump_width = CAN_BT_SJW_1TQ; + can_parameter.time_segment_1 = CAN_BT_BS1_7TQ; + can_parameter.time_segment_2 = CAN_BT_BS2_2TQ; + can_parameter.prescaler = 5; + /* Initialize CAN */ + can_init(CAN1, &can_parameter); + + /* initialize filter */ + can1_filter_start_bank(14); + + can_filter_mask_mode_init(0x12, 0x0000, CAN_STANDARD_FIFO0, 15); + nvic_irq_enable(CAN1_RX0_IRQn, 1, 0); + can_interrupt_enable(CAN1, CAN_INTEN_RFNEIE0); + + // nvic_irq_enable(CAN1_TX_IRQn, 1, 0); + // can_interrupt_enable(CAN1, CAN_INTEN_TMEIE); + + Osal_MutexCreate(&s_can1Mutex); + } + break; +#endif + default: + break; + } +} + +/** + * @brief Read UART data. + * @param uartNum UART number. + * @param buf Pointer to buffer used to store data. + * @param readSize Size of data to be read. + * @return Size of data read actually. + */ +int CAN_Read(E_CanNum canNum, uint8_t *buf, uint16_t readSize) +{ + uint16_t readRealSize; + + switch (canNum) + { +#ifdef USING_CAN0 + case CAN_NUM_0: + { + Osal_MutexLock(s_uart1Mutex); + readRealSize = RingBuf_Get(&s_uart1ReadRingBuffer, buf, readSize); + Osal_MutexUnlock(s_uart1Mutex); + } + break; +#endif + +#ifdef USING_CAN1 + case CAN_NUM_1: + { + Osal_MutexLock(s_can1Mutex); + readRealSize = RingBuf_Get(&s_can1ReadRingBuffer, buf, readSize); + Osal_MutexUnlock(s_can1Mutex); + } + break; +#endif + + default: + return CAN_ERROR; + } + + return readRealSize; +} + +/** + * @brief Write CAN data. + * @param canNum CAN number. + * @param buf Pointer to buffer used to store data. + * @param writeSize Size of data to be write. + * @return Size of data wrote actually. + */ +int CAN_Write(E_CanNum canNum, const uint8_t *buf, uint16_t writeSize) +{ + int writeRealLen; + uint16_t usedCapacityOfBuffer = 0; + can_trasnmit_message_struct transmit_message; + int32_t i = 0; + int32_t j = 0; + uint32_t packageCnt = 0; + uint32_t LastpackageSize = 0; + uint8_t mailBoxNum = 0; + + switch (canNum) + { + +#ifdef USING_CAN0 + case UART_NUM_1: + { + Osal_MutexLock(s_uart1Mutex); + writeRealLen = RingBuf_Put(&s_uart1WriteRingBuffer, buf, writeSize); + + /* enable USART TBE interrupt */ + usart_interrupt_enable(USART0, USART_INT_TBE); + usedCapacityOfBuffer = UART1_WRITE_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart1WriteRingBuffer); + s_uart1WriteBufferState.maxUsedCapacityOfBuffer = + usedCapacityOfBuffer > s_uart1WriteBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + : s_uart1WriteBufferState.maxUsedCapacityOfBuffer; + s_uart1WriteBufferState.countOfLostData += writeSize - writeRealLen; + Osal_MutexUnlock(s_uart1Mutex); + } + break; +#endif + +#ifdef USING_CAN1 + case CAN_NUM_1: + { + // Osal_MutexLock(s_can1Mutex); + + can_struct_para_init(CAN_TX_MESSAGE_STRUCT, &transmit_message); + transmit_message.tx_efid = 0x00; + transmit_message.tx_ft = CAN_FT_DATA; + transmit_message.tx_ff = CAN_FF_STANDARD; + + packageCnt = writeSize / 8; + LastpackageSize = writeSize % 8; + + for (i = 0; i < packageCnt; i++) + { + for (j = 0; j < 8; j++) + { + transmit_message.tx_data[j] = buf[i * 8 + j]; + } + transmit_message.tx_sfid = 0x21; + transmit_message.tx_dlen = 8; + mailBoxNum = can_message_transmit(CAN1, &transmit_message); + Osal_TaskSleepMs(1); + } + + if (LastpackageSize > 0) + { + for (j = 0; j < LastpackageSize; j++) + { + transmit_message.tx_data[j] = buf[packageCnt * 8 + j]; + } + + transmit_message.tx_sfid = 0x21; + transmit_message.tx_dlen = LastpackageSize; + mailBoxNum = can_message_transmit(CAN1, &transmit_message); + Osal_TaskSleepMs(1); + } + + // Osal_MutexUnlock(s_can1Mutex); + + // writeRealLen = RingBuf_Put(&s_can1WriteRingBuffer, buf, writeSize); + + // usedCapacityOfBuffer = CAN1_WRITE_BUF_SIZE - RingBuf_GetUnusedSize(&s_can1WriteRingBuffer); + // s_can1WriteBufferState.maxUsedCapacityOfBuffer = + // usedCapacityOfBuffer > s_can1WriteBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + // : s_can1WriteBufferState.maxUsedCapacityOfBuffer; + // s_can1WriteBufferState.countOfLostData += writeSize - writeRealLen; + // printf("Enable tmeie interrupt"); + // can_interrupt_enable(CAN1, CAN_INTEN_TMEIE); + } + break; +#endif + + default: + return CAN_ERROR; + } + + return writeRealLen; +} + +// void UART_GetBufferState(E_UartNum uartNum, T_CanBufferState *readBufferState, T_CanBufferState *writeBufferState) +// { +// switch (uartNum) { +// #ifdef USING_UART_PORT_1 +// case UART_NUM_1: +// memcpy(readBufferState, &s_uart1ReadBufferState, sizeof(T_CanBufferState)); +// memcpy(writeBufferState, &s_uart1WriteBufferState, sizeof(T_CanBufferState)); +// break; +// #endif +// #ifdef USING_UART_PORT_2 +// case UART_NUM_2: +// memcpy(readBufferState, &s_can1ReadBufferState, sizeof(T_CanBufferState)); +// memcpy(writeBufferState, &s_can1WriteBufferState, sizeof(T_CanBufferState)); +// break; +// #endif +// #ifdef USING_UART_PORT_3 +// case UART_NUM_3: +// memcpy(readBufferState, &s_uart3ReadBufferState, sizeof(T_CanBufferState)); +// memcpy(writeBufferState, &s_uart3WriteBufferState, sizeof(T_CanBufferState)); +// break; +// #endif +// default: +// break; +// } +// } + +/** + * @brief UART1 interrupt request handler fucntion. + */ +#ifdef USING_UART_PORT_1 + +void USART0_IRQHandler(void) +{ + uint8_t data; + uint16_t usedCapacityOfBuffer = 0; + uint16_t realCountPutBuffer = 0; + + if ((RESET != usart_interrupt_flag_get(USART0, USART_INT_FLAG_RBNE)) && + (RESET != usart_flag_get(USART0, USART_FLAG_RBNE))) + { + data = usart_data_receive(USART0); + realCountPutBuffer = RingBuf_Put(&s_uart1ReadRingBuffer, &data, 1); + usedCapacityOfBuffer = UART1_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart1ReadRingBuffer); + s_uart1ReadBufferState.maxUsedCapacityOfBuffer = + usedCapacityOfBuffer > s_uart1ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + : s_uart1ReadBufferState.maxUsedCapacityOfBuffer; + s_uart1ReadBufferState.countOfLostData += 1 - realCountPutBuffer; + } + if ((RESET != usart_flag_get(USART0, USART_FLAG_TBE)) && + (RESET != usart_interrupt_flag_get(USART0, USART_INT_FLAG_TBE))) + { + if (RingBuf_Get(&s_uart1WriteRingBuffer, &data, 1)) + { + /* Transmit Data */ + usart_data_transmit(USART0, data); + } + else + { + usart_interrupt_disable(USART0, USART_INT_TBE); + } + } + + // if (__HAL_USART_GET_IT_SOURCE(&s_uart1Handle, USART_IT_RXNE) != RESET && + // __HAL_USART_GET_FLAG(&s_uart1Handle, USART_FLAG_RXNE) != RESET) { + // data = (uint8_t) ((uint16_t) (s_uart1Handle.Instance->DR & (uint16_t) 0x01FF) & (uint16_t) 0x00FF); + // realCountPutBuffer = RingBuf_Put(&s_uart1ReadRingBuffer, &data, 1); + // usedCapacityOfBuffer = UART1_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart1ReadRingBuffer); + // s_uart1ReadBufferState.maxUsedCapacityOfBuffer = + // usedCapacityOfBuffer > s_uart1ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + // : s_uart1ReadBufferState.maxUsedCapacityOfBuffer; + // s_uart1ReadBufferState.countOfLostData += 1 - realCountPutBuffer; + // } + + // if (__HAL_USART_GET_IT_SOURCE(&s_uart1Handle, USART_IT_TXE) != RESET && + // __HAL_USART_GET_FLAG(&s_uart1Handle, USART_FLAG_TXE) != RESET) { + // if (RingBuf_Get(&s_uart1WriteRingBuffer, &data, 1)) { + // /* Transmit Data */ + // s_uart1Handle.Instance->DR = ((uint16_t) data & (uint16_t) 0x01FF); + // } else { + // __HAL_USART_DISABLE_IT(&s_uart1Handle, USART_IT_TXE); + // } + // } +} + +#endif + +/** + * @brief CAN1 interrupt request handler fucntion. + */ +#ifdef USING_CAN1 + +void CAN1_TX_IRQHandler(void) +{ + // if(RESET != can_interrupt_flag_get(CAN1, CAN_INT_FLAG_MTF0)) + // { + // can_interrupt_flag_clear(CAN1, CAN_INT_FLAG_MTF0); + // // printf("\r\nMTF0 data transmmit success\r\n"); + // } + // if(RESET != can_interrupt_flag_get(CAN1, CAN_INT_FLAG_MTF1)) + // { + // can_interrupt_flag_clear(CAN1, CAN_INT_FLAG_MTF1); + // // printf("\r\nMTF1 data transmmit success\r\n"); + // } + // if(RESET != can_interrupt_flag_get(CAN1, CAN_INT_FLAG_MTF2)) + // { + // can_interrupt_flag_clear(CAN1, CAN_INT_FLAG_MTF2); + // // printf("\r\nMTF2 data transmmit success\r\n"); + // } + + // Osal_SemaphorePost(s_can1Sema); + + // uint32_t readLen = 0; + // uint8_t data[8] = {0}; + // can_trasnmit_message_struct transmit_message; + + // readLen = RingBuf_Get(&s_can1WriteRingBuffer, &data, 8); + // if (readLen <= 8) + // { + // /* Transmit Data */ + // can_struct_para_init(CAN_TX_MESSAGE_STRUCT, &transmit_message); + // transmit_message.tx_sfid = 0x00; + // transmit_message.tx_efid = 0x00; + // transmit_message.tx_ft = CAN_FT_DATA; + // transmit_message.tx_ff = CAN_FF_STANDARD; + // transmit_message.tx_dlen = 8; + // /* initialize receive message */ + // can_struct_para_init(CAN_RX_MESSAGE_STRUCT, &transmit_message); + + // transmit_message.tx_dlen = readLen; + // transmit_message.tx_sfid = 0x21; + // can_message_transmit(CAN1, &transmit_message); + // } + // else + // { + // can_interrupt_disable(CAN1, CAN_INTEN_TMEIE); + // } +} + +void CAN1_RX0_IRQHandler(void) +{ + can_receive_message_struct receive_message; + uint16_t usedCapacityOfBuffer = 0; + uint16_t realCountPutBuffer = 0; + + /* check the receive message */ + can_message_receive(CAN1, CAN_FIFO0, &receive_message); + + realCountPutBuffer = RingBuf_Put(&s_can1ReadRingBuffer, &receive_message.rx_data, receive_message.rx_dlen); + usedCapacityOfBuffer = CAN1_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_can1ReadRingBuffer); + s_can1ReadBufferState.maxUsedCapacityOfBuffer = + usedCapacityOfBuffer > s_can1ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + : s_can1ReadBufferState.maxUsedCapacityOfBuffer; + s_can1ReadBufferState.countOfLostData += 1 - realCountPutBuffer; + + // int i = 0 ; + // printf("\r\n can1 receive data:"); + // for(i = 0; i < receive_message.rx_dlen; i++) { + // printf(" %02x", receive_message.rx_data[i]); + // } +} + +#endif + +/** + * @brief UART3 interrupt request handler fucntion. + */ +#ifdef USING_UART_PORT_3 + +void UART3_IRQHandler(void) +{ + uint8_t data; + uint16_t usedCapacityOfBuffer = 0; + uint16_t realCountPutBuffer = 0; + + if ((RESET != usart_interrupt_flag_get(UART3, USART_INT_FLAG_RBNE)) && + (RESET != usart_flag_get(UART3, USART_FLAG_RBNE))) + { + data = usart_data_receive(UART3); + realCountPutBuffer = RingBuf_Put(&s_uart3ReadRingBuffer, &data, 1); + usedCapacityOfBuffer = UART3_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart3ReadRingBuffer); + s_uart3ReadBufferState.maxUsedCapacityOfBuffer = + usedCapacityOfBuffer > s_uart3ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + : s_uart3ReadBufferState.maxUsedCapacityOfBuffer; + s_uart3ReadBufferState.countOfLostData += 1 - realCountPutBuffer; + } + if ((RESET != usart_flag_get(UART3, USART_FLAG_TBE)) && + (RESET != usart_interrupt_flag_get(UART3, USART_INT_FLAG_TBE))) + { + if (RingBuf_Get(&s_uart3WriteRingBuffer, &data, 1)) + { + /* Transmit Data */ + usart_data_transmit(UART3, data); + } + else + { + usart_interrupt_disable(UART3, USART_INT_TBE); + } + } + + // if (__HAL_USART_GET_IT_SOURCE(&s_uart3Handle, USART_IT_RXNE) != RESET && + // __HAL_USART_GET_FLAG(&s_uart3Handle, USART_FLAG_RXNE) != RESET) { + // data = (uint8_t) ((uint16_t) (s_uart3Handle.Instance->DR & (uint16_t) 0x01FF) & (uint16_t) 0x00FF); + // realCountPutBuffer = RingBuf_Put(&s_uart3ReadRingBuffer, &data, 1); + // usedCapacityOfBuffer = UART3_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart3ReadRingBuffer); + // s_uart3ReadBufferState.maxUsedCapacityOfBuffer = + // usedCapacityOfBuffer > s_uart3ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + // : s_uart3ReadBufferState.maxUsedCapacityOfBuffer; + // s_uart3ReadBufferState.countOfLostData += 1 - realCountPutBuffer; + // } + + // if (__HAL_USART_GET_IT_SOURCE(&s_uart3Handle, USART_IT_TXE) != RESET && + // __HAL_USART_GET_FLAG(&s_uart3Handle, USART_FLAG_TXE) != RESET) { + // if (RingBuf_Get(&s_uart3WriteRingBuffer, &data, 1)) { + // /* Transmit Data */ + // s_uart3Handle.Instance->DR = ((uint16_t) data & (uint16_t) 0x01FF); + // } else { + // __HAL_USART_DISABLE_IT(&s_uart3Handle, USART_IT_TXE); + // } + // } +} + +#endif diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/can.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/can.h new file mode 100644 index 0000000..09db5cf --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/can.h @@ -0,0 +1,67 @@ +/** + ****************************************************************************** + * @file can.h + * @version V1.0.0 + * @date 2024/05/22 + * @brief This is the header file for "can.c". + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __CAN_H__ +#define __CAN_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "dji_platform.h" + +/* Exported constants --------------------------------------------------------*/ +// #define USING_CAN0 +#define USING_CAN1 + +#define CAN_ERROR (-1) + +/* Exported macros -----------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef enum { + CAN_NUM_0 = 0, + CAN_NUM_1 = 1, +} E_CanNum; + +typedef struct { + uint32_t countOfLostData; /*!< Count of data lost, unit: byte. */ + uint16_t maxUsedCapacityOfBuffer; /*!< Max capacity of buffer that have been used, unit: byte. */ +} T_CanBufferState; + +/* Exported constants --------------------------------------------------------*/ +/* Exported variables --------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +void CAN_Init(E_CanNum canNum); +int CAN_Read(E_CanNum canNum, uint8_t *buf, uint16_t readSize); +int CAN_Write(E_CanNum canNum, const uint8_t *buf, uint16_t writeSize); + +// void CAN_GetBufferState(E_UartNum uartNum, T_UartBufferState *readBufferState, T_UartBufferState *writeBufferState); + +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +#endif diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/dji_ringbuffer.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/dji_ringbuffer.c new file mode 100644 index 0000000..caefd1f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/dji_ringbuffer.c @@ -0,0 +1,130 @@ +/** + ****************************************************************************** + * @file dji_ringbuffer.c + * @version V1.0.0 + * @date 2017/11/10 + * @brief The file defines ring buffer related functions, including initialize, put data to buffer, + * get data from buffer and get unused count of bytes of buffer. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "dji_ringbuffer.h" +#include + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +#define RINGBUF_MIN(a, b) (((a)<(b))?(a):(b)) + +/* Private variables ---------------------------------------------------------*/ +/* Exported variables --------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** + * @brief Cut buffer size to power of 2, in order to increase the convenience of get and put operating of buffer. + * @param bufSize Original buffer size. + * @return Buffer size after handling. + */ +static uint16_t RingBuf_CutBufSizeToPowOfTwo(uint16_t bufSize) +{ + uint16_t i = 0; + + while ((1 << (++i)) <= bufSize); + return (uint16_t) (1 << (--i)); +} + +/* Exported functions --------------------------------------------------------*/ + +/** + * @brief Ring buffer initialization. + * @param pthis Pointer to ring buffer structure. + * @param pBuf Pointer to data buffer. + * @param bufSize Size of data buffer. + * @return None. + */ +void RingBuf_Init(T_RingBuffer *pthis, uint8_t *pBuf, uint16_t bufSize) +{ + pthis->readIndex = 0; + pthis->writeIndex = 0; + pthis->bufferPtr = pBuf; + pthis->bufferSize = RingBuf_CutBufSizeToPowOfTwo(bufSize); +} + +/** + * @brief Put a block of data into ring buffer. + * @param pthis Pointer to ring buffer structure. + * @param pData Pointer to data to be stored. + * @param dataLen Length of data to be stored. + * @return Length of data to be stored. + */ +uint16_t RingBuf_Put(T_RingBuffer *pthis, const uint8_t *pData, uint16_t dataLen) +{ + uint16_t writeUpLen; + + dataLen = RINGBUF_MIN(dataLen, (uint16_t) (pthis->bufferSize - pthis->writeIndex + pthis->readIndex)); + + //fill up data + writeUpLen = RINGBUF_MIN(dataLen, (uint16_t) (pthis->bufferSize - (pthis->writeIndex & (pthis->bufferSize - 1)))); + memcpy(pthis->bufferPtr + (pthis->writeIndex & (pthis->bufferSize - 1)), pData, writeUpLen); + + //fill begin data + memcpy(pthis->bufferPtr, pData + writeUpLen, dataLen - writeUpLen); + + pthis->writeIndex += dataLen; + + return dataLen; +} + +/** + * @brief Get a block of data from ring buffer. +* @param pthis Pointer to ring buffer structure. +* @param pData Pointer to data to be read. +* @param dataLen Length of data to be read. +* @return Length of data to be read. + */ +uint16_t RingBuf_Get(T_RingBuffer *pthis, uint8_t *pData, uint16_t dataLen) +{ + uint16_t readUpLen; + + dataLen = RINGBUF_MIN(dataLen, (uint16_t) (pthis->writeIndex - pthis->readIndex)); + + //get up data + readUpLen = RINGBUF_MIN(dataLen, (uint16_t) (pthis->bufferSize - (pthis->readIndex & (pthis->bufferSize - 1)))); + memcpy(pData, pthis->bufferPtr + (pthis->readIndex & (pthis->bufferSize - 1)), readUpLen); + + //get begin data + memcpy(pData + readUpLen, pthis->bufferPtr, dataLen - readUpLen); + + pthis->readIndex += dataLen; + + return dataLen; +} + +/** + * @brief Get unused size of ring buffer. + * @param pthis Pointer to ring buffer structure. + * @return Unused size of ring buffer. + */ +uint16_t RingBuf_GetUnusedSize(T_RingBuffer *pthis) +{ + return (uint16_t) (pthis->bufferSize - pthis->writeIndex + pthis->readIndex); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/dji_ringbuffer.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/dji_ringbuffer.h new file mode 100644 index 0000000..b6569c3 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/dji_ringbuffer.h @@ -0,0 +1,63 @@ +/** + ****************************************************************************** + * @file dji_ringbuffer.h + * @version V1.0.0 + * @date 2017/11/10 + * @brief This is the header file for "dji_ringbuffer.c". + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef _DJI_RING_BUFFER_H_ +#define _DJI_RING_BUFFER_H_ + +/* Includes ------------------------------------------------------------------*/ +#include + +/* Exported constants --------------------------------------------------------*/ +/* Exported macros -----------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ + +//Note: not need lock for just one producer / one consumer +//need mutex to protect for multi-producer / multi-consumer + +typedef struct _ringBuffer { + uint8_t *bufferPtr; + uint16_t bufferSize; + + uint16_t readIndex; + uint16_t writeIndex; +} T_RingBuffer; + +/* Exported variables --------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +void RingBuf_Init(T_RingBuffer *pthis, uint8_t *pBuf, uint16_t bufSize); +uint16_t RingBuf_Put(T_RingBuffer *pthis, const uint8_t *pData, uint16_t dataLen); +uint16_t RingBuf_Get(T_RingBuffer *pthis, uint8_t *pData, uint16_t dataLen); +uint16_t RingBuf_GetUnusedSize(T_RingBuffer *pthis); + +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +#endif diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/flash_if.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/flash_if.c new file mode 100644 index 0000000..1b8874b --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/flash_if.c @@ -0,0 +1,394 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Src/flash_if.c + * @author MCD Application Team + * @brief This file provides all the memory related operation functions. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ + +/** @addtogroup Gd32F4xx_IAP_Main + * @{ + */ + +/* Includes ------------------------------------------------------------------*/ +#include "flash_if.h" +#include "gd32f5xx.h" +#include "gd32f5xx_fmc.h" + +/* Private typedef -----------------------------------------------------------*/ +#define ENABLE_BOR 0 + +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static int32_t Flash_If_GetSectorNum(uint32_t address); + +/* Private functions ---------------------------------------------------------*/ +static int32_t Flash_If_GetSectorNum(uint32_t address) +{ + int32_t sectorNum = 0; + + if (address >= ADDR_FLASH_SECTOR_0 && address < ADDR_FLASH_SECTOR_1) { + sectorNum = 0; + } else if (address >= ADDR_FLASH_SECTOR_1 && address < ADDR_FLASH_SECTOR_2) { + sectorNum = 1; + } else if (address >= ADDR_FLASH_SECTOR_2 && address < ADDR_FLASH_SECTOR_3) { + sectorNum = 2; + } else if (address >= ADDR_FLASH_SECTOR_3 && address < ADDR_FLASH_SECTOR_4) { + sectorNum = 3; + } else if (address >= ADDR_FLASH_SECTOR_4 && address < ADDR_FLASH_SECTOR_5) { + sectorNum = 4; + } else if (address >= ADDR_FLASH_SECTOR_5 && address < ADDR_FLASH_SECTOR_6) { + sectorNum = 5; + } else if (address >= ADDR_FLASH_SECTOR_6 && address < ADDR_FLASH_SECTOR_7) { + sectorNum = 6; + } else if (address >= ADDR_FLASH_SECTOR_7 && address < ADDR_FLASH_SECTOR_8) { + sectorNum = 7; + } else if (address >= ADDR_FLASH_SECTOR_8 && address < ADDR_FLASH_SECTOR_9) { + sectorNum = 8; + } else if (address >= ADDR_FLASH_SECTOR_9 && address < ADDR_FLASH_SECTOR_10) { + sectorNum = 9; + } else if (address >= ADDR_FLASH_SECTOR_10 && address < ADDR_FLASH_SECTOR_11) { + sectorNum = 10; + } else if (address >= ADDR_FLASH_SECTOR_11 && address < ADDR_FLASH_SECTOR_12) { + sectorNum = 11; + } else if (address >= ADDR_FLASH_SECTOR_12 && address < ADDR_FLASH_SECTOR_13) { + sectorNum = 12; + } else if (address >= ADDR_FLASH_SECTOR_13 && address < ADDR_FLASH_SECTOR_14) { + sectorNum = 13; + } else if (address >= ADDR_FLASH_SECTOR_14 && address < ADDR_FLASH_SECTOR_15) { + sectorNum = 14; + } else if (address >= ADDR_FLASH_SECTOR_15 && address < ADDR_FLASH_SECTOR_16) { + sectorNum = 15; + } else if (address >= ADDR_FLASH_SECTOR_16 && address < ADDR_FLASH_SECTOR_17) { + sectorNum = 16; + } else if (address >= ADDR_FLASH_SECTOR_17 && address < ADDR_FLASH_SECTOR_18) { + sectorNum = 17; + } else if (address >= ADDR_FLASH_SECTOR_18 && address < ADDR_FLASH_SECTOR_19) { + sectorNum = 18; + } else if (address >= ADDR_FLASH_SECTOR_19 && address < ADDR_FLASH_SECTOR_20) { + sectorNum = 19; + } else if (address >= ADDR_FLASH_SECTOR_20 && address < ADDR_FLASH_SECTOR_21) { + sectorNum = 20; + } else if (address >= ADDR_FLASH_SECTOR_21 && address < ADDR_FLASH_SECTOR_22) { + sectorNum = 21; + } else if (address >= ADDR_FLASH_SECTOR_22 && address < ADDR_FLASH_SECTOR_23) { + sectorNum = 22; + } else if (address >= ADDR_FLASH_SECTOR_23 && address < ADDR_FLASH_SECTOR_24) { + sectorNum = 23; + } else if (address >= ADDR_FLASH_SECTOR_24 && address < ADDR_FLASH_SECTOR_25) { + sectorNum = 24; + } else if (address >= ADDR_FLASH_SECTOR_25 && address < ADDR_FLASH_SECTOR_26) { + sectorNum = 25; + } else if (address >= ADDR_FLASH_SECTOR_26 && address < ADDR_FLASH_SECTOR_27) { + sectorNum = 26; + } else if (address >= ADDR_FLASH_SECTOR_27 && address < ADDR_FLASH_SECTOR_28) { + sectorNum = 27; + } else if (address >= ADDR_FLASH_SECTOR_28 && address < ADDR_FLASH_SECTOR_29) { + sectorNum = 28; + } else if (address >= ADDR_FLASH_SECTOR_29 && address < ADDR_FLASH_SECTOR_30) { + sectorNum = 29; + } else if (address >= ADDR_FLASH_SECTOR_30 && address < ADDR_FLASH_SECTOR_31) { + sectorNum = 30; + } else if (address >= ADDR_FLASH_SECTOR_31 && address < ADDR_FLASH_SECTOR_32) { + sectorNum = 31; + } else if (address >= ADDR_FLASH_SECTOR_32 && address < ADDR_FLASH_SECTOR_33) { + sectorNum = 32; + } else if (address >= ADDR_FLASH_SECTOR_33 && address < ADDR_FLASH_SECTOR_34) { + sectorNum = 33; + } else if (address >= ADDR_FLASH_SECTOR_34 && address < ADDR_FLASH_SECTOR_35) { + sectorNum = 34; + } else if (address >= ADDR_FLASH_SECTOR_35 && address < ADDR_FLASH_SECTOR_36) { + sectorNum = 35; + } else if (address >= ADDR_FLASH_SECTOR_36 && address < ADDR_FLASH_SECTOR_37) { + sectorNum = 36; + } else if (address >= ADDR_FLASH_SECTOR_37 && address < ADDR_FLASH_SECTOR_38) { + sectorNum = 37; + } else if (address >= ADDR_FLASH_SECTOR_38 && address < ADDR_FLASH_SECTOR_39) { + sectorNum = 38; + } else if (address >= ADDR_FLASH_SECTOR_39 && address < ADDR_FLASH_SECTOR_40) { + sectorNum = 39; + } else if (address >= ADDR_FLASH_SECTOR_40 && address < ADDR_FLASH_SECTOR_41) { + sectorNum = 40; + } else if (address >= ADDR_FLASH_SECTOR_41 && address < ADDR_FLASH_SECTOR_42) { + sectorNum = 41; + } else if (address >= ADDR_FLASH_SECTOR_42 && address < ADDR_FLASH_SECTOR_43) { + sectorNum = 42; + } else if (address >= ADDR_FLASH_SECTOR_43 && address < ADDR_FLASH_SECTOR_44) { + sectorNum = 43; + } else if (address >= ADDR_FLASH_SECTOR_44 && address < ADDR_FLASH_SECTOR_45) { + sectorNum = 44; + } else if (address >= ADDR_FLASH_SECTOR_45 && address < ADDR_FLASH_SECTOR_46) { + sectorNum = 45; + } else if (address >= ADDR_FLASH_SECTOR_46 && address < ADDR_FLASH_SECTOR_47) { + sectorNum = 46; + } else if (address >= ADDR_FLASH_SECTOR_47 && address < ADDR_FLASH_SECTOR_48) { + sectorNum = 47; + } else if (address >= ADDR_FLASH_SECTOR_48 && address < ADDR_FLASH_SECTOR_49) { + sectorNum = 48; + } else if (address >= ADDR_FLASH_SECTOR_49 && address < ADDR_FLASH_SECTOR_50) { + sectorNum = 49; + } else if (address >= ADDR_FLASH_SECTOR_50 && address < ADDR_FLASH_SECTOR_51) { + sectorNum = 50; + } else if (address >= ADDR_FLASH_SECTOR_51 && address < ADDR_FLASH_SECTOR_52) { + sectorNum = 51; + } else if (address >= ADDR_FLASH_SECTOR_52 && address < ADDR_FLASH_SECTOR_53) { + sectorNum = 52; + } else if (address >= ADDR_FLASH_SECTOR_53 && address <= FLASH_END_ADDRESS) { + sectorNum = 53; + } else { + printf("Not found sector by address: 0x%08X\r\n", address); + sectorNum = -1; + } + + return sectorNum; +} + +uint32_t FLASH_If_Init(void) +{ + int32_t result = 0; + uint32_t borValue = 0; + +#if ENABLE_BOR + fmc_unlock(); + ob_unlock(); + + ob_user_bor_threshold(OB_BOR_TH_VALUE3); + + borValue = ob_user_bor_threshold_get(); + if (borValue != OB_BOR_TH_VALUE3) { + return -1; + } + + ob_start(); + ob_lock(); + fmc_lock(); +#endif + + return result; +} + +/** + * @brief This function does an erase of all user flash area + * @param StartSector: start of user flash area + * @retval 0: user flash area successfully erased + * 1: error occurred + */ +uint32_t FLASH_If_Erase(uint32_t startAddress, uint32_t endAddress) +{ + uint32_t sectorNum = 0; + uint8_t isNeedErase[FLASH_SECTOR_NUM] = {0}; + int32_t startSectorNum = 0; + int32_t endSectorNum = 0; + fmc_state_enum fmc_state; + int32_t i = 0; + + if (startAddress < ADDR_FLASH_SECTOR_0 || startAddress > FLASH_END_ADDRESS) { + return -1; + } + + if (endAddress < ADDR_FLASH_SECTOR_0 || endAddress > FLASH_END_ADDRESS) { + return -1; + } + + if (endAddress <= startAddress) { + return -1; + } + + startSectorNum = Flash_If_GetSectorNum(startAddress); + endSectorNum = Flash_If_GetSectorNum(endAddress); + + if (startSectorNum < 0 || endSectorNum < 0) { + return -1; + } + + for (i = startSectorNum; i <= endSectorNum; i++) { + isNeedErase[i] = 1; + printf("isNeedErase %d\r\n", i); + } + + /* unlock the flash program erase controller */ + fmc_unlock(); + + /* clear pending flags */ + fmc_flag_clear(FMC_FLAG_END | FMC_FLAG_OPERR | FMC_FLAG_WPERR | FMC_FLAG_PGMERR | FMC_FLAG_PGSERR | FMC_FLAG_PGAERR); + + /* wait the erase operation complete*/ + for (i = 0; i < sizeof(isNeedErase); i++) { + if (isNeedErase[i] == 1) { + if (i <= 31) { + fmc_state = fmc_sector_erase(CTL_SN(i)); + if (fmc_state != FMC_READY) { + printf("Erase sector %d failed. fmc_state %d\r\n", i, fmc_state); + goto out; + } + } else { + fmc_state = fmc_sector_erase((SN_5 | CTL_SN(i - 32))); + if (fmc_state != FMC_READY) { + printf("Erase sector %d failed. fmc_state %d\r\n", i, fmc_state); + goto out; + } + } + } + } + + /* lock the flash program erase controller */ + fmc_lock(); + + return 0; + +out: + fmc_lock(); + return -1; +} + +/** + * @brief This function writes a data buffer in flash (data are 32-bit aligned). + * @note After writing data buffer, the flash content is checked. + * @param FlashAddress: start address for writing data buffer + * @param Data: pointer on data buffer + * @param DataLength: length of data buffer + * @retval 0: Data successfully written to Flash memory + * 1: Error occurred while writing data in Flash memory + * 2: Written Data in flash memory is different from expected one + */ +uint32_t FLASH_If_Write(uint32_t FlashAddress, const uint8_t *Data, uint32_t DataLength) +{ + uint32_t ret = 0; + uint32_t i = 0; + uint32_t writeAddress = 0; + uint32_t dataLenDoubleWord = 0; + + writeAddress = FlashAddress; + + /* unlock the flash program erase controller */ + fmc_unlock(); + /* clear pending flags */ + fmc_flag_clear(FMC_FLAG_END | FMC_FLAG_OPERR | FMC_FLAG_WPERR | FMC_FLAG_PGMERR | FMC_FLAG_PGSERR | FMC_FLAG_PGAERR); + + dataLenDoubleWord = DataLength / 8; + for(i = 0; (i < dataLenDoubleWord) && (writeAddress <= (FLASH_END_ADDRESS - 8)); i++) { + if(FMC_READY == fmc_doubleword_program(writeAddress, *(uint64_t *)(Data + i * 8))) { + writeAddress += 8; + } else { + ret = FLASHIF_WRITING_ERROR; + goto out; + } + } + + for (i = 0; i < DataLength % 8; i++) { + if(FMC_READY == fmc_byte_program(writeAddress, *(uint8_t *) (Data + writeAddress - FlashAddress))) { + writeAddress += 1; + } else { + ret = FLASHIF_WRITING_ERROR; + goto out; + } + } + + /* lock the flash program erase controller */ + fmc_lock(); + + return FLASHIF_OK; + +out: + fmc_lock(); + return ret; +} + +/** + * @brief Returns the write protection status of user flash area. + * @param None + * @retval 0: No write protected sectors inside the user flash area + * 1: Some sectors inside the user flash area are write protected + */ +uint16_t FLASH_If_GetWriteProtectionStatus(void) +{ + uint32_t bank0State = 0x0; + uint32_t bank1State = 0x0; + + /* unlock the flash program erase controller */ + fmc_unlock(); + + bank0State = ob_write_protection0_get(); + bank1State = ob_write_protection1_get(); + + /* lock the flash program erase controller */ + fmc_lock(); + + if (bank0State == 0xFFFFF || bank1State == 0xFFFFF) { + return FLASHIF_PROTECTION_NONE; + } else { + return FLASHIF_PROTECTION_WRPENABLED; + } +} + +/** + * @brief Configure the write protection status of user flash area. + * @param modifier DISABLE or ENABLE the protection + * @retval int32_t HAL_OK if change is applied. + */ +int32_t FLASH_If_WriteProtectionConfig(bool enableWriteProtection) +{ + uint32_t ProtectedSECTOR = 0xFFF; + int32_t result; + + fmc_unlock(); + ob_unlock(); + + if (enableWriteProtection == true) { + result = ob_write_protection_enable(OB_WP_ALL); + } else { + result = ob_write_protection_disable(OB_WP_ALL); + } + ob_start(); + ob_lock(); + fmc_lock(); + + return result; +} + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/flash_if.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/flash_if.h new file mode 100644 index 0000000..f239ced --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/flash_if.h @@ -0,0 +1,162 @@ +/** + ****************************************************************************** + * @file IAP/IAP_Main/Inc/flash_if.h + * @author MCD Application Team + * @brief This file provides all the headers of the flash_if functions. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution 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 STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS 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. + * + * @statement DJI has modified some symbols' name. + * + ****************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __FLASH_IF_H +#define __FLASH_IF_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_platform.h" + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Base address of the Flash sectors */ +/* Bank0 2MB*/ +#define ADDR_FLASH_SECTOR_0 ((uint32_t)0x08000000) /* Base @ of Sector 0, 16 Kbyte */ +#define ADDR_FLASH_SECTOR_1 ((uint32_t)0x08004000) /* Base @ of Sector 1, 16 Kbyte */ +#define ADDR_FLASH_SECTOR_2 ((uint32_t)0x08008000) /* Base @ of Sector 2, 16 Kbyte */ +#define ADDR_FLASH_SECTOR_3 ((uint32_t)0x0800C000) /* Base @ of Sector 3, 16 Kbyte */ +#define ADDR_FLASH_SECTOR_4 ((uint32_t)0x08010000) /* Base @ of Sector 4, 64 Kbyte */ +#define ADDR_FLASH_SECTOR_5 ((uint32_t)0x08020000) /* Base @ of Sector 5, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_6 ((uint32_t)0x08040000) /* Base @ of Sector 6, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_7 ((uint32_t)0x08060000) /* Base @ of Sector 7, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_8 ((uint32_t)0x08080000) /* Base @ of Sector 8, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_9 ((uint32_t)0x080A0000) /* Base @ of Sector 9, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_10 ((uint32_t)0x080C0000) /* Base @ of Sector 10, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_11 ((uint32_t)0x080E0000) /* Base @ of Sector 11, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_12 ((uint32_t)0x08100000) /* Base @ of Sector 12, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_13 ((uint32_t)0x08120000) /* Base @ of Sector 13, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_14 ((uint32_t)0x08140000) /* Base @ of Sector 14, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_15 ((uint32_t)0x08160000) /* Base @ of Sector 15, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_16 ((uint32_t)0x08180000) /* Base @ of Sector 16, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_17 ((uint32_t)0x081A0000) /* Base @ of Sector 17, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_18 ((uint32_t)0x081C0000) /* Base @ of Sector 18, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_19 ((uint32_t)0x081E0000) /* Base @ of Sector 19, 128 Kbyte */ + +/* Bank1 2MB*/ +#define ADDR_FLASH_SECTOR_20 ((uint32_t)0x08200000) /* Base @ of Sector 20, 16 Kbyte */ +#define ADDR_FLASH_SECTOR_21 ((uint32_t)0x08204000) /* Base @ of Sector 21, 16 Kbyte */ +#define ADDR_FLASH_SECTOR_22 ((uint32_t)0x08208000) /* Base @ of Sector 22, 16 Kbyte */ +#define ADDR_FLASH_SECTOR_23 ((uint32_t)0x0820C000) /* Base @ of Sector 23, 16 Kbyte */ +#define ADDR_FLASH_SECTOR_24 ((uint32_t)0x08218000) /* Base @ of Sector 24, 64 Kbyte */ +#define ADDR_FLASH_SECTOR_25 ((uint32_t)0x08220000) /* Base @ of Sector 25, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_26 ((uint32_t)0x08240000) /* Base @ of Sector 26, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_27 ((uint32_t)0x08260000) /* Base @ of Sector 27, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_28 ((uint32_t)0x08280000) /* Base @ of Sector 28, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_29 ((uint32_t)0x082A0000) /* Base @ of Sector 29, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_30 ((uint32_t)0x082C0000) /* Base @ of Sector 30, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_31 ((uint32_t)0x082E0000) /* Base @ of Sector 31, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_32 ((uint32_t)0x08300000) /* Base @ of Sector 32, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_33 ((uint32_t)0x08320000) /* Base @ of Sector 33, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_34 ((uint32_t)0x08340000) /* Base @ of Sector 34, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_35 ((uint32_t)0x08360000) /* Base @ of Sector 35, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_36 ((uint32_t)0x08380000) /* Base @ of Sector 36, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_37 ((uint32_t)0x083A0000) /* Base @ of Sector 37, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_38 ((uint32_t)0x083C0000) /* Base @ of Sector 38, 128 Kbyte */ +#define ADDR_FLASH_SECTOR_39 ((uint32_t)0x083E0000) /* Base @ of Sector 39, 128 Kbyte */ + +/* Bank1-Ex 3584KB*/ +#define ADDR_FLASH_SECTOR_40 ((uint32_t)0x08400000) /* Base @ of Sector 40, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_41 ((uint32_t)0x08440000) /* Base @ of Sector 41, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_42 ((uint32_t)0x08480000) /* Base @ of Sector 42, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_43 ((uint32_t)0x084C0000) /* Base @ of Sector 43, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_44 ((uint32_t)0x08500000) /* Base @ of Sector 44, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_45 ((uint32_t)0x08540000) /* Base @ of Sector 45, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_46 ((uint32_t)0x08580000) /* Base @ of Sector 46, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_47 ((uint32_t)0x085C0000) /* Base @ of Sector 47, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_48 ((uint32_t)0x08600000) /* Base @ of Sector 48, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_49 ((uint32_t)0x08640000) /* Base @ of Sector 49, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_50 ((uint32_t)0x08680000) /* Base @ of Sector 50, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_51 ((uint32_t)0x086C0000) /* Base @ of Sector 51, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_52 ((uint32_t)0x08700000) /* Base @ of Sector 52, 256 Kbyte */ +#define ADDR_FLASH_SECTOR_53 ((uint32_t)0x08740000) /* Base @ of Sector 53, 256 Kbyte */ + +/* Error code */ +enum { + FLASHIF_OK = 0, + FLASHIF_ERASE_ERROR, + FLASHIF_WRITINGCTRL_ERROR, + FLASHIF_WRITING_ERROR +}; + +enum { + FLASHIF_PROTECTION_NONE = 0, + FLASHIF_PROTECTION_PCROPENABLED = 0x1, + FLASHIF_PROTECTION_WRPENABLED = 0x2, + FLASHIF_PROTECTION_RDPENABLED = 0x4, +}; + +#define FLASH_SECTOR_NUM 54 +#define FLASH_END_ADDRESS 0x0877FFFF + +/* Define the address from where user application will be loaded. + Note: the 1st sector 0x08000000-0x08007FFF is reserved for the IAP code */ +#define APPLICATION_ADDRESS ADDR_FLASH_SECTOR_5 +#define APPLICATION_ADDRESS_END (ADDR_FLASH_SECTOR_19 - 1) + +/* Define the address from where user application will be stored in upgrade mode */ +#define APPLICATION_STORE_ADDRESS ADDR_FLASH_SECTOR_25 +#define APPLICATION_STORE_ADDRESS_END (ADDR_FLASH_SECTOR_39 - 1) + +/* Define the user application size */ +#define APPLICATION_FLASH_SIZE (APPLICATION_STORE_ADDRESS_END - APPLICATION_STORE_ADDRESS + 1) + +/* Define the address for param store */ +#define APPLICATION_PARAM_STORE_ADDRESS ADDR_FLASH_SECTOR_39 +#define APPLICATION_PARAM_STORE_ADDRESS_END (ADDR_FLASH_SECTOR_40 - 1) + +/* Exported macro ------------------------------------------------------------*/ + +/* Exported functions ------------------------------------------------------- */ +uint32_t FLASH_If_Init(void); +uint32_t FLASH_If_Erase(uint32_t StartAddress, uint32_t endAddress); +uint32_t FLASH_If_Write(uint32_t FlashAddress, const uint8_t *Data, uint32_t DataLength); +uint16_t FLASH_If_GetWriteProtectionStatus(void); +int32_t FLASH_If_WriteProtectionConfig(bool enableWriteProtection); + +#endif /* __FLASH_IF_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_hw.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_hw.c new file mode 100644 index 0000000..de130d8 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_hw.c @@ -0,0 +1,331 @@ +/*! + \file gd32f5xx_hw.c + \brief USB hardware configuration for GD32F5xx + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "drv_usb_hw.h" +#include "limits.h" +#include "osal.h" +#include "FreeRTOS.h" +#include "task.h" +#include "semphr.h" +#include "stdlib.h" + +#define TIM_MSEC_DELAY 0x01U +#define TIM_USEC_DELAY 0x02U + +__IO uint32_t delay_time = 0U; +__IO uint16_t timer_prescaler = 5U; + +/* local function prototypes ('static') */ +static void hw_time_set (uint8_t unit); +static void hw_delay (uint32_t ntime, uint8_t unit); + +/*! + \brief configure USB clock + \param[in] none + \param[out] none + \retval none +*/ +void usb_rcu_config(void) +{ +#ifdef USE_USB_FS + /* configure the PLLSAIP = 48MHz, PLLSAI_N = 288, PLLSAI_P = 6 */ + rcu_pllsai_p_config(288, 6); + /* enable PLLSAI */ + RCU_CTL |= RCU_CTL_PLLSAIEN; + /* wait until PLLSAI is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSAISTB)){ + } + + rcu_pll48m_clock_config(RCU_PLL48MSRC_PLLSAIP); + rcu_ck48m_clock_config(RCU_CK48MSRC_PLL48M); + + rcu_periph_clock_enable(RCU_USBFS); +#elif defined(USE_USB_HS) + #ifdef USE_EMBEDDED_PHY + rcu_pll48m_clock_config(RCU_PLL48MSRC_PLLQ); + rcu_ck48m_clock_config(RCU_CK48MSRC_PLL48M); + #elif defined(USE_ULPI_PHY) + rcu_periph_clock_enable(RCU_USBHSULPI); + #endif /* USE_EMBEDDED_PHY */ + + rcu_periph_clock_enable(RCU_USBHS); +#endif /* USB_USBFS */ +} + +/*! + \brief configure USB data line GPIO + \param[in] none + \param[out] none + \retval none +*/ +void usb_gpio_config(void) +{ + rcu_periph_clock_enable(RCU_SYSCFG); + +#ifdef USE_USB_FS + + rcu_periph_clock_enable(RCU_GPIOA); + + /* USBFS_DM(PA11) and USBFS_DP(PA12) GPIO pin configuration */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_11 | GPIO_PIN_12); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_11 | GPIO_PIN_12); + + gpio_af_set(GPIOA, GPIO_AF_10, GPIO_PIN_11 | GPIO_PIN_12); + +#elif defined(USE_USB_HS) + + #ifdef USE_ULPI_PHY + rcu_periph_clock_enable(RCU_GPIOA); + rcu_periph_clock_enable(RCU_GPIOB); + rcu_periph_clock_enable(RCU_GPIOC); + rcu_periph_clock_enable(RCU_GPIOI); + + /* ULPI_STP(PC0) GPIO pin configuration */ + gpio_mode_set(GPIOC, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_0); + gpio_output_options_set(GPIOC, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_0); + + /* ULPI_CK(PA5) GPIO pin configuration */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_5); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_5); + + /* ULPI_NXT(PC3) GPIO pin configuration */ + gpio_mode_set(GPIOC, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_3); + gpio_output_options_set(GPIOC, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_3); + +// /* ULPI_DIR(PI11) GPIO pin configuration */ +// gpio_mode_set(GPIOI, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_11); +// gpio_output_options_set(GPIOI, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_11); + /* ULPI_DIR(PI11) GPIO pin configuration */ + gpio_mode_set(GPIOC, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_2); + gpio_output_options_set(GPIOC, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_2); + + /* ULPI_D1(PB0), ULPI_D2(PB1), ULPI_D3(PB10), ULPI_D4(PB11) \ + ULPI_D5(PB12), ULPI_D6(PB13) and ULPI_D7(PB5) GPIO pin configuration */ + gpio_mode_set(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, \ + GPIO_PIN_5 | GPIO_PIN_13 | GPIO_PIN_12 |\ + GPIO_PIN_11 | GPIO_PIN_10 | GPIO_PIN_1 | GPIO_PIN_0); + gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, \ + GPIO_PIN_5 | GPIO_PIN_13 | GPIO_PIN_12 |\ + GPIO_PIN_11 | GPIO_PIN_10 | GPIO_PIN_1 | GPIO_PIN_0); + + /* ULPI_D0(PA3) GPIO pin configuration */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_3); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_3); + + gpio_af_set(GPIOI, GPIO_AF_10, GPIO_PIN_11); + gpio_af_set(GPIOC, GPIO_AF_10, GPIO_PIN_0 | GPIO_PIN_3); + gpio_af_set(GPIOA, GPIO_AF_10, GPIO_PIN_5 | GPIO_PIN_3); + gpio_af_set(GPIOB, GPIO_AF_10, GPIO_PIN_5 | GPIO_PIN_13 | GPIO_PIN_12 |\ + GPIO_PIN_11 | GPIO_PIN_10 | GPIO_PIN_1 | GPIO_PIN_0); + #elif defined(USE_EMBEDDED_PHY) + rcu_periph_clock_enable(RCU_GPIOB); + rcu_periph_clock_enable(RCU_GPIOC); + + gpio_mode_set(GPIOC, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_2); + gpio_output_options_set(GPIOC, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_2); + + /* USBHS_DM(PB14) and USBHS_DP(PB15) GPIO pin configuration */ + gpio_mode_set(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_14 | GPIO_PIN_15); + gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, GPIO_PIN_14 | GPIO_PIN_15); + gpio_af_set(GPIOB, GPIO_AF_12, GPIO_PIN_14 | GPIO_PIN_15); + #endif /* USE_ULPI_PHY */ + +#endif /* USE_USBFS */ +} + +/*! + \brief configure USB interrupt + \param[in] none + \param[out] none + \retval none +*/ +void usb_intr_config(void) +{ + nvic_priority_group_set(NVIC_PRIGROUP_PRE2_SUB2); + +#ifdef USE_USB_FS + nvic_irq_enable((uint8_t)USBFS_IRQn, 2U, 0U); + + #if USBFS_LOW_POWER + /* enable the power module clock */ + rcu_periph_clock_enable(RCU_PMU); + + /* USB wakeup EXTI line configuration */ + exti_interrupt_flag_clear(EXTI_18); + exti_init(EXTI_18, EXTI_INTERRUPT, EXTI_TRIG_RISING); + exti_interrupt_enable(EXTI_18); + + nvic_irq_enable((uint8_t)USBFS_WKUP_IRQn, 0U, 0U); + #endif /* USBFS_LOW_POWER */ +#elif defined(USE_USB_HS) + nvic_irq_enable((uint8_t)USBHS_IRQn, 2U, 0U); + + #if USBHS_LOW_POWER + /* enable the power module clock */ + rcu_periph_clock_enable(RCU_PMU); + + /* USB wakeup EXTI line configuration */ + exti_interrupt_flag_clear(EXTI_20); + exti_init(EXTI_20, EXTI_INTERRUPT, EXTI_TRIG_RISING); + exti_interrupt_enable(EXTI_20); + + nvic_irq_enable((uint8_t)USBHS_WKUP_IRQn, 0U, 0U); + #endif /* USBHS_LOW_POWER */ +#endif /* USE_USB_FS */ + +#ifdef USB_HS_DEDICATED_EP1_ENABLED + nvic_irq_enable(USBHS_EP1_Out_IRQn, 1, 0); + nvic_irq_enable(USBHS_EP1_In_IRQn, 1, 0); +#endif /* USB_HS_DEDICATED_EP1_ENABLED */ +} + +/*! + \brief initializes delay unit using Timer2 + \param[in] none + \param[out] none + \retval none +*/ +void usb_timer_init (void) +{ + /* configure the priority group to 2 bits */ + nvic_priority_group_set(NVIC_PRIGROUP_PRE2_SUB2); + + /* enable the TIMER2 global interrupt */ + nvic_irq_enable((uint8_t)TIMER2_IRQn, 1U, 0U); + + rcu_periph_clock_enable(RCU_TIMER2); +} + +/*! + \brief delay in micro seconds + \param[in] usec: value of delay required in micro seconds + \param[out] none + \retval none +*/ +void usb_udelay (const uint32_t usec) +{ + hw_delay(usec, TIM_USEC_DELAY); +} + +/*! + \brief delay in milliseconds + \param[in] msec: value of delay required in milliseconds + \param[out] none + \retval none +*/ +void usb_mdelay (const uint32_t msec) +{ + Osal_TaskSleepMs(msec); + // hw_delay(msec, TIM_MSEC_DELAY); +} + +/*! + \brief timer base IRQ + \param[in] none + \param[out] none + \retval none +*/ +void usb_timer_irq (void) +{ + if (RESET != timer_interrupt_flag_get(TIMER2, TIMER_INT_FLAG_UP)){ + timer_interrupt_flag_clear(TIMER2, TIMER_INT_FLAG_UP); + + if (delay_time > 0x00U){ + delay_time--; + } else { + timer_disable(TIMER2); + } + } +} + +/*! + \brief delay routine based on TIMER2 + \param[in] nTime: delay Time + \param[in] unit: delay Time unit = milliseconds / microseconds + \param[out] none + \retval none +*/ +static void hw_delay(uint32_t ntime, uint8_t unit) +{ + delay_time = ntime; + + hw_time_set(unit); + + while (0U != delay_time) { + } + + timer_disable(TIMER2); +} + +/*! + \brief configures TIMER for delay routine based on Timer2 + \param[in] unit: msec /usec + \param[out] none + \retval none +*/ +static void hw_time_set(uint8_t unit) +{ + timer_parameter_struct timer_basestructure; + + timer_prescaler = ((rcu_clock_freq_get(CK_APB1)/1000000*2)/12) - 1; + + timer_disable(TIMER2); + timer_interrupt_disable(TIMER2, TIMER_INT_UP); + + if(TIM_USEC_DELAY == unit) { + timer_basestructure.period = 11U; + } else if(TIM_MSEC_DELAY == unit) { + timer_basestructure.period = 11999U; + } else { + /* no operation */ + } + + timer_basestructure.prescaler = timer_prescaler; + timer_basestructure.alignedmode = TIMER_COUNTER_EDGE; + timer_basestructure.counterdirection = TIMER_COUNTER_UP; + timer_basestructure.clockdivision = TIMER_CKDIV_DIV1; + timer_basestructure.repetitioncounter = 0U; + + timer_init(TIMER2, &timer_basestructure); + + timer_interrupt_flag_clear(TIMER2, TIMER_INT_FLAG_UP); + + timer_auto_reload_shadow_enable(TIMER2); + + /* TIMER2 interrupt enable */ + timer_interrupt_enable(TIMER2, TIMER_INT_UP); + + /* TIMER2 enable counter */ + timer_enable(TIMER2); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_it.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_it.c new file mode 100644 index 0000000..3d66bb2 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_it.c @@ -0,0 +1,264 @@ +/*! + \file gd32f5xx_it.c + \brief interrupt service routines + + \version 2024-02-19, V1.1.0, demo for GD32F5xx +*/ + +/* + Copyright (c) 2024, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx.h" +#include "gd32f5xx_it.h" +#include "FreeRTOS.h" +#include "task.h" +#include "stdint.h" +#include "semphr.h" +#include "queue.h" +#include "gd32f5xx_it.h" +#include "drv_usbd_int.h" + +#ifdef USE_USB_FS +extern usb_core_driver cdc_acm; +#endif + +extern void usb_timer_irq (void); +static void resume_mcu_clk(void); + +#define MULTI_ECC_ERROR_HANDLE(s) do{}while(1) + +/*! + \brief this function handles NMI exception + \param[in] none + \param[out] none + \retval none +*/ +void NMI_Handler(void) +{ + if((SET == syscfg_interrupt_flag_get(SYSCFG_INT_FLAG_ECCME0)) || + (SET == syscfg_interrupt_flag_get(SYSCFG_INT_FLAG_ECCME1)) || + (SET == syscfg_interrupt_flag_get(SYSCFG_INT_FLAG_ECCME2)) || + (SET == syscfg_interrupt_flag_get(SYSCFG_INT_FLAG_ECCME3)) || + (SET == syscfg_interrupt_flag_get(SYSCFG_INT_FLAG_ECCME4)) || + (SET == syscfg_interrupt_flag_get(SYSCFG_INT_FLAG_ECCME5)) || + (SET == syscfg_interrupt_flag_get(SYSCFG_INT_FLAG_ECCME6))) { + MULTI_ECC_ERROR_HANDLE("SRAM or FLASH multi-bits non-correction ECC error\r\n"); + } else { + /* if NMI exception occurs, go to infinite loop */ + /* HXTAL clock monitor NMI error */ + while(1) { + } + } +} + +/*! + \brief this function handles HardFault exception + \param[in] none + \param[out] none + \retval none +*/ +void HardFault_Handler(void) +{ + /* if Hard Fault exception occurs, go to infinite loop */ + while(1) { + } +} + +/*! + \brief this function handles MemManage exception + \param[in] none + \param[out] none + \retval none +*/ +void MemManage_Handler(void) +{ + /* if Memory Manage exception occurs, go to infinite loop */ + while(1) { + } +} + +/*! + \brief this function handles BusFault exception + \param[in] none + \param[out] none + \retval none +*/ +void BusFault_Handler(void) +{ + /* if Bus Fault exception occurs, go to infinite loop */ + while(1) { + } +} + +/*! + \brief this function handles UsageFault exception + \param[in] none + \param[out] none + \retval none +*/ +void UsageFault_Handler(void) +{ + /* if Usage Fault exception occurs, go to infinite loop */ + while(1) { + } +} + +/*! + \brief this function handles DebugMon exception + \param[in] none + \param[out] none + \retval none +*/ +void DebugMon_Handler(void) +{ + /* if DebugMon exception occurs, go to infinite loop */ + while(1) { + } +} + +/*! + \brief this function handles timer2 interrupt Handler + \param[in] none + \param[out] none + \retval none +*/ +void TIMER2_IRQHandler(void) +{ + usb_timer_irq(); +} + +#ifdef USE_USB_FS + +/*! + \brief this function handles USBFS wakeup interrupt handler + \param[in] none + \param[out] none + \retval none +*/ +void USBFS_WKUP_IRQHandler(void) +{ + if (cdc_acm.bp.low_power) { + resume_mcu_clk(); + + rcu_pll48m_clock_config(RCU_PLL48MSRC_PLLQ); + rcu_ck48m_clock_config(RCU_CK48MSRC_PLL48M); + + rcu_periph_clock_enable(RCU_USBFS); + + usb_clock_active(&cdc_acm); + } + + exti_interrupt_flag_clear(EXTI_18); +} + +#elif defined(USE_USB_HS) + +/*! + \brief this function handles USBHS wakeup interrupt handler + \param[in] none + \param[out] none + \retval none +*/ +void USBHS_WKUP_IRQHandler(void) +{ + if (cdc_acm.bp.low_power) { + resume_mcu_clk(); + + #ifdef USE_EMBEDDED_PHY + rcu_pll48m_clock_config(RCU_PLL48MSRC_PLLQ); + rcu_ck48m_clock_config(RCU_CK48MSRC_PLL48M); + #elif defined(USE_ULPI_PHY) + rcu_periph_clock_enable(RCU_USBHSULPI); + #endif + + rcu_periph_clock_enable(RCU_USBHS); + + usb_clock_active(&cdc_acm); + } + + exti_interrupt_flag_clear(EXTI_20); +} + +#endif /* USE_USBFS */ + +#ifdef USE_USB_FS + +/*! + \brief this function handles USBFS IRQ Handler + \param[in] none + \param[out] none + \retval none +*/ +void USBFS_IRQHandler(void) +{ + usbd_isr(&cdc_acm); +} + +#elif defined(USE_USB_HS) + +/*! + \brief this function handles USBHS IRQ Handler + \param[in] none + \param[out] none + \retval none +*/ +void USBHS_IRQHandler(void) +{ + usbd_isr(&cdc_acm); +} + +#endif /* USE_USBFS */ + +/*! + \brief resume mcu clock + \param[in] none + \param[out] none + \retval none +*/ +static void resume_mcu_clk(void) +{ + /* enable HXTAL */ + rcu_osci_on(RCU_HXTAL); + + /* wait till HXTAL is ready */ + while(RESET == rcu_flag_get(RCU_FLAG_HXTALSTB)){ + } + + /* enable PLL */ + rcu_osci_on(RCU_PLL_CK); + + /* wait till PLL is ready */ + while(RESET == rcu_flag_get(RCU_FLAG_PLLSTB)){ + } + + /* select PLL as system clock source */ + rcu_system_clock_source_config(RCU_CKSYSSRC_PLLP); + + /* wait till PLL is used as system clock source */ + while(RCU_SCSS_PLLP != rcu_system_clock_source_get()){ + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_it.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_it.h new file mode 100644 index 0000000..3468031 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_it.h @@ -0,0 +1,72 @@ +/*! + \file gd32f5xx_it.h + \brief the header file of the ISR + + \version 2024-02-19, V1.1.0, demo for GD32F5xx +*/ + +/* + Copyright (c) 2024, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_IT_H +#define GD32F5XX_IT_H + +#include "gd32f5xx.h" + +/* function declarations */ +/* this function handles NMI exception */ +void NMI_Handler(void); +/* this function handles HardFault exception */ +void HardFault_Handler(void); +/* this function handles MemManage exception */ +void MemManage_Handler(void); +/* this function handles BusFault exception */ +void BusFault_Handler(void); +/* this function handles UsageFault exception */ +void UsageFault_Handler(void); +/* this function handles SVC exception */ +void SVC_Handler(void); +/* this function handles DebugMon exception */ +void DebugMon_Handler(void); +/* this function handles PendSV exception */ +void PendSV_Handler(void); +/* this function handles TIMER2 IRQ Handler */ +void TIMER2_IRQHandler(void); +#ifdef USE_USB_FS +/* this function handles USB wakeup interrupt handler */ +void USBFS_WKUP_IRQHandler(void); +/* this function handles USBFS IRQ Handler */ +void USBFS_IRQHandler(void); +#endif /* USE_USB_FS */ +#ifdef USE_USB_HS +/* this function handles USB wakeup interrupt handler */ +void USBHS_WKUP_IRQHandler(void); +/* this function handles USBHS IRQ Handler */ +void USBHS_IRQHandler(void); +#endif /* USE_USB_HS */ + +#endif /* GD32F5XX_IT_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_libopt.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_libopt.h new file mode 100644 index 0000000..0bcc424 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/gd32f5xx_libopt.h @@ -0,0 +1,73 @@ +/*! + \file gd32f5xx_libopt.h + \brief library optional for gd32f5xx + + \version 2024-02-19, V1.1.0, demo for GD32F5xx +*/ + +/* + Copyright (c) 2024, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_LIBOPT_H +#define GD32F5XX_LIBOPT_H + +#include "gd32f5xx_adc.h" +#include "gd32f5xx_can.h" +#include "gd32f5xx_cau.h" +#include "gd32f5xx_crc.h" +#include "gd32f5xx_ctc.h" +#include "gd32f5xx_dac.h" +#include "gd32f5xx_dbg.h" +#include "gd32f5xx_dci.h" +#include "gd32f5xx_dma.h" +#include "gd32f5xx_enet.h" +#include "gd32f5xx_exmc.h" +#include "gd32f5xx_exti.h" +#include "gd32f5xx_fmc.h" +#include "gd32f5xx_fwdgt.h" +#include "gd32f5xx_gpio.h" +#include "gd32f5xx_hau.h" +#include "gd32f5xx_i2c.h" +#include "gd32f5xx_i2c_add.h" +#include "gd32f5xx_ipa.h" +#include "gd32f5xx_iref.h" +#include "gd32f5xx_misc.h" +#include "gd32f5xx_pkcau.h" +#include "gd32f5xx_pmu.h" +#include "gd32f5xx_rcu.h" +#include "gd32f5xx_rtc.h" +#include "gd32f5xx_sai.h" +#include "gd32f5xx_sdio.h" +#include "gd32f5xx_spi.h" +#include "gd32f5xx_syscfg.h" +#include "gd32f5xx_timer.h" +#include "gd32f5xx_tli.h" +#include "gd32f5xx_trng.h" +#include "gd32f5xx_usart.h" +#include "gd32f5xx_wwdgt.h" + +#endif /* GD32F5XX_LIBOPT_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/led.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/led.c new file mode 100644 index 0000000..719e255 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/led.c @@ -0,0 +1,81 @@ +/** + ******************************************************************** + * @file led.c + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "led.h" +#include "gd32f5xx.h" + +/* Private constants ---------------------------------------------------------*/ +#define LED_RED_GPIO_PIN GPIO_PIN_7 +#define LED_RED_GPIO_PORT GPIOC +#define LED_RED_GPIO_CLK RCU_GPIOC + +#define LED_GREEN_GPIO_PIN GPIO_PIN_6 +#define LED_GREEN_GPIO_PORT GPIOC +#define LED_GREEN_GPIO_CLK RCU_GPIOC + +#define LED_BLUE_GPIO_PIN GPIO_PIN_8 +#define LED_BLUE_GPIO_PORT GPIOC +#define LED_BLUE_GPIO_CLK RCU_GPIOC + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static uint32_t GPIO_PORT[LED_NUM] = {LED_GREEN_GPIO_PORT, LED_GREEN_GPIO_PORT, LED_GREEN_GPIO_PORT}; +static uint32_t GPIO_PIN[LED_NUM] = {LED_RED_GPIO_PIN, LED_GREEN_GPIO_PIN, LED_BLUE_GPIO_PIN}; +static rcu_periph_enum GPIO_CLK[LED_NUM] = {LED_RED_GPIO_CLK, LED_GREEN_GPIO_CLK, LED_BLUE_GPIO_CLK}; + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +void Led_Init(E_LedNum ledNum) +{ + /* Enable the led clock */ + rcu_periph_clock_enable(GPIO_CLK[ledNum]); + + /* Configure led GPIO port */ + gpio_mode_set(GPIO_PORT[ledNum], GPIO_MODE_OUTPUT, GPIO_PUPD_NONE,GPIO_PIN[ledNum]); + gpio_output_options_set(GPIO_PORT[ledNum], GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ,GPIO_PIN[ledNum]); + + GPIO_BC(GPIO_PORT[ledNum]) = GPIO_PIN[ledNum]; +} + +void Led_On(E_LedNum ledNum) +{ + GPIO_BOP(GPIO_PORT[ledNum]) = GPIO_PIN[ledNum]; +} + +void Led_Off(E_LedNum ledNum) +{ + GPIO_BC(GPIO_PORT[ledNum]) = GPIO_PIN[ledNum]; +} + +void Led_Trigger(E_LedNum ledNum) +{ + GPIO_TG(GPIO_PORT[ledNum]) = GPIO_PIN[ledNum]; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/led.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/led.h new file mode 100644 index 0000000..bb9f3f5 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/led.h @@ -0,0 +1,59 @@ + +/** + ******************************************************************** + * @file led.h + * @brief This is the header file for "led.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef LED_H +#define LED_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_platform.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +typedef enum { + LED_RED = 0, + LED_GREEN, + LED_BLUE, + LED_NUM +} E_LedNum; + +/* Exported functions --------------------------------------------------------*/ +void Led_Init(E_LedNum ledNum); +void Led_On(E_LedNum ledNum); +void Led_Off(E_LedNum ledNum); +void Led_Trigger(E_LedNum ledNum); + +#ifdef __cplusplus +} +#endif + +#endif // LED_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pps.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pps.c new file mode 100644 index 0000000..920443b --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pps.c @@ -0,0 +1,156 @@ +/** + ******************************************************************** + * @file pps.c + * @version V2.0.0 + * @date 2019/9/20 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +//#include "Gd32f4xx_hal.h" +#include "pps.h" +#include "osal.h" +#include "stdio.h" +#include "dji_logger.h" +#include "gd32f5xx.h" + +/* Private constants ---------------------------------------------------------*/ +#define PPS_IRQn EXTI5_9_IRQn +#define DjiTest_PpsIrqHandler EXTI5_9_IRQHandler +#define PPS_IRQ_PRIO_PRE 0x0F +#define PPS_IRQ_PRIO_SUB 0x0F + +#define PPS_PORT GPIOB +#define PPS_PIN GPIO_PIN_9 +#define PPS_CLK RCU_GPIOB +#define PPS_EXTI_LINE EXTI_9 +#define PPS_EXTI_PORT_SOURCE EXTI_SOURCE_GPIOB +#define PPS_EXTI_PIN_SOURCE EXTI_SOURCE_PIN9 + +#define VSYNC_PORT GPIOE +#define VSYNC_PIN GPIO_PIN_5 +#define VSYNC_CLK RCU_GPIOE +#define VSYNC_EXTI_LINE EXTI_5 +#define VSYNC_EXTI_PORT_SOURCE EXTI_SOURCE_GPIOE +#define VSYNC_EXTI_PIN_SOURCE EXTI_SOURCE_PIN5 + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static uint32_t s_ppsNewestTriggerLocalTimeMs = 0; +static uint32_t s_ppsTriggerTimeMsDiff = 0; +static uint32_t s_vsyncNewestTriggerLocalTimeMs = 0; +static uint32_t s_vsyncTriggerTimeMsDiff = 0; + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +void DjiTest_PpsIrqHandler(void) +{ + T_DjiReturnCode psdkStat; + uint32_t timeMs = 0; + + /* EXTI line interrupt detected */ + if(RESET != exti_interrupt_flag_get(PPS_EXTI_LINE)) { + // USER_LOG_INFO("Pps signal triggered."); + + psdkStat = Osal_GetTimeMs(&timeMs); + if (psdkStat == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + s_ppsTriggerTimeMsDiff = timeMs - s_ppsNewestTriggerLocalTimeMs; + s_ppsNewestTriggerLocalTimeMs = timeMs; + } + exti_interrupt_flag_clear(PPS_EXTI_LINE); + } + + /* EXTI line interrupt detected */ + if(RESET != exti_interrupt_flag_get(VSYNC_EXTI_LINE)) { + // USER_LOG_INFO("Vsync signal triggered."); + + psdkStat = Osal_GetTimeMs(&timeMs); + if (psdkStat == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { + s_vsyncTriggerTimeMsDiff = timeMs - s_vsyncNewestTriggerLocalTimeMs; + s_vsyncNewestTriggerLocalTimeMs = timeMs; + } + exti_interrupt_flag_clear(VSYNC_EXTI_LINE); + } +} + +uint32_t DjiTest_GetPpsTriggerTimeMsDiff(void) +{ + return s_ppsTriggerTimeMsDiff; +} + +uint32_t DjiTest_GetVsyncTriggerTimeMsDiff(void) +{ + return s_vsyncTriggerTimeMsDiff; +} + +T_DjiReturnCode DjiTest_GetNewestPpsTriggerLocalTimeUs(uint64_t *localTimeUs) +{ + if (localTimeUs == NULL) { + USER_LOG_ERROR("input pointer is null."); + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + if (s_ppsNewestTriggerLocalTimeMs == 0) { + USER_LOG_WARN("pps have not been triggered."); + return DJI_ERROR_SYSTEM_MODULE_CODE_BUSY; + } + + *localTimeUs = s_ppsNewestTriggerLocalTimeMs * 1000; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiTest_PpsSignalResponseInit(void) +{ + /* Enable the pps clock */ + rcu_periph_clock_enable(PPS_CLK); + rcu_periph_clock_enable(RCU_SYSCFG); + + /* Configure pps pin as input */ + gpio_mode_set(PPS_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE, PPS_PIN); + + /* Enable and set pps EXTI interrupt to the lowest priority */ + nvic_irq_enable(PPS_IRQn, PPS_IRQ_PRIO_PRE, PPS_IRQ_PRIO_SUB); + + /* Connect pps EXTI line to key GPIO pin */ + syscfg_exti_line_config(PPS_EXTI_PORT_SOURCE, PPS_EXTI_PIN_SOURCE); + + /* Configure pps EXTI line */ + exti_init(PPS_EXTI_LINE, EXTI_INTERRUPT, EXTI_TRIG_RISING); + exti_interrupt_flag_clear(PPS_EXTI_LINE); + + /* Enable the pps clock */ + rcu_periph_clock_enable(VSYNC_CLK); + /* Configure pps pin as input */ + gpio_mode_set(VSYNC_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE, VSYNC_PIN); + /* Connect pps EXTI line to key GPIO pin */ + syscfg_exti_line_config(VSYNC_EXTI_PORT_SOURCE, VSYNC_EXTI_PIN_SOURCE); + /* Configure pps EXTI line */ + exti_init(VSYNC_EXTI_LINE, EXTI_INTERRUPT, EXTI_TRIG_RISING); + exti_interrupt_flag_clear(VSYNC_EXTI_LINE); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pps.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pps.h new file mode 100644 index 0000000..9ab52c0 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pps.h @@ -0,0 +1,52 @@ +/** + ******************************************************************** + * @file pps.h + * @version V2.0.0 + * @date 2019/9/20 + * @brief This is the header file for "pps.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef PPS_H +#define PPS_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode DjiTest_GetNewestPpsTriggerLocalTimeUs(uint64_t *localTimeUs); +T_DjiReturnCode DjiTest_PpsSignalResponseInit(void); + +#ifdef __cplusplus +} +#endif + +#endif // PPS_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pwm.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pwm.c new file mode 100644 index 0000000..9c46c99 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pwm.c @@ -0,0 +1,113 @@ +/** + ******************************************************************** + * @file pwm.c + * @version V1.0.0 + * @date 2024/05/22 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + + +/* Includes ------------------------------------------------------------------*/ +#include "pwm.h" +#include "gd32f5xx.h" + +/* Private constants ---------------------------------------------------------*/ + +/* Private types -------------------------------------------------------------*/ +static uint32_t period = 0; +static uint32_t duty_pluse = 0; + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +void Pwm_Init(E_PwmNum pwmNum, uint32_t freq, uint32_t duty) +{ + rcu_periph_clock_enable(RCU_GPIOA); + timer_oc_parameter_struct timer_ocintpara; + timer_parameter_struct timer_initpara; + + if (duty > 100) + { + return; + } + + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_2); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_2); + + gpio_af_set(GPIOA, GPIO_AF_1, GPIO_PIN_2); + + rcu_periph_clock_enable(RCU_TIMER1); + rcu_timer_clock_prescaler_config(RCU_TIMER_PSC_MUL4); + timer_deinit(TIMER1); + + /* ----------------------------------------------------------------------- + TIMER1 configuration: generate 3 PWM signals with 3 different duty cycles: + TIMER1CLK = SystemCoreClock / 200 = 1MHz + ----------------------------------------------------------------------- */ + period = 1000000 / freq - 1; + + /* TIMER1 configuration */ + timer_initpara.prescaler = 199; + timer_initpara.alignedmode = TIMER_COUNTER_EDGE; + timer_initpara.counterdirection = TIMER_COUNTER_UP; + timer_initpara.period = period; + timer_initpara.clockdivision = TIMER_CKDIV_DIV1; + timer_initpara.repetitioncounter = 0; + timer_init(TIMER1, &timer_initpara); + + /* CH1,CH2 and CH3 configuration in PWM mode */ + timer_ocintpara.ocpolarity = TIMER_OC_POLARITY_HIGH; + timer_ocintpara.outputstate = TIMER_CCX_ENABLE; + timer_ocintpara.ocnpolarity = TIMER_OCN_POLARITY_HIGH; + timer_ocintpara.outputnstate = TIMER_CCXN_DISABLE; + timer_ocintpara.ocidlestate = TIMER_OC_IDLE_STATE_LOW; + timer_ocintpara.ocnidlestate = TIMER_OCN_IDLE_STATE_LOW; + + timer_channel_output_config(TIMER1, TIMER_CH_2, &timer_ocintpara); + + duty_pluse = (float)((period + 1) / 100) * duty; + timer_channel_output_pulse_value_config(TIMER1, TIMER_CH_2, duty_pluse); + timer_channel_output_mode_config(TIMER1, TIMER_CH_2, TIMER_OC_MODE_PWM0); + timer_channel_output_shadow_config(TIMER1, TIMER_CH_2, TIMER_OC_SHADOW_DISABLE); + + /* auto-reload preload enable */ + timer_auto_reload_shadow_enable(TIMER1); + /* auto-reload preload enable */ + timer_enable(TIMER1); +} + +void Pwm_SetDuty(uint32_t duty) +{ + duty_pluse = (float)((period + 1) / 100) * duty; + timer_channel_output_pulse_value_config(TIMER1, TIMER_CH_2, duty_pluse); + timer_channel_output_mode_config(TIMER1, TIMER_CH_2, TIMER_OC_MODE_PWM0); + timer_channel_output_shadow_config(TIMER1, TIMER_CH_2, TIMER_OC_SHADOW_DISABLE); + + /* auto-reload preload enable */ + timer_auto_reload_shadow_enable(TIMER1); + /* auto-reload preload enable */ + timer_enable(TIMER1); +} + +/* Private functions definition-----------------------------------------------*/ + + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pwm.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pwm.h new file mode 100644 index 0000000..96bf5ea --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/pwm.h @@ -0,0 +1,59 @@ +/** + ******************************************************************** + * @file pwm.h + * @version V1.0.0 + * @date 2024/05/22 + * @brief This is the header file for "pwm.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef PWM_H +#define PWM_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include + +/* Exported constants --------------------------------------------------------*/ + + +/* Exported types ------------------------------------------------------------*/ +typedef enum +{ + PWM_FTS = 0, + PWM_NUM, +} E_PwmNum; + +/* Exported functions --------------------------------------------------------*/ +void Pwm_Init(E_PwmNum pwmNum, uint32_t freq, uint32_t duty); +void Pwm_SetDuty(uint32_t duty); + +#ifdef __cplusplus +} +#endif + +#endif // PWM_H + +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/startup_gd32f5xx.s b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/startup_gd32f5xx.s new file mode 100644 index 0000000..c4cd549 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/startup_gd32f5xx.s @@ -0,0 +1,495 @@ +;/*! +; \file startup_gd32f5xx.s +; \brief start up file +; +; \version 2024-02-19, V1.1.0, demo for GD32F5xx +;*/ +; +;/* +; * Copyright (c) 2009-2018 Arm Limited. All rights reserved. +; * Copyright (c) 2024, GigaDevice Semiconductor Inc. +; * +; * 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. +; */ +; +;/* This file refers the CMSIS standard, some adjustments are made according to GigaDevice chips */ + +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000800 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000400 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + +; /* reset Vector Mapped to at Address 0 */ + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + +; /* external interrupts handler */ + DCD WWDGT_IRQHandler ; 16:Window Watchdog Timer + DCD LVD_IRQHandler ; 17:LVD through EXTI Line detect + DCD TAMPER_STAMP_IRQHandler ; 18:Tamper and TimeStamp through EXTI Line detect + DCD RTC_WKUP_IRQHandler ; 19:RTC Wakeup through EXTI Line + DCD FMC_IRQHandler ; 20:FMC + DCD RCU_CTC_IRQHandler ; 21:RCU and CTC + DCD EXTI0_IRQHandler ; 22:EXTI Line 0 + DCD EXTI1_IRQHandler ; 23:EXTI Line 1 + DCD EXTI2_IRQHandler ; 24:EXTI Line 2 + DCD EXTI3_IRQHandler ; 25:EXTI Line 3 + DCD EXTI4_IRQHandler ; 26:EXTI Line 4 + DCD DMA0_Channel0_IRQHandler ; 27:DMA0 Channel0 + DCD DMA0_Channel1_IRQHandler ; 28:DMA0 Channel1 + DCD DMA0_Channel2_IRQHandler ; 29:DMA0 Channel2 + DCD DMA0_Channel3_IRQHandler ; 30:DMA0 Channel3 + DCD DMA0_Channel4_IRQHandler ; 31:DMA0 Channel4 + DCD DMA0_Channel5_IRQHandler ; 32:DMA0 Channel5 + DCD DMA0_Channel6_IRQHandler ; 33:DMA0 Channel6 + DCD ADC_IRQHandler ; 34:ADC + DCD CAN0_TX_IRQHandler ; 35:CAN0 TX + DCD CAN0_RX0_IRQHandler ; 36:CAN0 RX0 + DCD CAN0_RX1_IRQHandler ; 37:CAN0 RX1 + DCD CAN0_EWMC_IRQHandler ; 38:CAN0 EWMC + DCD EXTI5_9_IRQHandler ; 39:EXTI5 to EXTI9 + DCD TIMER0_BRK_TIMER8_IRQHandler ; 40:TIMER0 Break and TIMER8 + DCD TIMER0_UP_TIMER9_IRQHandler ; 41:TIMER0 Update and TIMER9 + DCD TIMER0_TRG_CMT_TIMER10_IRQHandler ; 42:TIMER0 Trigger and Commutation and TIMER10 + DCD TIMER0_Channel_IRQHandler ; 43:TIMER0 Capture Compare + DCD TIMER1_IRQHandler ; 44:TIMER1 + DCD TIMER2_IRQHandler ; 45:TIMER2 + DCD TIMER3_IRQHandler ; 46:TIMER3 + DCD I2C0_EV_IRQHandler ; 47:I2C0 Event + DCD I2C0_ER_IRQHandler ; 48:I2C0 Error + DCD I2C1_EV_IRQHandler ; 49:I2C1 Event + DCD I2C1_ER_IRQHandler ; 50:I2C1 Error + DCD SPI0_IRQHandler ; 51:SPI0 + DCD SPI1_IRQHandler ; 52:SPI1 + DCD USART0_IRQHandler ; 53:USART0 + DCD USART1_IRQHandler ; 54:USART1 + DCD USART2_IRQHandler ; 55:USART2 + DCD EXTI10_15_IRQHandler ; 56:EXTI10 to EXTI15 + DCD RTC_Alarm_IRQHandler ; 57:RTC Alarm + DCD USBFS_WKUP_IRQHandler ; 58:USBFS Wakeup + DCD TIMER7_BRK_TIMER11_IRQHandler ; 59:TIMER7 Break and TIMER11 + DCD TIMER7_UP_TIMER12_IRQHandler ; 60:TIMER7 Update and TIMER12 + DCD TIMER7_TRG_CMT_TIMER13_IRQHandler ; 61:TIMER7 Trigger and Commutation and TIMER13 + DCD TIMER7_Channel_IRQHandler ; 62:TIMER7 Channel Capture Compare + DCD DMA0_Channel7_IRQHandler ; 63:DMA0 Channel7 + DCD EXMC_IRQHandler ; 64:EXMC + DCD SDIO_IRQHandler ; 65:SDIO + DCD TIMER4_IRQHandler ; 66:TIMER4 + DCD SPI2_IRQHandler ; 67:SPI2 + DCD UART3_IRQHandler ; 68:UART3 + DCD UART4_IRQHandler ; 69:UART4 + DCD TIMER5_DAC_IRQHandler ; 70:TIMER5 and DAC0 DAC1 Underrun error + DCD TIMER6_IRQHandler ; 71:TIMER6 + DCD DMA1_Channel0_IRQHandler ; 72:DMA1 Channel0 + DCD DMA1_Channel1_IRQHandler ; 73:DMA1 Channel1 + DCD DMA1_Channel2_IRQHandler ; 74:DMA1 Channel2 + DCD DMA1_Channel3_IRQHandler ; 75:DMA1 Channel3 + DCD DMA1_Channel4_IRQHandler ; 76:DMA1 Channel4 + DCD ENET_IRQHandler ; 77:Ethernet + DCD ENET_WKUP_IRQHandler ; 78:Ethernet Wakeup through EXTI Line + DCD CAN1_TX_IRQHandler ; 79:CAN1 TX + DCD CAN1_RX0_IRQHandler ; 80:CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; 81:CAN1 RX1 + DCD CAN1_EWMC_IRQHandler ; 82:CAN1 EWMC + DCD USBFS_IRQHandler ; 83:USBFS + DCD DMA1_Channel5_IRQHandler ; 84:DMA1 Channel5 + DCD DMA1_Channel6_IRQHandler ; 85:DMA1 Channel6 + DCD DMA1_Channel7_IRQHandler ; 86:DMA1 Channel7 + DCD USART5_IRQHandler ; 87:USART5 + DCD I2C2_EV_IRQHandler ; 88:I2C2 Event + DCD I2C2_ER_IRQHandler ; 89:I2C2 Error + DCD USBHS_EP1_Out_IRQHandler ; 90:USBHS Endpoint 1 Out + DCD USBHS_EP1_In_IRQHandler ; 91:USBHS Endpoint 1 in + DCD USBHS_WKUP_IRQHandler ; 92:USBHS Wakeup through EXTI Line + DCD USBHS_IRQHandler ; 93:USBHS + DCD DCI_IRQHandler ; 94:DCI + DCD 0 ; 95:Reserved + DCD TRNG_IRQHandler ; 96:TRNG + DCD FPU_IRQHandler ; 97:FPU + DCD UART6_IRQHandler ; 98:UART6 + DCD UART7_IRQHandler ; 99:UART7 + DCD SPI3_IRQHandler ; 100:SPI3 + DCD SPI4_IRQHandler ; 101:SPI4 + DCD SPI5_IRQHandler ; 102:SPI5 + DCD SAI_IRQHandler ; 103:SAI + DCD TLI_IRQHandler ; 104:TLI + DCD TLI_ER_IRQHandler ; 105:TLI Error + DCD IPA_IRQHandler ; 106:IPA + DCD PKCAU_IRQHandler ; 107:PKCAU + DCD I2C3_EV_IRQHandler ; 108:I2C3 Event + DCD I2C3_ER_IRQHandler ; 109:I2C3 Error + DCD I2C4_EV_IRQHandler ; 110:I2C4 Event + DCD I2C4_ER_IRQHandler ; 111:I2C4 Error + DCD I2C5_EV_IRQHandler ; 112:I2C5 Event + DCD I2C5_ER_IRQHandler ; 113:I2C5 Error + DCD I2C3_WKUP_IRQHandler ; 114:I2C3 Wakeup through EXTI Line + DCD I2C4_WKUP_IRQHandler ; 115:I2C4 Wakeup through EXTI Line + DCD I2C5_WKUP_IRQHandler ; 116:I2C5 Wakeup through EXTI Line + DCD SYSCFG_SRAM_ECC_ER_IRQHandler ; 117:SYSCFG SRAM ECC Error + DCD HAU_IRQHandler ; 118:HAU + DCD CAU_IRQHandler ; 119:CAU + +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +;/* reset Handler */ +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + IMPORT |Image$$RW_IRAM1$$RW$$Base| + + LDR R0, =|Image$$RW_IRAM1$$RW$$Base| + ADD R1, R0, #0x8000 + LDR R2, =0x0 +MEM_INIT STRD R2, R2, [ R0 ] , #8 + CMP R0, R1 + BNE MEM_INIT + + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +;/* dummy Exception Handlers */ +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler\ + PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler\ + PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC +; /* external interrupts handler */ + EXPORT WWDGT_IRQHandler [WEAK] + EXPORT LVD_IRQHandler [WEAK] + EXPORT TAMPER_STAMP_IRQHandler [WEAK] + EXPORT RTC_WKUP_IRQHandler [WEAK] + EXPORT FMC_IRQHandler [WEAK] + EXPORT RCU_CTC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA0_Channel0_IRQHandler [WEAK] + EXPORT DMA0_Channel1_IRQHandler [WEAK] + EXPORT DMA0_Channel2_IRQHandler [WEAK] + EXPORT DMA0_Channel3_IRQHandler [WEAK] + EXPORT DMA0_Channel4_IRQHandler [WEAK] + EXPORT DMA0_Channel5_IRQHandler [WEAK] + EXPORT DMA0_Channel6_IRQHandler [WEAK] + EXPORT ADC_IRQHandler [WEAK] + EXPORT CAN0_TX_IRQHandler [WEAK] + EXPORT CAN0_RX0_IRQHandler [WEAK] + EXPORT CAN0_RX1_IRQHandler [WEAK] + EXPORT CAN0_EWMC_IRQHandler [WEAK] + EXPORT EXTI5_9_IRQHandler [WEAK] + EXPORT TIMER0_BRK_TIMER8_IRQHandler [WEAK] + EXPORT TIMER0_UP_TIMER9_IRQHandler [WEAK] + EXPORT TIMER0_TRG_CMT_TIMER10_IRQHandler [WEAK] + EXPORT TIMER0_Channel_IRQHandler [WEAK] + EXPORT TIMER1_IRQHandler [WEAK] + EXPORT TIMER2_IRQHandler [WEAK] + EXPORT TIMER3_IRQHandler [WEAK] + EXPORT I2C0_EV_IRQHandler [WEAK] + EXPORT I2C0_ER_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT SPI0_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT USART0_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT EXTI10_15_IRQHandler [WEAK] + EXPORT RTC_Alarm_IRQHandler [WEAK] + EXPORT USBFS_WKUP_IRQHandler [WEAK] + EXPORT TIMER7_BRK_TIMER11_IRQHandler [WEAK] + EXPORT TIMER7_UP_TIMER12_IRQHandler [WEAK] + EXPORT TIMER7_TRG_CMT_TIMER13_IRQHandler [WEAK] + EXPORT TIMER7_Channel_IRQHandler [WEAK] + EXPORT DMA0_Channel7_IRQHandler [WEAK] + EXPORT EXMC_IRQHandler [WEAK] + EXPORT SDIO_IRQHandler [WEAK] + EXPORT TIMER4_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT UART3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT TIMER5_DAC_IRQHandler [WEAK] + EXPORT TIMER6_IRQHandler [WEAK] + EXPORT DMA1_Channel0_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT ENET_IRQHandler [WEAK] + EXPORT ENET_WKUP_IRQHandler [WEAK] + EXPORT CAN1_TX_IRQHandler [WEAK] + EXPORT CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_EWMC_IRQHandler [WEAK] + EXPORT USBFS_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT USART5_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT USBHS_EP1_Out_IRQHandler [WEAK] + EXPORT USBHS_EP1_In_IRQHandler [WEAK] + EXPORT USBHS_WKUP_IRQHandler [WEAK] + EXPORT USBHS_IRQHandler [WEAK] + EXPORT DCI_IRQHandler [WEAK] + EXPORT TRNG_IRQHandler [WEAK] + EXPORT FPU_IRQHandler [WEAK] + EXPORT UART6_IRQHandler [WEAK] + EXPORT UART7_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT SPI4_IRQHandler [WEAK] + EXPORT SPI5_IRQHandler [WEAK] + EXPORT SAI_IRQHandler [WEAK] + EXPORT TLI_IRQHandler [WEAK] + EXPORT TLI_ER_IRQHandler [WEAK] + EXPORT IPA_IRQHandler [WEAK] + EXPORT PKCAU_IRQHandler [WEAK] + EXPORT I2C3_EV_IRQHandler [WEAK] + EXPORT I2C3_ER_IRQHandler [WEAK] + EXPORT I2C4_EV_IRQHandler [WEAK] + EXPORT I2C4_ER_IRQHandler [WEAK] + EXPORT I2C5_EV_IRQHandler [WEAK] + EXPORT I2C5_ER_IRQHandler [WEAK] + EXPORT I2C3_WKUP_IRQHandler [WEAK] + EXPORT I2C4_WKUP_IRQHandler [WEAK] + EXPORT I2C5_WKUP_IRQHandler [WEAK] + EXPORT SYSCFG_SRAM_ECC_ER_IRQHandler [WEAK] + EXPORT HAU_IRQHandler [WEAK] + EXPORT CAU_IRQHandler [WEAK] + +;/* external interrupts handler */ +WWDGT_IRQHandler +LVD_IRQHandler +TAMPER_STAMP_IRQHandler +RTC_WKUP_IRQHandler +FMC_IRQHandler +RCU_CTC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA0_Channel0_IRQHandler +DMA0_Channel1_IRQHandler +DMA0_Channel2_IRQHandler +DMA0_Channel3_IRQHandler +DMA0_Channel4_IRQHandler +DMA0_Channel5_IRQHandler +DMA0_Channel6_IRQHandler +ADC_IRQHandler +CAN0_TX_IRQHandler +CAN0_RX0_IRQHandler +CAN0_RX1_IRQHandler +CAN0_EWMC_IRQHandler +EXTI5_9_IRQHandler +TIMER0_BRK_TIMER8_IRQHandler +TIMER0_UP_TIMER9_IRQHandler +TIMER0_TRG_CMT_TIMER10_IRQHandler +TIMER0_Channel_IRQHandler +TIMER1_IRQHandler +TIMER2_IRQHandler +TIMER3_IRQHandler +I2C0_EV_IRQHandler +I2C0_ER_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +SPI0_IRQHandler +SPI1_IRQHandler +USART0_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +EXTI10_15_IRQHandler +RTC_Alarm_IRQHandler +USBFS_WKUP_IRQHandler +TIMER7_BRK_TIMER11_IRQHandler +TIMER7_UP_TIMER12_IRQHandler +TIMER7_TRG_CMT_TIMER13_IRQHandler +TIMER7_Channel_IRQHandler +DMA0_Channel7_IRQHandler +EXMC_IRQHandler +SDIO_IRQHandler +TIMER4_IRQHandler +SPI2_IRQHandler +UART3_IRQHandler +UART4_IRQHandler +TIMER5_DAC_IRQHandler +TIMER6_IRQHandler +DMA1_Channel0_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +ENET_IRQHandler +ENET_WKUP_IRQHandler +CAN1_TX_IRQHandler +CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_EWMC_IRQHandler +USBFS_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +USART5_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +USBHS_EP1_Out_IRQHandler +USBHS_EP1_In_IRQHandler +USBHS_WKUP_IRQHandler +USBHS_IRQHandler +DCI_IRQHandler +TRNG_IRQHandler +FPU_IRQHandler +UART6_IRQHandler +UART7_IRQHandler +SPI3_IRQHandler +SPI4_IRQHandler +SPI5_IRQHandler +SAI_IRQHandler +TLI_IRQHandler +TLI_ER_IRQHandler +IPA_IRQHandler +PKCAU_IRQHandler +I2C3_EV_IRQHandler +I2C3_ER_IRQHandler +I2C4_EV_IRQHandler +I2C4_ER_IRQHandler +I2C5_EV_IRQHandler +I2C5_ER_IRQHandler +I2C3_WKUP_IRQHandler +I2C4_WKUP_IRQHandler +I2C5_WKUP_IRQHandler +SYSCFG_SRAM_ECC_ER_IRQHandler +HAU_IRQHandler +CAU_IRQHandler + + B . + ENDP + + ALIGN + +; user Initial Stack & Heap + + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap PROC + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + ENDP + + ALIGN + + ENDIF + + END diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/uart.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/uart.c new file mode 100644 index 0000000..631c1c8 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/uart.c @@ -0,0 +1,490 @@ +/** + ****************************************************************************** + * @file uart.c + * @version V1.0.0 + * @date 2017/11/10 + * @brief The file define UART interface driver functions. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "uart.h" +#include "dji_ringbuffer.h" +#include "FreeRTOS.h" +#include "task.h" +#include "osal.h" +#include "gd32f5xx.h" + +/* Private typedef -----------------------------------------------------------*/ + + +/* Private define ------------------------------------------------------------*/ +//uart uart buffer size define +#define UART1_READ_BUF_SIZE 2048 +#define UART1_WRITE_BUF_SIZE 4096 +#define UART2_READ_BUF_SIZE 2048 +#define UART2_WRITE_BUF_SIZE 2048 +#define UART3_READ_BUF_SIZE 1024 +#define UART3_WRITE_BUF_SIZE 4096 + +/* Private macro -------------------------------------------------------------*/ + + +/* Private variables ---------------------------------------------------------*/ +#ifdef USING_UART_PORT_1 +//UART1 read ring buffer structure +static T_RingBuffer s_uart1ReadRingBuffer; +//USART1 read buffer state +static T_UartBufferState s_uart1ReadBufferState; +//UART1 write ring buffer structure +static T_RingBuffer s_uart1WriteRingBuffer; +//USART1 write buffer state +static T_UartBufferState s_uart1WriteBufferState; +//UART1 read buffer +static uint8_t s_uart1ReadBuf[UART1_READ_BUF_SIZE]; +//UART1 write buffer +static uint8_t s_uart1WriteBuf[UART1_WRITE_BUF_SIZE]; + +//UART1 mutex +static T_DjiMutexHandle s_uart1Mutex; +//USART1 handle +//static UART_HandleTypeDef s_uart1Handle; +#endif + +#ifdef USING_UART_PORT_2 +static T_RingBuffer s_uart2ReadRingBuffer; +static T_UartBufferState s_uart2ReadBufferState; +static T_RingBuffer s_uart2WriteRingBuffer; +static T_UartBufferState s_uart2WriteBufferState; +static uint8_t s_uart2ReadBuf[UART2_READ_BUF_SIZE]; +static uint8_t s_uart2WriteBuf[UART2_WRITE_BUF_SIZE]; + +static T_DjiMutexHandle s_uart2Mutex; +//static UART_HandleTypeDef s_uart2Handle; +#endif + +#ifdef USING_UART_PORT_3 +static T_RingBuffer s_uart3ReadRingBuffer; +static T_UartBufferState s_uart3ReadBufferState; +static T_RingBuffer s_uart3WriteRingBuffer; +static T_UartBufferState s_uart3WriteBufferState; +static uint8_t s_uart3ReadBuf[UART3_READ_BUF_SIZE]; +static uint8_t s_uart3WriteBuf[UART3_WRITE_BUF_SIZE]; + +static T_DjiMutexHandle s_uart3Mutex; +//static UART_HandleTypeDef s_uart3Handle; +#endif + +/* Exported variables --------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** + * @brief UART initialization function. + * @param uartNum UART number to be initialized. + * @param baudRate UART baudrate. + * @return None. + */ +void UART_Init(E_UartNum uartNum, uint32_t baudRate) +{ + switch (uartNum) { + +#ifdef USING_UART_PORT_1 + case UART_NUM_1: { + RingBuf_Init(&s_uart1ReadRingBuffer, s_uart1ReadBuf, UART1_READ_BUF_SIZE); + RingBuf_Init(&s_uart1WriteRingBuffer, s_uart1WriteBuf, UART1_WRITE_BUF_SIZE); + + rcu_periph_clock_enable(RCU_GPIOA); + rcu_periph_clock_enable(RCU_USART0); + + gpio_af_set(GPIOA, GPIO_AF_7, GPIO_PIN_9); + gpio_af_set(GPIOA, GPIO_AF_7, GPIO_PIN_10); + + /* configure USART Tx as alternate function push-pull */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_PULLUP,GPIO_PIN_9); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ,GPIO_PIN_9); + + /* configure USART Rx as alternate function push-pull */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_PULLUP, GPIO_PIN_10); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_10); + + nvic_irq_enable(USART0_IRQn, 0, 0); + + /* USART configure */ + usart_deinit(USART0); + usart_baudrate_set(USART0,baudRate); + usart_receive_config(USART0, USART_RECEIVE_ENABLE); + usart_transmit_config(USART0, USART_TRANSMIT_ENABLE); + usart_enable(USART0); + usart_interrupt_enable(USART0, USART_INT_RBNE); + + Osal_MutexCreate(&s_uart1Mutex); + } + break; +#endif + +#ifdef USING_UART_PORT_2 + case UART_NUM_2: { + RingBuf_Init(&s_uart2ReadRingBuffer, s_uart2ReadBuf, UART2_READ_BUF_SIZE); + RingBuf_Init(&s_uart2WriteRingBuffer, s_uart2WriteBuf, UART2_WRITE_BUF_SIZE); + +// s_uart2Handle.Instance = USART2; +// s_uart2Handle.Init.BaudRate = baudRate; +// s_uart2Handle.Init.WordLength = UART_WORDLENGTH_8B; +// s_uart2Handle.Init.StopBits = UART_STOPBITS_1; +// s_uart2Handle.Init.Parity = UART_PARITY_NONE; +// s_uart2Handle.Init.HwFlowCtl = UART_HWCONTROL_NONE; +// s_uart2Handle.Init.Mode = UART_MODE_TX_RX; +// s_uart2Handle.Init.OverSampling = UART_OVERSAMPLING_16; +// HAL_UART_Init(&s_uart2Handle); +// __HAL_UART_ENABLE_IT(&s_uart2Handle, UART_IT_RXNE); + + Osal_MutexCreate(&s_uart2Mutex); + } + break; +#endif + +#ifdef USING_UART_PORT_3 + case UART_NUM_3: { + RingBuf_Init(&s_uart3ReadRingBuffer, s_uart3ReadBuf, UART3_READ_BUF_SIZE); + RingBuf_Init(&s_uart3WriteRingBuffer, s_uart3WriteBuf, UART3_WRITE_BUF_SIZE); + + rcu_periph_clock_enable(RCU_GPIOA); + rcu_periph_clock_enable(RCU_UART3); + + gpio_af_set(GPIOA, GPIO_AF_8, GPIO_PIN_0); + gpio_af_set(GPIOA, GPIO_AF_8, GPIO_PIN_1); + + /* configure USART Tx as alternate function push-pull */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_PULLUP, GPIO_PIN_0); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_0); + + /* configure USART Rx as alternate function push-pull */ + gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_PULLUP, GPIO_PIN_1); + gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_1); + + nvic_irq_enable(UART3_IRQn, 0, 0); + + /* USART configure */ + usart_deinit(UART3); + usart_baudrate_set(UART3,baudRate); + usart_receive_config(UART3, USART_RECEIVE_ENABLE); + usart_transmit_config(UART3, USART_TRANSMIT_ENABLE); + usart_enable(UART3); + usart_interrupt_enable(UART3, USART_INT_RBNE); + + Osal_MutexCreate(&s_uart3Mutex); + } + break; +#endif + + default: + break; + } +} + +/** + * @brief Read UART data. + * @param uartNum UART number. + * @param buf Pointer to buffer used to store data. + * @param readSize Size of data to be read. + * @return Size of data read actually. + */ +int UART_Read(E_UartNum uartNum, uint8_t *buf, uint16_t readSize) +{ + uint16_t readRealSize; + + switch (uartNum) { + +#ifdef USING_UART_PORT_1 + case UART_NUM_1: { + Osal_MutexLock(s_uart1Mutex); + readRealSize = RingBuf_Get(&s_uart1ReadRingBuffer, buf, readSize); + Osal_MutexUnlock(s_uart1Mutex); + } + break; +#endif + +#ifdef USING_UART_PORT_2 + case UART_NUM_2: { + Osal_MutexLock(s_uart2Mutex); + readRealSize = RingBuf_Get(&s_uart2ReadRingBuffer, buf, readSize); + Osal_MutexUnlock(s_uart2Mutex); + } + break; +#endif + +#ifdef USING_UART_PORT_3 + case UART_NUM_3: { + Osal_MutexLock(s_uart3Mutex); + readRealSize = RingBuf_Get(&s_uart3ReadRingBuffer, buf, readSize); + Osal_MutexUnlock(s_uart3Mutex); + } + break; +#endif + + default: + return UART_ERROR; + } + + return readRealSize; +} + +/** + * @brief Write UART data. + * @param uartNum UART number. + * @param buf Pointer to buffer used to store data. + * @param writeSize Size of data to be write. + * @return Size of data wrote actually. + */ +int UART_Write(E_UartNum uartNum, const uint8_t *buf, uint16_t writeSize) +{ + int writeRealLen; + uint16_t usedCapacityOfBuffer = 0; + + switch (uartNum) { + +#ifdef USING_UART_PORT_1 + case UART_NUM_1: { + Osal_MutexLock(s_uart1Mutex); + writeRealLen = RingBuf_Put(&s_uart1WriteRingBuffer, buf, writeSize); + + /* enable USART TBE interrupt */ + usart_interrupt_enable(USART0, USART_INT_TBE); + usedCapacityOfBuffer = UART1_WRITE_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart1WriteRingBuffer); + s_uart1WriteBufferState.maxUsedCapacityOfBuffer = + usedCapacityOfBuffer > s_uart1WriteBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + : s_uart1WriteBufferState.maxUsedCapacityOfBuffer; + s_uart1WriteBufferState.countOfLostData += writeSize - writeRealLen; + Osal_MutexUnlock(s_uart1Mutex); + } + break; +#endif + +#ifdef USING_UART_PORT_2 + case UART_NUM_2: { +// Osal_MutexLock(s_uart2Mutex); +// writeRealLen = RingBuf_Put(&s_uart2WriteRingBuffer, buf, writeSize); +// __HAL_USART_ENABLE_IT(&s_uart2Handle, USART_IT_TXE); +// usedCapacityOfBuffer = UART2_WRITE_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart2WriteRingBuffer); +// s_uart2WriteBufferState.maxUsedCapacityOfBuffer = +// usedCapacityOfBuffer > s_uart2WriteBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer +// : s_uart2WriteBufferState.maxUsedCapacityOfBuffer; +// s_uart2WriteBufferState.countOfLostData += writeSize - writeRealLen; +// Osal_MutexUnlock(s_uart2Mutex); + } + break; +#endif + +#ifdef USING_UART_PORT_3 + case UART_NUM_3: { + Osal_MutexLock(s_uart3Mutex); + writeRealLen = RingBuf_Put(&s_uart3WriteRingBuffer, buf, writeSize); + + /* enable USART TBE interrupt */ + usart_interrupt_enable(UART3, USART_INT_TBE); + usedCapacityOfBuffer = UART3_WRITE_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart3WriteRingBuffer); + s_uart3WriteBufferState.maxUsedCapacityOfBuffer = + usedCapacityOfBuffer > s_uart3WriteBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + : s_uart3WriteBufferState.maxUsedCapacityOfBuffer; + s_uart3WriteBufferState.countOfLostData += writeSize - writeRealLen; + Osal_MutexUnlock(s_uart3Mutex); + } + break; +#endif + + default: + return UART_ERROR; + } + + return writeRealLen; +} + +void UART_GetBufferState(E_UartNum uartNum, T_UartBufferState *readBufferState, T_UartBufferState *writeBufferState) +{ + switch (uartNum) { +#ifdef USING_UART_PORT_1 + case UART_NUM_1: + memcpy(readBufferState, &s_uart1ReadBufferState, sizeof(T_UartBufferState)); + memcpy(writeBufferState, &s_uart1WriteBufferState, sizeof(T_UartBufferState)); + break; +#endif +#ifdef USING_UART_PORT_2 + case UART_NUM_2: + memcpy(readBufferState, &s_uart2ReadBufferState, sizeof(T_UartBufferState)); + memcpy(writeBufferState, &s_uart2WriteBufferState, sizeof(T_UartBufferState)); + break; +#endif +#ifdef USING_UART_PORT_3 + case UART_NUM_3: + memcpy(readBufferState, &s_uart3ReadBufferState, sizeof(T_UartBufferState)); + memcpy(writeBufferState, &s_uart3WriteBufferState, sizeof(T_UartBufferState)); + break; +#endif + default: + break; + } +} + +/** + * @brief UART1 interrupt request handler fucntion. + */ +#ifdef USING_UART_PORT_1 + +void USART0_IRQHandler(void) +{ + uint8_t data; + uint16_t usedCapacityOfBuffer = 0; + uint16_t realCountPutBuffer = 0; + + if((RESET != usart_interrupt_flag_get(USART0, USART_INT_FLAG_RBNE)) && + (RESET != usart_flag_get(USART0, USART_FLAG_RBNE))) { + data = usart_data_receive(USART0); + realCountPutBuffer = RingBuf_Put(&s_uart1ReadRingBuffer, &data, 1); + usedCapacityOfBuffer = UART1_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart1ReadRingBuffer); + s_uart1ReadBufferState.maxUsedCapacityOfBuffer = + usedCapacityOfBuffer > s_uart1ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + : s_uart1ReadBufferState.maxUsedCapacityOfBuffer; + s_uart1ReadBufferState.countOfLostData += 1 - realCountPutBuffer; + } + if((RESET != usart_flag_get(USART0, USART_FLAG_TBE)) && + (RESET != usart_interrupt_flag_get(USART0, USART_INT_FLAG_TBE))) { + if (RingBuf_Get(&s_uart1WriteRingBuffer, &data, 1)) { + /* Transmit Data */ + usart_data_transmit(USART0, data); + } else { + usart_interrupt_disable(USART0, USART_INT_TBE); + } + } + +// if (__HAL_USART_GET_IT_SOURCE(&s_uart1Handle, USART_IT_RXNE) != RESET && +// __HAL_USART_GET_FLAG(&s_uart1Handle, USART_FLAG_RXNE) != RESET) { +// data = (uint8_t) ((uint16_t) (s_uart1Handle.Instance->DR & (uint16_t) 0x01FF) & (uint16_t) 0x00FF); +// realCountPutBuffer = RingBuf_Put(&s_uart1ReadRingBuffer, &data, 1); +// usedCapacityOfBuffer = UART1_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart1ReadRingBuffer); +// s_uart1ReadBufferState.maxUsedCapacityOfBuffer = +// usedCapacityOfBuffer > s_uart1ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer +// : s_uart1ReadBufferState.maxUsedCapacityOfBuffer; +// s_uart1ReadBufferState.countOfLostData += 1 - realCountPutBuffer; +// } + +// if (__HAL_USART_GET_IT_SOURCE(&s_uart1Handle, USART_IT_TXE) != RESET && +// __HAL_USART_GET_FLAG(&s_uart1Handle, USART_FLAG_TXE) != RESET) { +// if (RingBuf_Get(&s_uart1WriteRingBuffer, &data, 1)) { +// /* Transmit Data */ +// s_uart1Handle.Instance->DR = ((uint16_t) data & (uint16_t) 0x01FF); +// } else { +// __HAL_USART_DISABLE_IT(&s_uart1Handle, USART_IT_TXE); +// } +// } +} + +#endif + +/** + * @brief UART2 interrupt request handler fucntion. + */ +#ifdef USING_UART_PORT_2 + +void USART2_IRQHandler(void) +{ + uint8_t data; + uint16_t usedCapacityOfBuffer = 0; + uint16_t realCountPutBuffer = 0; + +// if (__HAL_USART_GET_IT_SOURCE(&s_uart2Handle, USART_IT_RXNE) != RESET && +// __HAL_USART_GET_FLAG(&s_uart2Handle, USART_FLAG_RXNE) != RESET) { +// data = (uint8_t) ((uint16_t) (s_uart2Handle.Instance->DR & (uint16_t) 0x01FF) & (uint16_t) 0x00FF); +// realCountPutBuffer = RingBuf_Put(&s_uart2ReadRingBuffer, &data, 1); +// usedCapacityOfBuffer = UART2_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart2ReadRingBuffer); +// s_uart2ReadBufferState.maxUsedCapacityOfBuffer = +// usedCapacityOfBuffer > s_uart2ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer +// : s_uart2ReadBufferState.maxUsedCapacityOfBuffer; +// s_uart2ReadBufferState.countOfLostData += 1 - realCountPutBuffer; +// } + +// if (__HAL_USART_GET_IT_SOURCE(&s_uart2Handle, USART_IT_TXE) != RESET && +// __HAL_USART_GET_FLAG(&s_uart2Handle, USART_FLAG_TXE) != RESET) { +// if (RingBuf_Get(&s_uart2WriteRingBuffer, &data, 1)) { +// /* Transmit Data */ +// s_uart2Handle.Instance->DR = ((uint16_t) data & (uint16_t) 0x01FF); +// } else { +// __HAL_USART_DISABLE_IT(&s_uart2Handle, USART_IT_TXE); +// } +// } +} + +#endif + +/** + * @brief UART3 interrupt request handler fucntion. + */ +#ifdef USING_UART_PORT_3 + +void UART3_IRQHandler(void) +{ + uint8_t data; + uint16_t usedCapacityOfBuffer = 0; + uint16_t realCountPutBuffer = 0; + + if((RESET != usart_interrupt_flag_get(UART3, USART_INT_FLAG_RBNE)) && + (RESET != usart_flag_get(UART3, USART_FLAG_RBNE))) { + data = usart_data_receive(UART3); + realCountPutBuffer = RingBuf_Put(&s_uart3ReadRingBuffer, &data, 1); + usedCapacityOfBuffer = UART3_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart3ReadRingBuffer); + s_uart3ReadBufferState.maxUsedCapacityOfBuffer = + usedCapacityOfBuffer > s_uart3ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer + : s_uart3ReadBufferState.maxUsedCapacityOfBuffer; + s_uart3ReadBufferState.countOfLostData += 1 - realCountPutBuffer; + } + if((RESET != usart_flag_get(UART3, USART_FLAG_TBE)) && + (RESET != usart_interrupt_flag_get(UART3, USART_INT_FLAG_TBE))) { + if (RingBuf_Get(&s_uart3WriteRingBuffer, &data, 1)) { + /* Transmit Data */ + usart_data_transmit(UART3, data); + } else { + usart_interrupt_disable(UART3, USART_INT_TBE); + } + } + +// if (__HAL_USART_GET_IT_SOURCE(&s_uart3Handle, USART_IT_RXNE) != RESET && +// __HAL_USART_GET_FLAG(&s_uart3Handle, USART_FLAG_RXNE) != RESET) { +// data = (uint8_t) ((uint16_t) (s_uart3Handle.Instance->DR & (uint16_t) 0x01FF) & (uint16_t) 0x00FF); +// realCountPutBuffer = RingBuf_Put(&s_uart3ReadRingBuffer, &data, 1); +// usedCapacityOfBuffer = UART3_READ_BUF_SIZE - RingBuf_GetUnusedSize(&s_uart3ReadRingBuffer); +// s_uart3ReadBufferState.maxUsedCapacityOfBuffer = +// usedCapacityOfBuffer > s_uart3ReadBufferState.maxUsedCapacityOfBuffer ? usedCapacityOfBuffer +// : s_uart3ReadBufferState.maxUsedCapacityOfBuffer; +// s_uart3ReadBufferState.countOfLostData += 1 - realCountPutBuffer; +// } + +// if (__HAL_USART_GET_IT_SOURCE(&s_uart3Handle, USART_IT_TXE) != RESET && +// __HAL_USART_GET_FLAG(&s_uart3Handle, USART_FLAG_TXE) != RESET) { +// if (RingBuf_Get(&s_uart3WriteRingBuffer, &data, 1)) { +// /* Transmit Data */ +// s_uart3Handle.Instance->DR = ((uint16_t) data & (uint16_t) 0x01FF); +// } else { +// __HAL_USART_DISABLE_IT(&s_uart3Handle, USART_IT_TXE); +// } +// } +} + +#endif diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/uart.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/uart.h new file mode 100644 index 0000000..f22a2a5 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/uart.h @@ -0,0 +1,71 @@ +/** + ****************************************************************************** + * @file uart.h + * @version V1.0.0 + * @date 2017/11/10 + * @brief This is the header file for "uart.c". + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USART_H__ +#define __USART_H__ + +/* Includes ------------------------------------------------------------------*/ +#include "dji_platform.h" + +/* Exported constants --------------------------------------------------------*/ +#define USING_UART_PORT_1 +#define USING_UART_PORT_2 +#define USING_UART_PORT_3 + +#define UART_ERROR (-1) + +/* Exported macros -----------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef enum { + UART_NUM_1 = 1, + UART_NUM_2 = 2, + UART_NUM_3 = 3, +} E_UartNum; + +typedef struct { + uint32_t countOfLostData; /*!< Count of data lost, unit: byte. */ + uint16_t maxUsedCapacityOfBuffer; /*!< Max capacity of buffer that have been used, unit: byte. */ +} T_UartBufferState; + +/* Exported constants --------------------------------------------------------*/ +#define DJI_CONSOLE_UART_NUM UART_NUM_3 +#define DJI_CONSOLE_UART_BAUD 921600 + +/* Exported variables --------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +void UART_Init(E_UartNum uartNum, uint32_t baudRate); +int UART_Read(E_UartNum uartNum, uint8_t *buf, uint16_t readSize); +int UART_Write(E_UartNum uartNum, const uint8_t *buf, uint16_t writeSize); +void UART_GetBufferState(E_UartNum uartNum, T_UartBufferState *readBufferState, T_UartBufferState *writeBufferState); + +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +#endif diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/upgrade_platform_opt_gd32.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/upgrade_platform_opt_gd32.c new file mode 100644 index 0000000..9820554 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/upgrade_platform_opt_gd32.c @@ -0,0 +1,183 @@ +/** + ******************************************************************** + * @file upgrade_platform_opt_gd32.c + * @version V2.0.0 + * @date 3/25/20 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "upgrade_platform_opt_gd32.h" +#include +#include "dji_logger.h" +#include "gd32f5xx.h" + +/* Private constants ---------------------------------------------------------*/ +#define DJI_TEST_UPGRADE_FILE_INFO_STORE_ADDR (APPLICATION_STORE_ADDRESS_END - 1023) +#define DJI_TEST_UPGRADE_REBOOT_KEY 0x11223344 + +/* Private types -------------------------------------------------------------*/ +typedef struct { + uint32_t upgradeRebootKey; + T_DjiUpgradeEndInfo upgradeEndInfo; +} T_DjiTestUpgradeRebootParam; + +/* Private values -------------------------------------------------------------*/ +static T_DjiUpgradeFileInfo s_upgradeFileInfo = {0}; + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode DjiUpgradePlatformGd32_RebootSystem(void) +{ + __disable_irq(); +#ifdef __CC_ARM + __disable_fiq(); +#endif + NVIC_SystemReset(); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_CleanUpgradeProgramFileStoreArea(void) +{ + uint32_t result; + + result = FLASH_If_Erase(APPLICATION_STORE_ADDRESS, APPLICATION_STORE_ADDRESS_END); + if (result != FLASHIF_OK) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_CreateUpgradeProgramFile(const T_DjiUpgradeFileInfo *fileInfo) +{ + s_upgradeFileInfo = *fileInfo; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_WriteUpgradeProgramFile(uint32_t offset, const uint8_t *data, + uint16_t dataLen) +{ + uint32_t result; + + result = FLASH_If_Write(APPLICATION_STORE_ADDRESS + offset, (uint8_t *) data, dataLen); + if (result != FLASHIF_OK) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_ReadUpgradeProgramFile(uint32_t offset, uint16_t readDataLen, uint8_t *data, + uint16_t *realLen) +{ + memcpy(data, (const void *) (APPLICATION_STORE_ADDRESS + offset), readDataLen); + *realLen = readDataLen; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_CloseUpgradeProgramFile(void) +{ + FLASH_If_Write(DJI_TEST_UPGRADE_FILE_INFO_STORE_ADDR, (uint8_t *) &s_upgradeFileInfo, + sizeof(T_DjiUpgradeFileInfo)); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_ReplaceOldProgram(void) +{ + uint32_t result; + T_DjiUpgradeFileInfo *upgradeFileInfo = (T_DjiUpgradeFileInfo *) (DJI_TEST_UPGRADE_FILE_INFO_STORE_ADDR); + + if (upgradeFileInfo->fileSize > APPLICATION_ADDRESS_END - APPLICATION_ADDRESS + 1) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + result = FLASH_If_Erase(APPLICATION_ADDRESS, APPLICATION_ADDRESS_END); + if (result != FLASHIF_OK) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + result = FLASH_If_Write(APPLICATION_ADDRESS, (uint8_t *) APPLICATION_STORE_ADDRESS, upgradeFileInfo->fileSize); + if (result != FLASHIF_OK) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_SetUpgradeRebootState(const T_DjiUpgradeEndInfo *upgradeEndInfo) +{ + uint32_t result; + T_DjiTestUpgradeRebootParam upgradeRebootParam; + + upgradeRebootParam.upgradeRebootKey = DJI_TEST_UPGRADE_REBOOT_KEY; + upgradeRebootParam.upgradeEndInfo = *upgradeEndInfo; + + result = FLASH_If_Erase(APPLICATION_PARAM_STORE_ADDRESS, APPLICATION_PARAM_STORE_ADDRESS_END); + if (result != FLASHIF_OK) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + result = FLASH_If_Write(APPLICATION_PARAM_STORE_ADDRESS, (uint8_t *) &upgradeRebootParam, + sizeof(T_DjiTestUpgradeRebootParam)); + if (result != FLASHIF_OK) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_GetUpgradeRebootState(bool *isUpgradeReboot, + T_DjiUpgradeEndInfo *upgradeEndInfo) +{ + T_DjiTestUpgradeRebootParam upgradeRebootParam; + + upgradeRebootParam = *(T_DjiTestUpgradeRebootParam *) (APPLICATION_PARAM_STORE_ADDRESS); + + if (upgradeRebootParam.upgradeRebootKey == DJI_TEST_UPGRADE_REBOOT_KEY) { + *isUpgradeReboot = true; + *upgradeEndInfo = upgradeRebootParam.upgradeEndInfo; + } else { + *isUpgradeReboot = false; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode DjiUpgradePlatformGd32_CleanUpgradeRebootState(void) +{ + uint32_t result; + + result = FLASH_If_Erase(APPLICATION_PARAM_STORE_ADDRESS, APPLICATION_PARAM_STORE_ADDRESS_END); + if (result != FLASHIF_OK) { + return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/upgrade_platform_opt_gd32.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/upgrade_platform_opt_gd32.h new file mode 100644 index 0000000..1f02f13 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/upgrade_platform_opt_gd32.h @@ -0,0 +1,68 @@ +/** + ******************************************************************** + * @file upgrade_platform_opt_gd32.h + * @version V2.0.0 + * @date 3/25/20 + * @brief This is the header file for "upgrade_platform_opt_gd32.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef UPGRADE_PLATFORM_OPT_Gd32_H +#define UPGRADE_PLATFORM_OPT_Gd32_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" +#include "dji_upgrade.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode DjiUpgradePlatformGd32_RebootSystem(void); + +T_DjiReturnCode DjiUpgradePlatformGd32_CleanUpgradeProgramFileStoreArea(void); +T_DjiReturnCode DjiUpgradePlatformGd32_CreateUpgradeProgramFile(const T_DjiUpgradeFileInfo *fileInfo); +T_DjiReturnCode DjiUpgradePlatformGd32_WriteUpgradeProgramFile(uint32_t offset, const uint8_t *data, + uint16_t dataLen); +T_DjiReturnCode DjiUpgradePlatformGd32_ReadUpgradeProgramFile(uint32_t offset, uint16_t readDataLen, uint8_t *data, + uint16_t *realLen); +T_DjiReturnCode DjiUpgradePlatformGd32_CloseUpgradeProgramFile(void); + +T_DjiReturnCode DjiUpgradePlatformGd32_ReplaceOldProgram(void); + +T_DjiReturnCode DjiUpgradePlatformGd32_SetUpgradeRebootState(const T_DjiUpgradeEndInfo *upgradeEndInfo); +T_DjiReturnCode DjiUpgradePlatformGd32_GetUpgradeRebootState(bool *isUpgradeReboot, + T_DjiUpgradeEndInfo *upgradeEndInfo); +T_DjiReturnCode DjiUpgradePlatformGd32_CleanUpgradeRebootState(void); + + +#ifdef __cplusplus +} +#endif + +#endif // UPGRADE_PLATFORM_OPT_Gd32_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_conf.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_conf.h new file mode 100644 index 0000000..0b89a9d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_conf.h @@ -0,0 +1,182 @@ +/*! + \file usb_conf.h + \brief USB core driver basic configuration + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USB_CONF_H +#define __USB_CONF_H + +#include +#include "gd32f5xx.h" + +/* USB Core and PHY interface configuration */ + +/****************** USB FS PHY CONFIGURATION ******************************* + * The USB FS Core supports one on-chip Full Speed PHY. + * The USE_EMBEDDED_PHY symbol is defined in the project compiler preprocessor + * when FS core is used. +*******************************************************************************/ + +#ifdef USE_USB_FS + #define USB_FS_CORE +#endif /* USE_USB_FS */ + +#ifdef USE_USB_HS + #define USB_HS_CORE +#endif /* USE_USB_HS */ + +/******************************************************************************* + * FIFO Size Configuration in Device mode + * + * (i) Receive data FIFO size = RAM for setup packets + + * OUT endpoint control information + + * data OUT packets + miscellaneous + * Space = ONE 32-bits words + * --> RAM for setup packets = 10 spaces + * (n is the nbr of CTRL EPs the device core supports) + * --> OUT EP CTRL info = 1 space + * (one space for status information written to the FIFO along with each + * received packet) + * --> Data OUT packets = (Largest Packet Size / 4) + 1 spaces + * (MINIMUM to receive packets) + * --> OR data OUT packets = at least 2* (Largest Packet Size / 4) + 1 spaces + * (if high-bandwidth EP is enabled or multiple isochronous EPs) + * --> Miscellaneous = 1 space per OUT EP + * (one space for transfer complete status information also pushed to the + * FIFO with each endpoint's last packet) + * + * (ii) MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for + * that particular IN EP. More space allocated in the IN EP Tx FIFO results + * in a better performance on the USB and can hide latencies on the AHB. + * + * (iii) TXn min size = 16 words. (n:Transmit FIFO index) + * + * (iv) When a TxFIFO is not used, the Configuration should be as follows: + * case 1: n > m and Txn is not used (n,m:Transmit FIFO indexes) + * --> Txm can use the space allocated for Txn. + * case 2: n < m and Txn is not used (n,m:Transmit FIFO indexes) + * --> Txn should be configured with the minimum space of 16 words + * + * (v) The FIFO is used optimally when used TxFIFOs are allocated in the top + * of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. + * + * (vi) In HS case12 FIFO locations should be reserved for internal DMA registers + * so total FIFO size should be 1012 Only instead of 1024 +*******************************************************************************/ + +#ifdef USB_FS_CORE + #define RX_FIFO_FS_SIZE 128 + #define TX0_FIFO_FS_SIZE 64 + #define TX1_FIFO_FS_SIZE 64 + #define TX2_FIFO_FS_SIZE 64 + #define TX3_FIFO_FS_SIZE 0 + + #define USBFS_SOF_OUTPUT 0 + #define USBFS_LOW_POWER 0 +#endif /* USB_FS_CORE */ + +#ifdef USB_HS_CORE + #define RX_FIFO_HS_SIZE 512 + #define TX0_FIFO_HS_SIZE 128 + #define TX1_FIFO_HS_SIZE 128 + #define TX2_FIFO_HS_SIZE 128 + #define TX3_FIFO_HS_SIZE 0 + #define TX4_FIFO_HS_SIZE 0 + #define TX5_FIFO_HS_SIZE 0 + + #ifdef USE_ULPI_PHY + #define USB_ULPI_PHY_ENABLED + #endif + + #ifdef USE_EMBEDDED_PHY + #define USB_EMBEDDED_PHY_ENABLED + #endif + +// #define USB_HS_INTERNAL_DMA_ENABLED +// #define USB_HS_DEDICATED_EP1_ENABLED + + #define USBHS_SOF_OUTPUT 0 + #define USBHS_LOW_POWER 0 +#endif /* USB_HS_CORE */ + +//#define VBUS_SENSING_ENABLED + +//#define USE_HOST_MODE +#define USE_DEVICE_MODE +//#define USE_OTG_MODE + +//#ifndef USB_FS_CORE +// #ifndef USB_HS_CORE +// #error "USB_HS_CORE or USB_FS_CORE should be defined!" +// #endif +//#endif + +#ifndef USE_DEVICE_MODE + #ifndef USE_HOST_MODE + #error "USE_DEVICE_MODE or USE_HOST_MODE should be defined!" + #endif +#endif + +//#ifndef USE_USB_HS +// #ifndef USE_USB_FS +// #error "USE_USB_HS or USE_USB_FS should be defined!" +// #endif +//#endif + +/* In Cortex-M33 Core, all variables and data structures during the USB transaction + process should be 4-bytes aligned */ + +#if defined (__GNUC__) /* GNU Compiler */ + #define __ALIGN_END __attribute__ ((aligned (4))) + #define __ALIGN_BEGIN +#else + #define __ALIGN_END + + #if defined (__CC_ARM) /* ARM Compiler */ + #define __ALIGN_BEGIN __align(4) + #elif defined (__ICCARM__) /* IAR Compiler */ + #define __ALIGN_BEGIN + #elif defined (__TASKING__)/* TASKING Compiler */ + #define __ALIGN_BEGIN __align(4) + #endif /* __CC_ARM */ +#endif /* __GNUC__ */ + +/* __packed keyword used to decrease the data type alignment to 1-byte */ +#if defined (__GNUC__) /* GNU Compiler */ + #ifndef __packed + #define __packed __attribute__ ((__packed__)) + #endif +#elif defined (__TASKING__) /* TASKING Compiler */ + #define __packed __unaligned +#endif /* __CC_ARM */ + +#endif /* __USB_CONF_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_device.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_device.c new file mode 100644 index 0000000..89f4707 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_device.c @@ -0,0 +1,143 @@ +/** + ******************************************************************** + * @file usb_device.c + * @version V2.0.0 + * @date 2019/9/20 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_device.h" +#include "osal.h" +#include "stdio.h" +#include "dji_logger.h" +#include "gd32f5xx.h" +#include "dji_ringbuffer.h" +#include "FreeRTOS.h" +#include "task.h" +#include "drv_usb_hw.h" +#include "cdc_acm_core.h" + +/* Private constants ---------------------------------------------------------*/ +#define USB_DEVICE_READ_BUF_SIZE 4096 +#define USB_DEVICE_WRITE_BUF_SIZE 4096 +#define USB_DEVICE_READ_DATA_SIZE 1024 + +/* Private types -------------------------------------------------------------*/ + +/* Private values -------------------------------------------------------------*/ +static T_RingBuffer s_usbDeviceReadRingBuffer; +static T_UsbDeviceBufferState s_usbDeviceReadBufferState; +static T_RingBuffer s_usbDeviceWriteRingBuffer; +static T_UsbDeviceBufferState s_usbDeviceWriteBufferState; +static uint8_t s_usbDeviceReadBuf[USB_DEVICE_READ_BUF_SIZE]; +static uint8_t s_usbDeviceWriteBuf[USB_DEVICE_WRITE_BUF_SIZE]; +static T_DjiMutexHandle s_usbDeviceMutex; +usb_core_driver cdc_acm; + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode USBD_CDC_Init(void) +{ + RingBuf_Init(&s_usbDeviceReadRingBuffer, s_usbDeviceReadBuf, USB_DEVICE_READ_BUF_SIZE); + RingBuf_Init(&s_usbDeviceWriteRingBuffer, s_usbDeviceWriteBuf, USB_DEVICE_WRITE_BUF_SIZE); + + // USB CDC Init + usb_gpio_config(); + usb_rcu_config(); + usb_timer_init(); + + usbd_init(&cdc_acm, +#ifdef USE_USB_FS + USB_CORE_ENUM_FS, +#elif defined(USE_USB_HS) + USB_CORE_ENUM_HS, +#endif /* USE_USB_FS */ + &cdc_desc, + &cdc_class); + + usb_intr_config(); + + Osal_MutexCreate(&s_usbDeviceMutex); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode USBD_CDC_DeInit(void) +{ + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode USBD_CDC_ReadData(uint8_t *buf, uint32_t len, uint32_t *realLen) +{ + Osal_MutexLock(s_usbDeviceMutex); + *realLen = RingBuf_Get(&s_usbDeviceReadRingBuffer, buf, len); + Osal_MutexUnlock(s_usbDeviceMutex); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode USBD_CDC_WriteData(const uint8_t *buf, uint32_t len, uint32_t *realLen) +{ + uint32_t blockSize = USB_CDC_DATA_PACKET_SIZE; + uint32_t blockNum = len / blockSize; + uint32_t blockRemain = len % blockSize; + uint32_t sentLen = 0; + *realLen = 0; + + for (uint32_t i = 0; i < blockNum; i++) { + cdc_acm_data_send(&cdc_acm, &buf[i * blockSize], blockSize, &sentLen); + *realLen += sentLen; + } + + if (blockRemain > 0) { + cdc_acm_data_send(&cdc_acm, &buf[blockNum * blockSize], blockRemain, &sentLen); + *realLen += sentLen; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +void USBD_CDC_Handle(void) +{ + uint16_t usedCapacityOfBuffer = 0; + uint16_t realCountPutBuffer = 0; + uint32_t readRealLen = 0; + uint8_t readBuf[USB_DEVICE_READ_DATA_SIZE] = {0}; + + if (USBD_CONFIGURED != cdc_acm.dev.cur_status) { + return; + } + + cdc_acm_data_receive(&cdc_acm, readBuf, USB_DEVICE_READ_DATA_SIZE, &readRealLen); + if (readRealLen > 0) { + Osal_MutexLock(s_usbDeviceMutex); + realCountPutBuffer = RingBuf_Put(&s_usbDeviceReadRingBuffer, readBuf, readRealLen); + Osal_MutexUnlock(s_usbDeviceMutex); + USER_LOG_DEBUG("Rececive cdc data finished, dataLen: %d", readRealLen); + } + + return; +} +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_device.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_device.h new file mode 100644 index 0000000..f5da3f8 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usb_device.h @@ -0,0 +1,59 @@ +/** + ******************************************************************** + * @file usb_device.h + * @version V2.0.0 + * @date 2019/9/20 + * @brief This is the header file for "usb_device.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef USB_DEVICE_H +#define USB_DEVICE_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_typedef.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ +typedef struct { + uint32_t countOfLostData; /*!< Count of data lost, unit: byte. */ + uint16_t maxUsedCapacityOfBuffer; /*!< Max capacity of buffer that have been used, unit: byte. */ +} T_UsbDeviceBufferState; + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode USBD_CDC_Init(void); +T_DjiReturnCode USBD_CDC_DeInit(void); +T_DjiReturnCode USBD_CDC_WriteData(const uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode USBD_CDC_ReadData(uint8_t *buf, uint32_t len, uint32_t *realLen);\ +void USBD_CDC_Handle(void); + +#ifdef __cplusplus +} +#endif + +#endif // USB_DEVICE_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usbd_conf.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usbd_conf.h new file mode 100644 index 0000000..c332769 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/BSP/usbd_conf.h @@ -0,0 +1,72 @@ +/*! + \file usbd_conf.h + \brief the header file of USB device configuration + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBD_CONF_H +#define __USBD_CONF_H + +#include "usb_conf.h" + +#define USBD_CFG_MAX_NUM 1 +#define USBD_ITF_MAX_NUM 1 + +#define CDC_COM_INTERFACE 0 + +#define USB_STR_DESC_MAX_SIZE 255 + +#define CDC_DATA_IN_EP EP1_IN /* EP1 for data IN */ +#define CDC_DATA_OUT_EP EP3_OUT /* EP3 for data OUT */ +#define CDC_CMD_EP EP2_IN /* EP2 for CDC commands */ + +#define USB_STRING_COUNT 4 + +#define USB_CDC_CMD_PACKET_SIZE 8 /* Control Endpoint Packet size */ + +#define APP_RX_DATA_SIZE 2048 /* Total size of IN buffer: + APP_RX_DATA_SIZE*8 / MAX_BAUDARATE * 1000 should be > CDC_IN_FRAME_INTERVAL*8 */ + +/* CDC endpoints parameters: you can fine tune these values depending on the needed baud rate and performance */ +#ifdef USE_USB_HS + #ifdef USE_ULPI_PHY + #define USB_CDC_DATA_PACKET_SIZE 512 /* Endpoint IN & OUT Packet size */ + #define CDC_IN_FRAME_INTERVAL 40 /* Number of micro-frames between IN transfers */ + #else + #define USB_CDC_DATA_PACKET_SIZE 64 /* Endpoint IN & OUT Packet size */ + #define CDC_IN_FRAME_INTERVAL 5 /* Number of frames between IN transfers */ + #endif +#else + #define USB_CDC_DATA_PACKET_SIZE 64 /* Endpoint IN & OUT Packet size */ + #define CDC_IN_FRAME_INTERVAL 5 /* Number of frames between IN transfers */ +#endif /* USE_USB_HS */ + +#endif /* __USBD_CONF_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Include/gd32f5xx.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Include/gd32f5xx.h new file mode 100644 index 0000000..8922c94 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Include/gd32f5xx.h @@ -0,0 +1,302 @@ +/*! + \file gd32f5xx.h + \brief general definitions for GD32F5xx + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * Copyright (c) 2023, GigaDevice Semiconductor Inc. + * + * 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. + */ + +/* This file refers the CMSIS standard, some adjustments are made according to GigaDevice chips */ + +#ifndef GD32F5XX_H +#define GD32F5XX_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* define GD32F5xx */ +#if !defined (GD32F527) +/* #define GD32F527 */ +#endif /* define GD32F5xx */ + +#if !defined (GD32F527) +#error "Please select the target GD32F5xx device in gd32f5xx.h file" +#endif /* undefine GD32F5xx tip */ + +/* define value of high speed crystal oscillator (HXTAL) in Hz */ +#if !defined (HXTAL_VALUE) +#define HXTAL_VALUE ((uint32_t)12000000) +#endif /* high speed crystal oscillator value */ + +/* define startup timeout value of high speed crystal oscillator (HXTAL) */ +#if !defined (HXTAL_STARTUP_TIMEOUT) +#define HXTAL_STARTUP_TIMEOUT ((uint16_t)0xFFFF) +#endif /* high speed crystal oscillator startup timeout */ + +/* define value of internal 16MHz RC oscillator (IRC16M) in Hz */ +#if !defined (IRC16M_VALUE) +#define IRC16M_VALUE ((uint32_t)16000000) +#endif /* internal 16MHz RC oscillator value */ + +/* define startup timeout value of internal 16MHz RC oscillator (IRC16M) */ +#if !defined (IRC16M_STARTUP_TIMEOUT) +#define IRC16M_STARTUP_TIMEOUT ((uint16_t)0x0500) +#endif /* internal 16MHz RC oscillator startup timeout */ + +/* define value of internal 32KHz RC oscillator(IRC32K) in Hz */ +#if !defined (IRC32K_VALUE) +#define IRC32K_VALUE ((uint32_t)32000) +#endif /* internal 32KHz RC oscillator value */ + +/* define value of low speed crystal oscillator (LXTAL)in Hz */ +#if !defined (LXTAL_VALUE) +#define LXTAL_VALUE ((uint32_t)32768) +#endif /* low speed crystal oscillator value */ + +/* I2S external clock in selection */ +//#define I2S_EXTERNAL_CLOCK_IN (uint32_t)12288000U + +/* GD32F5xx firmware library version number V1.0 */ +#define __GD32F5xx_STDPERIPH_VERSION_MAIN (0x01) /*!< [31:24] main version */ +#define __GD32F5xx_STDPERIPH_VERSION_SUB1 (0x00) /*!< [23:16] sub1 version */ +#define __GD32F5xx_STDPERIPH_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ +#define __GD32F5xx_STDPERIPH_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __GD32F5xx_STDPERIPH_VERSION ((__GD32F5xx_STDPERIPH_VERSION_MAIN << 24)\ + |(__GD32F5xx_STDPERIPH_VERSION_SUB1 << 16)\ + |(__GD32F5xx_STDPERIPH_VERSION_SUB2 << 8)\ + |(__GD32F5xx_STDPERIPH_VERSION_RC)) + +/* configuration of the cortex-M33 processor and core peripherals */ +#define __CM33_REV 0x0001 /*!< core revision r0p1 */ +#define __MPU_PRESENT 1 /*!< GD32F5xx provide MPU */ +#define __NVIC_PRIO_BITS 4 /*!< GD32F5xx uses 4 bits for the priority levels */ +#define __Vendor_SysTickConfig 0 /*!< set to 1 if different sysTick config is used */ +#define __FPU_PRESENT 1 /*!< FPU present */ +#define __DSP_PRESENT 1 /*!< DSP present */ +/* define interrupt number */ +typedef enum IRQn { + /* cortex-M33 processor exceptions numbers */ + NonMaskableInt_IRQn = -14, /*!< 2 non maskable interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 cortex-M33 memory management interrupt */ + BusFault_IRQn = -11, /*!< 5 cortex-M33 bus fault interrupt */ + UsageFault_IRQn = -10, /*!< 6 cortex-M33 usage fault interrupt */ + SVCall_IRQn = -5, /*!< 11 cortex-M33 SV call interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 cortex-M33 debug monitor interrupt */ + PendSV_IRQn = -2, /*!< 14 cortex-M33 pend SV interrupt */ + SysTick_IRQn = -1, /*!< 15 cortex-M33 system tick interrupt */ + /* interruput numbers */ + WWDGT_IRQn = 0, /*!< window watchdog timer interrupt */ + LVD_IRQn = 1, /*!< LVD through EXTI line detect interrupt */ + TAMPER_STAMP_IRQn = 2, /*!< tamper and timestamp through EXTI line detect */ + RTC_WKUP_IRQn = 3, /*!< RTC wakeup through EXTI line interrupt */ + FMC_IRQn = 4, /*!< FMC interrupt */ + RCU_CTC_IRQn = 5, /*!< RCU and CTC interrupt */ + EXTI0_IRQn = 6, /*!< EXTI line 0 interrupts */ + EXTI1_IRQn = 7, /*!< EXTI line 1 interrupts */ + EXTI2_IRQn = 8, /*!< EXTI line 2 interrupts */ + EXTI3_IRQn = 9, /*!< EXTI line 3 interrupts */ + EXTI4_IRQn = 10, /*!< EXTI line 4 interrupts */ + DMA0_Channel0_IRQn = 11, /*!< DMA0 channel0 Interrupt */ + DMA0_Channel1_IRQn = 12, /*!< DMA0 channel1 Interrupt */ + DMA0_Channel2_IRQn = 13, /*!< DMA0 channel2 interrupt */ + DMA0_Channel3_IRQn = 14, /*!< DMA0 channel3 interrupt */ + DMA0_Channel4_IRQn = 15, /*!< DMA0 channel4 interrupt */ + DMA0_Channel5_IRQn = 16, /*!< DMA0 channel5 interrupt */ + DMA0_Channel6_IRQn = 17, /*!< DMA0 channel6 interrupt */ + ADC_IRQn = 18, /*!< ADC interrupt */ + CAN0_TX_IRQn = 19, /*!< CAN0 TX interrupt */ + CAN0_RX0_IRQn = 20, /*!< CAN0 RX0 interrupt */ + CAN0_RX1_IRQn = 21, /*!< CAN0 RX1 interrupt */ + CAN0_EWMC_IRQn = 22, /*!< CAN0 EWMC interrupt */ + EXTI5_9_IRQn = 23, /*!< EXTI[9:5] interrupts */ + TIMER0_BRK_TIMER8_IRQn = 24, /*!< TIMER0 break and TIMER8 interrupts */ + TIMER0_UP_TIMER9_IRQn = 25, /*!< TIMER0 update and TIMER9 interrupts */ + TIMER0_TRG_CMT_TIMER10_IRQn = 26, /*!< TIMER0 trigger and commutation and TIMER10 interrupts */ + TIMER0_Channel_IRQn = 27, /*!< TIMER0 channel capture compare interrupt */ + TIMER1_IRQn = 28, /*!< TIMER1 interrupt */ + TIMER2_IRQn = 29, /*!< TIMER2 interrupt */ + TIMER3_IRQn = 30, /*!< TIMER3 interrupts */ + I2C0_EV_IRQn = 31, /*!< I2C0 event interrupt */ + I2C0_ER_IRQn = 32, /*!< I2C0 error interrupt */ + I2C1_EV_IRQn = 33, /*!< I2C1 event interrupt */ + I2C1_ER_IRQn = 34, /*!< I2C1 error interrupt */ + SPI0_IRQn = 35, /*!< SPI0 interrupt */ + SPI1_IRQn = 36, /*!< SPI1 interrupt */ + USART0_IRQn = 37, /*!< USART0 interrupt */ + USART1_IRQn = 38, /*!< USART1 interrupt */ + USART2_IRQn = 39, /*!< USART2 interrupt */ + EXTI10_15_IRQn = 40, /*!< EXTI[15:10] interrupts */ + RTC_Alarm_IRQn = 41, /*!< RTC alarm interrupt */ + USBFS_WKUP_IRQn = 42, /*!< USBFS wakeup interrupt */ + TIMER7_BRK_TIMER11_IRQn = 43, /*!< TIMER7 break and TIMER11 interrupts */ + TIMER7_UP_TIMER12_IRQn = 44, /*!< TIMER7 update and TIMER12 interrupts */ + TIMER7_TRG_CMT_TIMER13_IRQn = 45, /*!< TIMER7 trigger and commutation and TIMER13 interrupts */ + TIMER7_Channel_IRQn = 46, /*!< TIMER7 channel capture compare interrupt */ + DMA0_Channel7_IRQn = 47, /*!< DMA0 channel7 interrupt */ + EXMC_IRQn = 48, /*!< EXMC interrupt */ + SDIO_IRQn = 49, /*!< SDIO interrupt */ + TIMER4_IRQn = 50, /*!< TIMER4 interrupt */ + SPI2_IRQn = 51, /*!< SPI2 interrupt */ + UART3_IRQn = 52, /*!< UART3 interrupt */ + UART4_IRQn = 53, /*!< UART4 interrupt */ + TIMER5_DAC_IRQn = 54, /*!< TIMER5 and DAC0 DAC1 underrun error interrupts */ + TIMER6_IRQn = 55, /*!< TIMER6 interrupt */ + DMA1_Channel0_IRQn = 56, /*!< DMA1 channel0 interrupt */ + DMA1_Channel1_IRQn = 57, /*!< DMA1 channel1 interrupt */ + DMA1_Channel2_IRQn = 58, /*!< DMA1 channel2 interrupt */ + DMA1_Channel3_IRQn = 59, /*!< DMA1 channel3 interrupt */ + DMA1_Channel4_IRQn = 60, /*!< DMA1 channel4 interrupt */ + ENET_IRQn = 61, /*!< ENET interrupt */ + ENET_WKUP_IRQn = 62, /*!< ENET wakeup through EXTI line interrupt */ + CAN1_TX_IRQn = 63, /*!< CAN1 TX interrupt */ + CAN1_RX0_IRQn = 64, /*!< CAN1 RX0 interrupt */ + CAN1_RX1_IRQn = 65, /*!< CAN1 RX1 interrupt */ + CAN1_EWMC_IRQn = 66, /*!< CAN1 EWMC interrupt */ + USBFS_IRQn = 67, /*!< USBFS interrupt */ + DMA1_Channel5_IRQn = 68, /*!< DMA1 channel5 interrupt */ + DMA1_Channel6_IRQn = 69, /*!< DMA1 channel6 interrupt */ + DMA1_Channel7_IRQn = 70, /*!< DMA1 channel7 interrupt */ + USART5_IRQn = 71, /*!< USART5 interrupt */ + I2C2_EV_IRQn = 72, /*!< I2C2 event interrupt */ + I2C2_ER_IRQn = 73, /*!< I2C2 error interrupt */ + USBHS_EP1_Out_IRQn = 74, /*!< USBHS endpoint 1 out interrupt */ + USBHS_EP1_In_IRQn = 75, /*!< USBHS endpoint 1 in interrupt */ + USBHS_WKUP_IRQn = 76, /*!< USBHS wakeup through EXTI line interrupt */ + USBHS_IRQn = 77, /*!< USBHS interrupt */ + DCI_IRQn = 78, /*!< DCI interrupt */ + TRNG_IRQn = 80, /*!< TRNG interrupt */ + FPU_IRQn = 81, /*!< FPU interrupt */ + UART6_IRQn = 82, /*!< UART6 interrupt */ + UART7_IRQn = 83, /*!< UART7 interrupt */ + SPI3_IRQn = 84, /*!< SPI3 interrupt */ + SPI4_IRQn = 85, /*!< SPI4 interrupt */ + SPI5_IRQn = 86, /*!< SPI5 interrupt */ + SAI_IRQn = 87, /*!< SAI interrupt */ + TLI_IRQn = 88, /*!< TLI interrupt */ + TLI_ER_IRQn = 89, /*!< TLI error interrupt */ + IPA_IRQn = 90, /*!< IPA interrupt */ + PKCAU_IRQn = 91, /*!< PKCAU interrupt */ + I2C3_EV_IRQn = 92, /*!< I2C3 Event interrupt */ + I2C3_ER_IRQn = 93, /*!< I2C3 Error interrupt */ + I2C4_EV_IRQn = 94, /*!< I2C4 Event interrupt */ + I2C4_ER_IRQn = 95, /*!< I2C4 Error interrupt */ + I2C5_EV_IRQn = 96, /*!< I2C5 Event interrupt */ + I2C5_ER_IRQn = 97, /*!< I2C5 Error interrupt */ + I2C3_WKUP_IRQn = 98, /*!< I2C3 Wakeup through EXTI Line interrupt */ + I2C4_WKUP_IRQn = 99, /*!< I2C4 Wakeup through EXTI Line interrupt */ + I2C5_WKUP_IRQn = 100, /*!< I2C5 Wakeup through EXTI Line interrupt */ + SYSCFG_SRAM_ECC_ER_IRQn = 101, /*!< SYSCFG SRAM ECC Error interrupt */ + HAU_IRQn = 102, /*!< HAU interrupt */ + CAU_IRQn = 103 /*!< CAU interrupt */ +} IRQn_Type; + +/* includes */ +#include "core_cm33.h" +#include "system_gd32f5xx.h" +#include + +/* enum definitions */ +typedef enum {DISABLE = 0, ENABLE = !DISABLE} EventStatus, ControlStatus; +typedef enum {RESET = 0, SET = !RESET} FlagStatus; +typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrStatus; + +/* bit operations */ +#define REG32(addr) (*(volatile uint32_t *)(uint32_t)(addr)) +#define REG16(addr) (*(volatile uint16_t *)(uint32_t)(addr)) +#define REG8(addr) (*(volatile uint8_t *)(uint32_t)(addr)) +#define BIT(x) ((uint32_t)((uint32_t)0x01U<<(x))) +#define BITS(start, end) ((0xFFFFFFFFUL << (start)) & (0xFFFFFFFFUL >> (31U - (uint32_t)(end)))) +#define GET_BITS(regval, start, end) (((regval) & BITS((start),(end))) >> (start)) + +/* main flash and SRAM memory map */ +#define FLASH_BASE ((uint32_t)0x08000000U) /*!< main FLASH base address */ +#define TCMSRAM_BASE ((uint32_t)0x10000000U) /*!< TCMSRAM(64KB) base address */ +#define OPTION_BASE ((uint32_t)0x1FFFC000U) /*!< Option bytes base address */ +#define SRAM_BASE ((uint32_t)0x20000000U) /*!< SRAM0 base address */ + +/* peripheral memory map */ +#define APB1_BUS_BASE ((uint32_t)0x40000000U) /*!< apb1 base address */ +#define APB2_BUS_BASE ((uint32_t)0x40010000U) /*!< apb2 base address */ +#define AHB1_BUS_BASE ((uint32_t)0x40020000U) /*!< ahb1 base address */ +#define AHB2_BUS_BASE ((uint32_t)0x50000000U) /*!< ahb2 base address */ + +/* EXMC memory map */ +#define EXMC_BASE ((uint32_t)0xA0000000U) /*!< EXMC register base address */ + +/* advanced peripheral bus 1 memory map */ +#define TIMER_BASE (APB1_BUS_BASE + 0x00000000U) /*!< TIMER base address */ +#define RTC_BASE (APB1_BUS_BASE + 0x00002800U) /*!< RTC base address */ +#define WWDGT_BASE (APB1_BUS_BASE + 0x00002C00U) /*!< WWDGT base address */ +#define FWDGT_BASE (APB1_BUS_BASE + 0x00003000U) /*!< FWDGT base address */ +#define I2S_ADD_BASE (APB1_BUS_BASE + 0x00003400U) /*!< I2S1_add base address */ +#define SPI_BASE (APB1_BUS_BASE + 0x00003800U) /*!< SPI base address */ +#define USART_BASE (APB1_BUS_BASE + 0x00004400U) /*!< USART base address */ +#define I2C_BASE (APB1_BUS_BASE + 0x00005400U) /*!< I2C base address */ +#define CAN_BASE (APB1_BUS_BASE + 0x00006400U) /*!< CAN base address */ +#define CTC_BASE (APB1_BUS_BASE + 0x00006C00U) /*!< CTC base address */ +#define PMU_BASE (APB1_BUS_BASE + 0x00007000U) /*!< PMU base address */ +#define DAC_BASE (APB1_BUS_BASE + 0x00007400U) /*!< DAC base address */ +#define IREF_BASE (APB1_BUS_BASE + 0x0000C400U) /*!< IREF base address */ + +/* advanced peripheral bus 2 memory map */ +#define ADC_BASE (APB2_BUS_BASE + 0x00002000U) /*!< ADC base address */ +#define SDIO_BASE (APB2_BUS_BASE + 0x00002C00U) /*!< SDIO base address */ +#define SYSCFG_BASE (APB2_BUS_BASE + 0x00003800U) /*!< SYSCFG base address */ +#define EXTI_BASE (APB2_BUS_BASE + 0x00003C00U) /*!< EXTI base address */ +#define SAI_BASE (APB2_BUS_BASE + 0x00005800U) /*!< SAI base address */ +#define TLI_BASE (APB2_BUS_BASE + 0x00006800U) /*!< TLI base address */ + +/* advanced high performance bus 1 memory map */ +#define GPIO_BASE (AHB1_BUS_BASE + 0x00000000U) /*!< GPIO base address */ +#define CRC_BASE (AHB1_BUS_BASE + 0x00003000U) /*!< CRC base address */ +#define RCU_BASE (AHB1_BUS_BASE + 0x00003800U) /*!< RCU base address */ +#define FMC_BASE (AHB1_BUS_BASE + 0x00003C00U) /*!< FMC base address */ +#define BKPSRAM_BASE (AHB1_BUS_BASE + 0x00004000U) /*!< BKPSRAM base address */ +#define DMA_BASE (AHB1_BUS_BASE + 0x00006000U) /*!< DMA base address */ +#define ENET_BASE (AHB1_BUS_BASE + 0x00008000U) /*!< ENET base address */ +#define IPA_BASE (AHB1_BUS_BASE + 0x0000B000U) /*!< IPA base address */ +#define USBHS_BASE (AHB1_BUS_BASE + 0x00020000U) /*!< USBHS base address */ + +/* advanced high performance bus 2 memory map */ +#define USBFS_BASE (AHB2_BUS_BASE + 0x00000000U) /*!< USBFS base address */ +#define DCI_BASE (AHB2_BUS_BASE + 0x00050000U) /*!< DCI base address */ +#define CAU_BASE (AHB2_BUS_BASE + 0x00060000U) /*!< CAU base address */ +#define HAU_BASE (AHB2_BUS_BASE + 0x00060400U) /*!< HAU base address */ +#define TRNG_BASE (AHB2_BUS_BASE + 0x00060800U) /*!< TRNG base address */ +#define PKCAU_BASE (AHB2_BUS_BASE + 0x00061000U) /*!< PKCAU base address */ + +/* option byte and debug memory map */ +#define OB_BASE ((uint32_t)0x1FFEC000U) /*!< OB base address */ +#define DBG_BASE ((uint32_t)0xE0044000U) /*!< DBG base address */ + +/* define marco USE_STDPERIPH_DRIVER */ +#if !defined USE_STDPERIPH_DRIVER +#define USE_STDPERIPH_DRIVER +#endif +#ifdef USE_STDPERIPH_DRIVER +#include "gd32f5xx_libopt.h" +#endif /* USE_STDPERIPH_DRIVER */ + +#ifdef __cplusplus +} +#endif +#endif diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Include/system_gd32f5xx.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Include/system_gd32f5xx.h new file mode 100644 index 0000000..72543ac --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Include/system_gd32f5xx.h @@ -0,0 +1,50 @@ +/*! + \file system_gd32f5xx.h + \brief CMSIS Cortex-M33 Device Peripheral Access Layer Header File for + GD32F5xx Device Series +*/ + +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * Copyright (c) 2023, GigaDevice Semiconductor Inc. + * + * 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. + */ + +/* This file refers the CMSIS standard, some adjustments are made according to GigaDevice chips */ + +#ifndef SYSTEM_GD32F5XX_H +#define SYSTEM_GD32F5XX_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +/* system clock frequency (core clock) */ +extern uint32_t SystemCoreClock; + +/* function declarations */ +/* initialize the system and update the SystemCoreClock variable */ +extern void SystemInit (void); +/* update the SystemCoreClock with current core clock retrieved from cpu registers */ +extern void SystemCoreClockUpdate (void); + +#ifdef __cplusplus +} +#endif + +#endif /* SYSTEM_GD32F5XX_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/ARM/startup_gd32f5xx.s b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/ARM/startup_gd32f5xx.s new file mode 100644 index 0000000..a68d4da --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/ARM/startup_gd32f5xx.s @@ -0,0 +1,495 @@ +;/*! +; \file startup_gd32f5xx.s +; \brief start up file +; +; \version 2023-12-20, V1.0.0, firmware for GD32F5xx +;*/ +; +;/* +; * Copyright (c) 2009-2018 Arm Limited. All rights reserved. +; * Copyright (c) 2023, GigaDevice Semiconductor Inc. +; * +; * 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. +; */ +; +;/* This file refers the CMSIS standard, some adjustments are made according to GigaDevice chips */ + +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000400 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + +; /* reset Vector Mapped to at Address 0 */ + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + +; /* external interrupts handler */ + DCD WWDGT_IRQHandler ; 16:Window Watchdog Timer + DCD LVD_IRQHandler ; 17:LVD through EXTI Line detect + DCD TAMPER_STAMP_IRQHandler ; 18:Tamper and TimeStamp through EXTI Line detect + DCD RTC_WKUP_IRQHandler ; 19:RTC Wakeup through EXTI Line + DCD FMC_IRQHandler ; 20:FMC + DCD RCU_CTC_IRQHandler ; 21:RCU and CTC + DCD EXTI0_IRQHandler ; 22:EXTI Line 0 + DCD EXTI1_IRQHandler ; 23:EXTI Line 1 + DCD EXTI2_IRQHandler ; 24:EXTI Line 2 + DCD EXTI3_IRQHandler ; 25:EXTI Line 3 + DCD EXTI4_IRQHandler ; 26:EXTI Line 4 + DCD DMA0_Channel0_IRQHandler ; 27:DMA0 Channel0 + DCD DMA0_Channel1_IRQHandler ; 28:DMA0 Channel1 + DCD DMA0_Channel2_IRQHandler ; 29:DMA0 Channel2 + DCD DMA0_Channel3_IRQHandler ; 30:DMA0 Channel3 + DCD DMA0_Channel4_IRQHandler ; 31:DMA0 Channel4 + DCD DMA0_Channel5_IRQHandler ; 32:DMA0 Channel5 + DCD DMA0_Channel6_IRQHandler ; 33:DMA0 Channel6 + DCD ADC_IRQHandler ; 34:ADC + DCD CAN0_TX_IRQHandler ; 35:CAN0 TX + DCD CAN0_RX0_IRQHandler ; 36:CAN0 RX0 + DCD CAN0_RX1_IRQHandler ; 37:CAN0 RX1 + DCD CAN0_EWMC_IRQHandler ; 38:CAN0 EWMC + DCD EXTI5_9_IRQHandler ; 39:EXTI5 to EXTI9 + DCD TIMER0_BRK_TIMER8_IRQHandler ; 40:TIMER0 Break and TIMER8 + DCD TIMER0_UP_TIMER9_IRQHandler ; 41:TIMER0 Update and TIMER9 + DCD TIMER0_TRG_CMT_TIMER10_IRQHandler ; 42:TIMER0 Trigger and Commutation and TIMER10 + DCD TIMER0_Channel_IRQHandler ; 43:TIMER0 Capture Compare + DCD TIMER1_IRQHandler ; 44:TIMER1 + DCD TIMER2_IRQHandler ; 45:TIMER2 + DCD TIMER3_IRQHandler ; 46:TIMER3 + DCD I2C0_EV_IRQHandler ; 47:I2C0 Event + DCD I2C0_ER_IRQHandler ; 48:I2C0 Error + DCD I2C1_EV_IRQHandler ; 49:I2C1 Event + DCD I2C1_ER_IRQHandler ; 50:I2C1 Error + DCD SPI0_IRQHandler ; 51:SPI0 + DCD SPI1_IRQHandler ; 52:SPI1 + DCD USART0_IRQHandler ; 53:USART0 + DCD USART1_IRQHandler ; 54:USART1 + DCD USART2_IRQHandler ; 55:USART2 + DCD EXTI10_15_IRQHandler ; 56:EXTI10 to EXTI15 + DCD RTC_Alarm_IRQHandler ; 57:RTC Alarm + DCD USBFS_WKUP_IRQHandler ; 58:USBFS Wakeup + DCD TIMER7_BRK_TIMER11_IRQHandler ; 59:TIMER7 Break and TIMER11 + DCD TIMER7_UP_TIMER12_IRQHandler ; 60:TIMER7 Update and TIMER12 + DCD TIMER7_TRG_CMT_TIMER13_IRQHandler ; 61:TIMER7 Trigger and Commutation and TIMER13 + DCD TIMER7_Channel_IRQHandler ; 62:TIMER7 Channel Capture Compare + DCD DMA0_Channel7_IRQHandler ; 63:DMA0 Channel7 + DCD EXMC_IRQHandler ; 64:EXMC + DCD SDIO_IRQHandler ; 65:SDIO + DCD TIMER4_IRQHandler ; 66:TIMER4 + DCD SPI2_IRQHandler ; 67:SPI2 + DCD UART3_IRQHandler ; 68:UART3 + DCD UART4_IRQHandler ; 69:UART4 + DCD TIMER5_DAC_IRQHandler ; 70:TIMER5 and DAC0 DAC1 Underrun error + DCD TIMER6_IRQHandler ; 71:TIMER6 + DCD DMA1_Channel0_IRQHandler ; 72:DMA1 Channel0 + DCD DMA1_Channel1_IRQHandler ; 73:DMA1 Channel1 + DCD DMA1_Channel2_IRQHandler ; 74:DMA1 Channel2 + DCD DMA1_Channel3_IRQHandler ; 75:DMA1 Channel3 + DCD DMA1_Channel4_IRQHandler ; 76:DMA1 Channel4 + DCD ENET_IRQHandler ; 77:Ethernet + DCD ENET_WKUP_IRQHandler ; 78:Ethernet Wakeup through EXTI Line + DCD CAN1_TX_IRQHandler ; 79:CAN1 TX + DCD CAN1_RX0_IRQHandler ; 80:CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; 81:CAN1 RX1 + DCD CAN1_EWMC_IRQHandler ; 82:CAN1 EWMC + DCD USBFS_IRQHandler ; 83:USBFS + DCD DMA1_Channel5_IRQHandler ; 84:DMA1 Channel5 + DCD DMA1_Channel6_IRQHandler ; 85:DMA1 Channel6 + DCD DMA1_Channel7_IRQHandler ; 86:DMA1 Channel7 + DCD USART5_IRQHandler ; 87:USART5 + DCD I2C2_EV_IRQHandler ; 88:I2C2 Event + DCD I2C2_ER_IRQHandler ; 89:I2C2 Error + DCD USBHS_EP1_Out_IRQHandler ; 90:USBHS Endpoint 1 Out + DCD USBHS_EP1_In_IRQHandler ; 91:USBHS Endpoint 1 in + DCD USBHS_WKUP_IRQHandler ; 92:USBHS Wakeup through EXTI Line + DCD USBHS_IRQHandler ; 93:USBHS + DCD DCI_IRQHandler ; 94:DCI + DCD 0 ; 95:Reserved + DCD TRNG_IRQHandler ; 96:TRNG + DCD FPU_IRQHandler ; 97:FPU + DCD UART6_IRQHandler ; 98:UART6 + DCD UART7_IRQHandler ; 99:UART7 + DCD SPI3_IRQHandler ; 100:SPI3 + DCD SPI4_IRQHandler ; 101:SPI4 + DCD SPI5_IRQHandler ; 102:SPI5 + DCD SAI_IRQHandler ; 103:SAI + DCD TLI_IRQHandler ; 104:TLI + DCD TLI_ER_IRQHandler ; 105:TLI Error + DCD IPA_IRQHandler ; 106:IPA + DCD PKCAU_IRQHandler ; 107:PKCAU + DCD I2C3_EV_IRQHandler ; 108:I2C3 Event + DCD I2C3_ER_IRQHandler ; 109:I2C3 Error + DCD I2C4_EV_IRQHandler ; 110:I2C4 Event + DCD I2C4_ER_IRQHandler ; 111:I2C4 Error + DCD I2C5_EV_IRQHandler ; 112:I2C5 Event + DCD I2C5_ER_IRQHandler ; 113:I2C5 Error + DCD I2C3_WKUP_IRQHandler ; 114:I2C3 Wakeup through EXTI Line + DCD I2C4_WKUP_IRQHandler ; 115:I2C4 Wakeup through EXTI Line + DCD I2C5_WKUP_IRQHandler ; 116:I2C5 Wakeup through EXTI Line + DCD SYSCFG_SRAM_ECC_ER_IRQHandler ; 117:SYSCFG SRAM ECC Error + DCD HAU_IRQHandler ; 118:HAU + DCD CAU_IRQHandler ; 119:CAU + +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +;/* reset Handler */ +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + IMPORT |Image$$RW_IRAM1$$RW$$Base| + + LDR R0, =|Image$$RW_IRAM1$$RW$$Base| + ADD R1, R0, #0x8000 + LDR R2, =0x0 +MEM_INIT STRD R2, R2, [ R0 ] , #8 + CMP R0, R1 + BNE MEM_INIT + + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +;/* dummy Exception Handlers */ +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler\ + PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler\ + PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC +; /* external interrupts handler */ + EXPORT WWDGT_IRQHandler [WEAK] + EXPORT LVD_IRQHandler [WEAK] + EXPORT TAMPER_STAMP_IRQHandler [WEAK] + EXPORT RTC_WKUP_IRQHandler [WEAK] + EXPORT FMC_IRQHandler [WEAK] + EXPORT RCU_CTC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA0_Channel0_IRQHandler [WEAK] + EXPORT DMA0_Channel1_IRQHandler [WEAK] + EXPORT DMA0_Channel2_IRQHandler [WEAK] + EXPORT DMA0_Channel3_IRQHandler [WEAK] + EXPORT DMA0_Channel4_IRQHandler [WEAK] + EXPORT DMA0_Channel5_IRQHandler [WEAK] + EXPORT DMA0_Channel6_IRQHandler [WEAK] + EXPORT ADC_IRQHandler [WEAK] + EXPORT CAN0_TX_IRQHandler [WEAK] + EXPORT CAN0_RX0_IRQHandler [WEAK] + EXPORT CAN0_RX1_IRQHandler [WEAK] + EXPORT CAN0_EWMC_IRQHandler [WEAK] + EXPORT EXTI5_9_IRQHandler [WEAK] + EXPORT TIMER0_BRK_TIMER8_IRQHandler [WEAK] + EXPORT TIMER0_UP_TIMER9_IRQHandler [WEAK] + EXPORT TIMER0_TRG_CMT_TIMER10_IRQHandler [WEAK] + EXPORT TIMER0_Channel_IRQHandler [WEAK] + EXPORT TIMER1_IRQHandler [WEAK] + EXPORT TIMER2_IRQHandler [WEAK] + EXPORT TIMER3_IRQHandler [WEAK] + EXPORT I2C0_EV_IRQHandler [WEAK] + EXPORT I2C0_ER_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT SPI0_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT USART0_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT EXTI10_15_IRQHandler [WEAK] + EXPORT RTC_Alarm_IRQHandler [WEAK] + EXPORT USBFS_WKUP_IRQHandler [WEAK] + EXPORT TIMER7_BRK_TIMER11_IRQHandler [WEAK] + EXPORT TIMER7_UP_TIMER12_IRQHandler [WEAK] + EXPORT TIMER7_TRG_CMT_TIMER13_IRQHandler [WEAK] + EXPORT TIMER7_Channel_IRQHandler [WEAK] + EXPORT DMA0_Channel7_IRQHandler [WEAK] + EXPORT EXMC_IRQHandler [WEAK] + EXPORT SDIO_IRQHandler [WEAK] + EXPORT TIMER4_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT UART3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT TIMER5_DAC_IRQHandler [WEAK] + EXPORT TIMER6_IRQHandler [WEAK] + EXPORT DMA1_Channel0_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT ENET_IRQHandler [WEAK] + EXPORT ENET_WKUP_IRQHandler [WEAK] + EXPORT CAN1_TX_IRQHandler [WEAK] + EXPORT CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_EWMC_IRQHandler [WEAK] + EXPORT USBFS_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT USART5_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT USBHS_EP1_Out_IRQHandler [WEAK] + EXPORT USBHS_EP1_In_IRQHandler [WEAK] + EXPORT USBHS_WKUP_IRQHandler [WEAK] + EXPORT USBHS_IRQHandler [WEAK] + EXPORT DCI_IRQHandler [WEAK] + EXPORT TRNG_IRQHandler [WEAK] + EXPORT FPU_IRQHandler [WEAK] + EXPORT UART6_IRQHandler [WEAK] + EXPORT UART7_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT SPI4_IRQHandler [WEAK] + EXPORT SPI5_IRQHandler [WEAK] + EXPORT SAI_IRQHandler [WEAK] + EXPORT TLI_IRQHandler [WEAK] + EXPORT TLI_ER_IRQHandler [WEAK] + EXPORT IPA_IRQHandler [WEAK] + EXPORT PKCAU_IRQHandler [WEAK] + EXPORT I2C3_EV_IRQHandler [WEAK] + EXPORT I2C3_ER_IRQHandler [WEAK] + EXPORT I2C4_EV_IRQHandler [WEAK] + EXPORT I2C4_ER_IRQHandler [WEAK] + EXPORT I2C5_EV_IRQHandler [WEAK] + EXPORT I2C5_ER_IRQHandler [WEAK] + EXPORT I2C3_WKUP_IRQHandler [WEAK] + EXPORT I2C4_WKUP_IRQHandler [WEAK] + EXPORT I2C5_WKUP_IRQHandler [WEAK] + EXPORT SYSCFG_SRAM_ECC_ER_IRQHandler [WEAK] + EXPORT HAU_IRQHandler [WEAK] + EXPORT CAU_IRQHandler [WEAK] + +;/* external interrupts handler */ +WWDGT_IRQHandler +LVD_IRQHandler +TAMPER_STAMP_IRQHandler +RTC_WKUP_IRQHandler +FMC_IRQHandler +RCU_CTC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA0_Channel0_IRQHandler +DMA0_Channel1_IRQHandler +DMA0_Channel2_IRQHandler +DMA0_Channel3_IRQHandler +DMA0_Channel4_IRQHandler +DMA0_Channel5_IRQHandler +DMA0_Channel6_IRQHandler +ADC_IRQHandler +CAN0_TX_IRQHandler +CAN0_RX0_IRQHandler +CAN0_RX1_IRQHandler +CAN0_EWMC_IRQHandler +EXTI5_9_IRQHandler +TIMER0_BRK_TIMER8_IRQHandler +TIMER0_UP_TIMER9_IRQHandler +TIMER0_TRG_CMT_TIMER10_IRQHandler +TIMER0_Channel_IRQHandler +TIMER1_IRQHandler +TIMER2_IRQHandler +TIMER3_IRQHandler +I2C0_EV_IRQHandler +I2C0_ER_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +SPI0_IRQHandler +SPI1_IRQHandler +USART0_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +EXTI10_15_IRQHandler +RTC_Alarm_IRQHandler +USBFS_WKUP_IRQHandler +TIMER7_BRK_TIMER11_IRQHandler +TIMER7_UP_TIMER12_IRQHandler +TIMER7_TRG_CMT_TIMER13_IRQHandler +TIMER7_Channel_IRQHandler +DMA0_Channel7_IRQHandler +EXMC_IRQHandler +SDIO_IRQHandler +TIMER4_IRQHandler +SPI2_IRQHandler +UART3_IRQHandler +UART4_IRQHandler +TIMER5_DAC_IRQHandler +TIMER6_IRQHandler +DMA1_Channel0_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +ENET_IRQHandler +ENET_WKUP_IRQHandler +CAN1_TX_IRQHandler +CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_EWMC_IRQHandler +USBFS_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +USART5_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +USBHS_EP1_Out_IRQHandler +USBHS_EP1_In_IRQHandler +USBHS_WKUP_IRQHandler +USBHS_IRQHandler +DCI_IRQHandler +TRNG_IRQHandler +FPU_IRQHandler +UART6_IRQHandler +UART7_IRQHandler +SPI3_IRQHandler +SPI4_IRQHandler +SPI5_IRQHandler +SAI_IRQHandler +TLI_IRQHandler +TLI_ER_IRQHandler +IPA_IRQHandler +PKCAU_IRQHandler +I2C3_EV_IRQHandler +I2C3_ER_IRQHandler +I2C4_EV_IRQHandler +I2C4_ER_IRQHandler +I2C5_EV_IRQHandler +I2C5_ER_IRQHandler +I2C3_WKUP_IRQHandler +I2C4_WKUP_IRQHandler +I2C5_WKUP_IRQHandler +SYSCFG_SRAM_ECC_ER_IRQHandler +HAU_IRQHandler +CAU_IRQHandler + + B . + ENDP + + ALIGN + +; user Initial Stack & Heap + + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap PROC + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + ENDP + + ALIGN + + ENDIF + + END diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/IAR/startup_gd32f5xx.s b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/IAR/startup_gd32f5xx.s new file mode 100644 index 0000000..8dccb3f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/IAR/startup_gd32f5xx.s @@ -0,0 +1,755 @@ +;/*! +; \file startup_gd32f5xx.s +; \brief start up file +; +; \version 2023-12-20, V1.0.0, firmware for GD32F5xx +;*/ +; +;/* +; * Copyright (c) 2009-2018 Arm Limited. All rights reserved. +; * Copyright (c) 2023, GigaDevice Semiconductor Inc. +; * +; * 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. +; */ +; +;/* This file refers the CMSIS standard, some adjustments are made according to GigaDevice chips */ + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) ; top of stack + DCD Reset_Handler ; Vector Number 1,Reset Handler + + DCD NMI_Handler ; Vector Number 2,NMI Handler + DCD HardFault_Handler ; Vector Number 3,Hard Fault Handler + DCD MemManage_Handler ; Vector Number 4,MPU Fault Handler + DCD BusFault_Handler ; Vector Number 5,Bus Fault Handler + DCD UsageFault_Handler ; Vector Number 6,Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; Vector Number 11,SVCall Handler + DCD DebugMon_Handler ; Vector Number 12,Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; Vector Number 14,PendSV Handler + DCD SysTick_Handler ; Vector Number 15,SysTick Handler + + ; External Interrupts + DCD WWDGT_IRQHandler ; 16:Window Watchdog Timer + DCD LVD_IRQHandler ; 17:LVD through EXTI Line detect + DCD TAMPER_STAMP_IRQHandler ; 18:Tamper and TimeStamp through EXTI Line detect + DCD RTC_WKUP_IRQHandler ; 19:RTC Wakeup through EXTI Line + DCD FMC_IRQHandler ; 20:FMC + DCD RCU_CTC_IRQHandler ; 21:RCU and CTC + DCD EXTI0_IRQHandler ; 22:EXTI Line 0 + DCD EXTI1_IRQHandler ; 23:EXTI Line 1 + DCD EXTI2_IRQHandler ; 24:EXTI Line 2 + DCD EXTI3_IRQHandler ; 25:EXTI Line 3 + DCD EXTI4_IRQHandler ; 26:EXTI Line 4 + DCD DMA0_Channel0_IRQHandler ; 27:DMA0 Channel0 + DCD DMA0_Channel1_IRQHandler ; 28:DMA0 Channel1 + DCD DMA0_Channel2_IRQHandler ; 29:DMA0 Channel2 + DCD DMA0_Channel3_IRQHandler ; 30:DMA0 Channel3 + DCD DMA0_Channel4_IRQHandler ; 31:DMA0 Channel4 + DCD DMA0_Channel5_IRQHandler ; 32:DMA0 Channel5 + DCD DMA0_Channel6_IRQHandler ; 33:DMA0 Channel6 + DCD ADC_IRQHandler ; 34:ADC + DCD CAN0_TX_IRQHandler ; 35:CAN0 TX + DCD CAN0_RX0_IRQHandler ; 36:CAN0 RX0 + DCD CAN0_RX1_IRQHandler ; 37:CAN0 RX1 + DCD CAN0_EWMC_IRQHandler ; 38:CAN0 EWMC + DCD EXTI5_9_IRQHandler ; 39:EXTI5 to EXTI9 + DCD TIMER0_BRK_TIMER8_IRQHandler ; 40:TIMER0 Break and TIMER8 + DCD TIMER0_UP_TIMER9_IRQHandler ; 41:TIMER0 Update and TIMER9 + DCD TIMER0_TRG_CMT_TIMER10_IRQHandler ; 42:TIMER0 Trigger and Commucation and TIMER10 + DCD TIMER0_Channel_IRQHandler ; 43:TIMER0 Channel Capture Compare + DCD TIMER1_IRQHandler ; 44:TIMER1 + DCD TIMER2_IRQHandler ; 45:TIMER2 + DCD TIMER3_IRQHandler ; 46:TIMER3 + DCD I2C0_EV_IRQHandler ; 47:I2C0 Event + DCD I2C0_ER_IRQHandler ; 48:I2C0 Error + DCD I2C1_EV_IRQHandler ; 49:I2C1 Event + DCD I2C1_ER_IRQHandler ; 50:I2C1 Error + DCD SPI0_IRQHandler ; 51:SPI0 + DCD SPI1_IRQHandler ; 52:SPI1 + DCD USART0_IRQHandler ; 53:USART0 + DCD USART1_IRQHandler ; 54:USART1 + DCD USART2_IRQHandler ; 55:USART2 + DCD EXTI10_15_IRQHandler ; 56:EXTI10 to EXTI15 + DCD RTC_Alarm_IRQHandler ; 57:RTC Alarm + DCD USBFS_WKUP_IRQHandler ; 58:USBFS Wakeup + DCD TIMER7_BRK_TIMER11_IRQHandler ; 59:TIMER7 Break and TIMER11 + DCD TIMER7_UP_TIMER12_IRQHandler ; 60:TIMER7 Update and TIMER12 + DCD TIMER7_TRG_CMT_TIMER13_IRQHandler ; 61:TIMER7 Trigger and Commucation and TIMER13 + DCD TIMER7_Channel_IRQHandler ; 62:TIMER7 Channel Capture Compare + DCD DMA0_Channel7_IRQHandler ; 63:DMA0 Channel7 + DCD EXMC_IRQHandler ; 64:EXMC + DCD SDIO_IRQHandler ; 65:SDIO + DCD TIMER4_IRQHandler ; 66:TIMER4 + DCD SPI2_IRQHandler ; 67:SPI2 + DCD UART3_IRQHandler ; 68:UART3 + DCD UART4_IRQHandler ; 69:UART4 + DCD TIMER5_DAC_IRQHandler ; 70:TIMER5 and DAC0 DAC1 Underrun error + DCD TIMER6_IRQHandler ; 71:TIMER6 + DCD DMA1_Channel0_IRQHandler ; 72:DMA1 Channel0 + DCD DMA1_Channel1_IRQHandler ; 73:DMA1 Channel1 + DCD DMA1_Channel2_IRQHandler ; 74:DMA1 Channel2 + DCD DMA1_Channel3_IRQHandler ; 75:DMA1 Channel3 + DCD DMA1_Channel4_IRQHandler ; 76:DMA1 Channel4 + DCD ENET_IRQHandler ; 77:Ethernet + DCD ENET_WKUP_IRQHandler ; 78:Ethernet Wakeup through EXTI Line + DCD CAN1_TX_IRQHandler ; 79:CAN1 TX + DCD CAN1_RX0_IRQHandler ; 80:CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; 81:CAN1 RX1 + DCD CAN1_EWMC_IRQHandler ; 82:CAN1 EWMC + DCD USBFS_IRQHandler ; 83:USBFS + DCD DMA1_Channel5_IRQHandler ; 84:DMA1 Channel5 + DCD DMA1_Channel6_IRQHandler ; 85:DMA1 Channel6 + DCD DMA1_Channel7_IRQHandler ; 86:DMA1 Channel7 + DCD USART5_IRQHandler ; 87:USART5 + DCD I2C2_EV_IRQHandler ; 88:I2C2 Event + DCD I2C2_ER_IRQHandler ; 89:I2C2 Error + DCD USBHS_EP1_Out_IRQHandler ; 90:USBHS Endpoint 1 Out + DCD USBHS_EP1_In_IRQHandler ; 91:USBHS Endpoint 1 in + DCD USBHS_WKUP_IRQHandler ; 92:USBHS Wakeup through EXTI Line + DCD USBHS_IRQHandler ; 93:USBHS + DCD DCI_IRQHandler ; 94:DCI + DCD 0 ; 95:Reserved + DCD TRNG_IRQHandler ; 96:TRNG + DCD FPU_IRQHandler ; 97:FPU + DCD UART6_IRQHandler ; 98:UART6 + DCD UART7_IRQHandler ; 99:UART7 + DCD SPI3_IRQHandler ; 100:SPI3 + DCD SPI4_IRQHandler ; 101:SPI4 + DCD SPI5_IRQHandler ; 102:SPI5 + DCD SAI_IRQHandler ; 103:SAI + DCD TLI_IRQHandler ; 104:TLI + DCD TLI_ER_IRQHandler ; 105:TLI Error + DCD IPA_IRQHandler ; 106:IPA + DCD PKCAU_IRQHandler ; 107:PKCAU + DCD I2C3_EV_IRQHandler ; 108:I2C3 Event + DCD I2C3_ER_IRQHandler ; 109:I2C3 Error + DCD I2C4_EV_IRQHandler ; 110:I2C4 Event + DCD I2C4_ER_IRQHandler ; 111:I2C4 Error + DCD I2C5_EV_IRQHandler ; 112:I2C5 Event + DCD I2C5_ER_IRQHandler ; 113:I2C5 Error + DCD I2C3_WKUP_IRQHandler ; 114:I2C3 Wakeup through EXTI Line + DCD I2C4_WKUP_IRQHandler ; 115:I2C4 Wakeup through EXTI Line + DCD I2C5_WKUP_IRQHandler ; 116:I2C5 Wakeup through EXTI Line + DCD SYSCFG_SRAM_ECC_ER_IRQHandler ; 117:SYSCFG SRAM ECC Error + DCD HAU_IRQHandler ; 118:HAU + DCD CAU_IRQHandler ; 119:CAU + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:NOROOT:REORDER(2) +Reset_Handler +; LDR r0, =0x1FFF7A20 +; LDR r2, [r0] +; LDR r0, = 0x0000FFFF +; AND r2, r2, r0 +; LSL r2, r2, #10 + LDR r2, =0x80000 + LDR r1, =0x20000000 + MOV r0, #0x00 + +SRAM_INIT + STM r1!, {r0} + SUBS r2, r2, #4 + CMP r2, #0x00 + BNE SRAM_INIT + + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDGT_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +WWDGT_IRQHandler + B WWDGT_IRQHandler + + PUBWEAK LVD_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +LVD_IRQHandler + B LVD_IRQHandler + + PUBWEAK TAMPER_STAMP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TAMPER_STAMP_IRQHandler + B TAMPER_STAMP_IRQHandler + + PUBWEAK RTC_WKUP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +RTC_WKUP_IRQHandler + B RTC_WKUP_IRQHandler + + PUBWEAK FMC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +FMC_IRQHandler + B FMC_IRQHandler + + PUBWEAK RCU_CTC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +RCU_CTC_IRQHandler + B RCU_CTC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA0_Channel0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA0_Channel0_IRQHandler + B DMA0_Channel0_IRQHandler + + PUBWEAK DMA0_Channel1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA0_Channel1_IRQHandler + B DMA0_Channel1_IRQHandler + + PUBWEAK DMA0_Channel2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA0_Channel2_IRQHandler + B DMA0_Channel2_IRQHandler + + PUBWEAK DMA0_Channel3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA0_Channel3_IRQHandler + B DMA0_Channel3_IRQHandler + + PUBWEAK DMA0_Channel4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA0_Channel4_IRQHandler + B DMA0_Channel4_IRQHandler + + PUBWEAK DMA0_Channel5_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA0_Channel5_IRQHandler + B DMA0_Channel5_IRQHandler + + PUBWEAK DMA0_Channel6_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA0_Channel6_IRQHandler + B DMA0_Channel6_IRQHandler + + PUBWEAK ADC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +ADC_IRQHandler + B ADC_IRQHandler + + PUBWEAK CAN0_TX_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAN0_TX_IRQHandler + B CAN0_TX_IRQHandler + + PUBWEAK CAN0_RX0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAN0_RX0_IRQHandler + B CAN0_RX0_IRQHandler + + PUBWEAK CAN0_RX1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAN0_RX1_IRQHandler + B CAN0_RX1_IRQHandler + + PUBWEAK CAN0_EWMC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAN0_EWMC_IRQHandler + B CAN0_EWMC_IRQHandler + + PUBWEAK EXTI5_9_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI5_9_IRQHandler + B EXTI5_9_IRQHandler + + PUBWEAK TIMER0_BRK_TIMER8_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER0_BRK_TIMER8_IRQHandler + B TIMER0_BRK_TIMER8_IRQHandler + + PUBWEAK TIMER0_UP_TIMER9_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER0_UP_TIMER9_IRQHandler + B TIMER0_UP_TIMER9_IRQHandler + + PUBWEAK TIMER0_TRG_CMT_TIMER10_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER0_TRG_CMT_TIMER10_IRQHandler + B TIMER0_TRG_CMT_TIMER10_IRQHandler + + PUBWEAK TIMER0_Channel_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER0_Channel_IRQHandler + B TIMER0_Channel_IRQHandler + + PUBWEAK TIMER1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER1_IRQHandler + B TIMER1_IRQHandler + + PUBWEAK TIMER2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER2_IRQHandler + B TIMER2_IRQHandler + + PUBWEAK TIMER3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER3_IRQHandler + B TIMER3_IRQHandler + + PUBWEAK I2C0_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C0_EV_IRQHandler + B I2C0_EV_IRQHandler + + PUBWEAK I2C0_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C0_ER_IRQHandler + B I2C0_ER_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK SPI0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI0_IRQHandler + B SPI0_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK USART0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USART0_IRQHandler + B USART0_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK EXTI10_15_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI10_15_IRQHandler + B EXTI10_15_IRQHandler + + PUBWEAK RTC_Alarm_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +RTC_Alarm_IRQHandler + B RTC_Alarm_IRQHandler + + PUBWEAK USBFS_WKUP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USBFS_WKUP_IRQHandler + B USBFS_WKUP_IRQHandler + + PUBWEAK TIMER7_BRK_TIMER11_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER7_BRK_TIMER11_IRQHandler + B TIMER7_BRK_TIMER11_IRQHandler + + PUBWEAK TIMER7_UP_TIMER12_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER7_UP_TIMER12_IRQHandler + B TIMER7_UP_TIMER12_IRQHandler + + PUBWEAK TIMER7_TRG_CMT_TIMER13_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER7_TRG_CMT_TIMER13_IRQHandler + B TIMER7_TRG_CMT_TIMER13_IRQHandler + + PUBWEAK TIMER7_Channel_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER7_Channel_IRQHandler + B TIMER7_Channel_IRQHandler + + PUBWEAK DMA0_Channel7_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA0_Channel7_IRQHandler + B DMA0_Channel7_IRQHandler + + PUBWEAK EXMC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXMC_IRQHandler + B EXMC_IRQHandler + + PUBWEAK SDIO_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SDIO_IRQHandler + B SDIO_IRQHandler + + PUBWEAK TIMER4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER4_IRQHandler + B TIMER4_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK UART3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +UART3_IRQHandler + B UART3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK TIMER5_DAC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER5_DAC_IRQHandler + B TIMER5_DAC_IRQHandler + + PUBWEAK TIMER6_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIMER6_IRQHandler + B TIMER6_IRQHandler + + PUBWEAK DMA1_Channel0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel0_IRQHandler + B DMA1_Channel0_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK ENET_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +ENET_IRQHandler + B ENET_IRQHandler + + PUBWEAK ENET_WKUP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +ENET_WKUP_IRQHandler + B ENET_WKUP_IRQHandler + + PUBWEAK CAN1_TX_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAN1_TX_IRQHandler + B CAN1_TX_IRQHandler + + PUBWEAK CAN1_RX0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAN1_RX0_IRQHandler + B CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_EWMC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAN1_EWMC_IRQHandler + B CAN1_EWMC_IRQHandler + + PUBWEAK USBFS_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USBFS_IRQHandler + B USBFS_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK USART5_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USART5_IRQHandler + B USART5_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK USBHS_EP1_Out_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USBHS_EP1_Out_IRQHandler + B USBHS_EP1_Out_IRQHandler + + PUBWEAK USBHS_EP1_In_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USBHS_EP1_In_IRQHandler + B USBHS_EP1_In_IRQHandler + + PUBWEAK USBHS_WKUP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USBHS_WKUP_IRQHandler + B USBHS_WKUP_IRQHandler + + PUBWEAK USBHS_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USBHS_IRQHandler + B USBHS_IRQHandler + + PUBWEAK DCI_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DCI_IRQHandler + B DCI_IRQHandler + + PUBWEAK TRNG_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TRNG_IRQHandler + B TRNG_IRQHandler + + PUBWEAK FPU_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +FPU_IRQHandler + B FPU_IRQHandler + + PUBWEAK UART6_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +UART6_IRQHandler + B UART6_IRQHandler + + PUBWEAK UART7_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +UART7_IRQHandler + B UART7_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK SPI4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI4_IRQHandler + B SPI4_IRQHandler + + PUBWEAK SPI5_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI5_IRQHandler + B SPI5_IRQHandler + + PUBWEAK SAI_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SAI_IRQHandler + B SAI_IRQHandler + + PUBWEAK TLI_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TLI_IRQHandler + B TLI_IRQHandler + + PUBWEAK TLI_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TLI_ER_IRQHandler + B TLI_ER_IRQHandler + + PUBWEAK IPA_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +IPA_IRQHandler + B IPA_IRQHandler + + PUBWEAK PKCAU_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +PKCAU_IRQHandler + B PKCAU_IRQHandler + + PUBWEAK I2C3_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C3_EV_IRQHandler + B I2C3_EV_IRQHandler + + PUBWEAK I2C3_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C3_ER_IRQHandler + B I2C3_ER_IRQHandler + + PUBWEAK I2C4_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C4_EV_IRQHandler + B I2C4_EV_IRQHandler + + PUBWEAK I2C4_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C4_ER_IRQHandler + B I2C4_ER_IRQHandler + + PUBWEAK I2C5_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C5_EV_IRQHandler + B I2C5_EV_IRQHandler + + PUBWEAK I2C5_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C5_ER_IRQHandler + B I2C5_ER_IRQHandler + + PUBWEAK I2C3_WKUP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C3_WKUP_IRQHandler + B I2C3_WKUP_IRQHandler + + PUBWEAK I2C4_WKUP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C4_WKUP_IRQHandler + B I2C4_WKUP_IRQHandler + + PUBWEAK I2C5_WKUP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C5_WKUP_IRQHandler + B I2C5_WKUP_IRQHandler + + PUBWEAK SYSCFG_SRAM_ECC_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SYSCFG_SRAM_ECC_ER_IRQHandler + B SYSCFG_SRAM_ECC_ER_IRQHandler + + PUBWEAK HAU_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +HAU_IRQHandler + B HAU_IRQHandler + + PUBWEAK CAU_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CAU_IRQHandler + B CAU_IRQHandler + + END \ No newline at end of file diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/system_gd32f5xx.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/system_gd32f5xx.c new file mode 100644 index 0000000..7e17102 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/GD/GD32F5xx/Source/system_gd32f5xx.c @@ -0,0 +1,934 @@ +/*! + \file system_gd32f5xx.c + \brief CMSIS Cortex-M33 Device Peripheral Access Layer Source File for + GD32F5xx Device Series +*/ + +/* + * Copyright (c) 2009-2018 Arm Limited. All rights reserved. + * Copyright (c) 2023, GigaDevice Semiconductor Inc. + * + * 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. + */ + +/* This file refers the CMSIS standard, some adjustments are made according to GigaDevice chips */ + +#include "gd32f5xx.h" + +/* system frequency define */ +#define __IRC16M (IRC16M_VALUE) /* internal 16 MHz RC oscillator frequency */ +#define __HXTAL (HXTAL_VALUE) /* high speed crystal oscillator frequency */ +#define __SYS_OSC_CLK (__IRC16M) /* main oscillator frequency */ + +#ifdef USE_BOOTLOADER +#define VECT_TAB_OFFSET (uint32_t)0x20000 /* vector table base offset */ +#else +#define VECT_TAB_OFFSET (uint32_t)0x00 /* vector table base offset */ +#endif +/* select a system clock by uncommenting the following line */ +//#define __SYSTEM_CLOCK_IRC16M (uint32_t)(__IRC16M) +//#define __SYSTEM_CLOCK_HXTAL (uint32_t)(__HXTAL) +//#define __SYSTEM_CLOCK_120M_PLL_IRC16M (uint32_t)(120000000) +//#define __SYSTEM_CLOCK_120M_PLL_8M_HXTAL (uint32_t)(120000000) +//#define __SYSTEM_CLOCK_120M_PLL_25M_HXTAL (uint32_t)(120000000) +//#define __SYSTEM_CLOCK_168M_PLL_IRC16M (uint32_t)(168000000) +//#define __SYSTEM_CLOCK_168M_PLL_8M_HXTAL (uint32_t)(168000000) +//#define __SYSTEM_CLOCK_168M_PLL_25M_HXTAL (uint32_t)(168000000) +//#define __SYSTEM_CLOCK_200M_PLL_IRC16M (uint32_t)(200000000) +//#define __SYSTEM_CLOCK_200M_PLL_8M_HXTAL (uint32_t)(200000000) +#define __SYSTEM_CLOCK_200M_PLL_25M_HXTAL (uint32_t)(200000000) + +#define RCU_MODIFY(__delay) do{ \ + volatile uint32_t i; \ + if(0U != __delay){ \ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV2; \ + for(i=0U; i<__delay; i++){ \ + } \ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV4; \ + for(i=0U; i<__delay; i++){ \ + } \ + } \ + }while(0) + +#define SEL_IRC16M 0x00U +#define SEL_HXTAL 0x01U +#define SEL_PLLP 0x02U + +/* set the system clock frequency and declare the system clock configuration function */ +#ifdef __SYSTEM_CLOCK_IRC16M +uint32_t SystemCoreClock = __SYSTEM_CLOCK_IRC16M; +static void system_clock_16m_irc16m(void); +#elif defined (__SYSTEM_CLOCK_HXTAL) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_HXTAL; +static void system_clock_hxtal(void); +#elif defined (__SYSTEM_CLOCK_120M_PLL_IRC16M) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_120M_PLL_IRC16M; +static void system_clock_120m_irc16m(void); +#elif defined (__SYSTEM_CLOCK_120M_PLL_8M_HXTAL) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_120M_PLL_8M_HXTAL; +static void system_clock_120m_8m_hxtal(void); +#elif defined (__SYSTEM_CLOCK_120M_PLL_25M_HXTAL) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_120M_PLL_25M_HXTAL; +static void system_clock_120m_25m_hxtal(void); +#elif defined (__SYSTEM_CLOCK_168M_PLL_IRC16M) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_168M_PLL_IRC16M; +static void system_clock_168m_irc16m(void); +#elif defined (__SYSTEM_CLOCK_168M_PLL_8M_HXTAL) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_168M_PLL_8M_HXTAL; +static void system_clock_168m_8m_hxtal(void); +#elif defined (__SYSTEM_CLOCK_168M_PLL_25M_HXTAL) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_168M_PLL_25M_HXTAL; +static void system_clock_168m_25m_hxtal(void); +#elif defined (__SYSTEM_CLOCK_200M_PLL_IRC16M) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_200M_PLL_IRC16M; +static void system_clock_200m_irc16m(void); +#elif defined (__SYSTEM_CLOCK_200M_PLL_8M_HXTAL) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_200M_PLL_8M_HXTAL; +static void system_clock_200m_8m_hxtal(void); +#elif defined (__SYSTEM_CLOCK_200M_PLL_25M_HXTAL) +uint32_t SystemCoreClock = __SYSTEM_CLOCK_200M_PLL_25M_HXTAL; +static void system_clock_200m_25m_hxtal(void); + +#endif /* __SYSTEM_CLOCK_IRC16M */ + +/* configure the system clock */ +static void system_clock_config(void); + +/*! + \brief setup the microcontroller system, initialize the system + \param[in] none + \param[out] none + \retval none +*/ +void SystemInit (void) +{ + /* FPU settings */ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1U) + SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ +#endif + /* Reset the RCU clock configuration to the default reset state */ + /* Set IRC16MEN bit */ + RCU_CTL |= RCU_CTL_IRC16MEN; + while(0U == (RCU_CTL & RCU_CTL_IRC16MSTB)){ + } + RCU_MODIFY(0x50U); + + RCU_CFG0 &= ~RCU_CFG0_SCS; + + /* Reset HXTALEN, CKMEN and PLLEN bits */ + RCU_CTL &= ~(RCU_CTL_PLLEN | RCU_CTL_CKMEN | RCU_CTL_HXTALEN); + + /* Reset HSEBYP bit */ + RCU_CTL &= ~(RCU_CTL_HXTALBPS); + + /* Reset CFG0 register */ + RCU_CFG0 = 0x00000000U; + + /* wait until IRC16M is selected as system clock */ + while(RCU_SCSS_IRC16M != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } + + /* Reset PLLCFGR register */ + RCU_PLL = 0x24003010U; + + /* Disable all interrupts */ + RCU_INT = 0x00000000U; + + /* Configure the System clock source, PLL Multiplier and Divider factors, + AHB/APBx prescalers and Flash settings */ + system_clock_config(); + +#ifdef VECT_TAB_SRAM + nvic_vector_table_set(NVIC_VECTTAB_RAM, VECT_TAB_OFFSET); +#else + nvic_vector_table_set(NVIC_VECTTAB_FLASH, VECT_TAB_OFFSET); +#endif +} +/*! + \brief configure the system clock + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_config(void) +{ +#ifdef __SYSTEM_CLOCK_IRC16M + system_clock_16m_irc16m(); +#elif defined (__SYSTEM_CLOCK_HXTAL) + system_clock_hxtal(); +#elif defined (__SYSTEM_CLOCK_120M_PLL_IRC16M) + system_clock_120m_irc16m(); +#elif defined (__SYSTEM_CLOCK_120M_PLL_8M_HXTAL) + system_clock_120m_8m_hxtal(); +#elif defined (__SYSTEM_CLOCK_120M_PLL_25M_HXTAL) + system_clock_120m_25m_hxtal(); +#elif defined (__SYSTEM_CLOCK_168M_PLL_IRC16M) + system_clock_168m_irc16m(); +#elif defined (__SYSTEM_CLOCK_168M_PLL_8M_HXTAL) + system_clock_168m_8m_hxtal(); +#elif defined (__SYSTEM_CLOCK_168M_PLL_25M_HXTAL) + system_clock_168m_25m_hxtal(); +#elif defined (__SYSTEM_CLOCK_200M_PLL_IRC16M) + system_clock_200m_irc16m(); +#elif defined (__SYSTEM_CLOCK_200M_PLL_8M_HXTAL) + system_clock_200m_8m_hxtal(); +#elif defined (__SYSTEM_CLOCK_200M_PLL_25M_HXTAL) + system_clock_200m_25m_hxtal(); +#endif /* __SYSTEM_CLOCK_IRC16M */ +} + +#ifdef __SYSTEM_CLOCK_IRC16M +/*! + \brief configure the system clock to 16M by IRC16M + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_16m_irc16m(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable IRC16M */ + RCU_CTL |= RCU_CTL_IRC16MEN; + + /* wait until IRC16M is stable or the startup time is longer than IRC16M_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_IRC16MSTB); + }while((0U == stab_flag) && (IRC16M_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_IRC16MSTB)){ + while(1){ + } + } + + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV1; + /* APB1 = AHB */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV1; + + /* select IRC16M as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_IRC16M; + + /* wait until IRC16M is selected as system clock */ + while(RCU_SCSS_IRC16M != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_HXTAL) +/*! + \brief configure the system clock to HXTAL + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_hxtal(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable HXTAL */ + RCU_CTL |= RCU_CTL_HXTALEN; + + /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB); + }while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){ + while(1){ + } + } + + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV1; + /* APB1 = AHB */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV1; + + /* select HXTAL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_HXTAL; + + /* wait until HXTAL is selected as system clock */ + while(RCU_SCSS_HXTAL != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_120M_PLL_IRC16M) +/*! + \brief configure the system clock to 120M by PLL which selects IRC16M as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_120m_irc16m(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable IRC16M */ + RCU_CTL |= RCU_CTL_IRC16MEN; + + /* wait until IRC16M is stable or the startup time is longer than IRC16M_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_IRC16MSTB); + }while((0U == stab_flag) && (IRC16M_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_IRC16MSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + + /* IRC16M is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB/2 */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB/4 */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 16, PLL_N = 240, PLL_P = 2, PLL_Q = 5 */ + RCU_PLL = (16U | (240U << 6U) | (((2U >> 1U) - 1U) << 16U) | + (RCU_PLLSRC_IRC16M) | (5U << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 120 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_120M_PLL_8M_HXTAL) +/*! + \brief configure the system clock to 120M by PLL which selects HXTAL(8M) as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_120m_8m_hxtal(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable HXTAL */ + RCU_CTL |= RCU_CTL_HXTALEN; + + /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB); + }while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + + /* HXTAL is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB/2 */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB/4 */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 8, PLL_N = 240, PLL_P = 2, PLL_Q = 5 */ + RCU_PLL = (8U | (240U << 6U) | (((2U >> 1U) - 1U) << 16U) | + (RCU_PLLSRC_HXTAL) | (5U << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 120 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_120M_PLL_25M_HXTAL) +/*! + \brief configure the system clock to 120M by PLL which selects HXTAL(25M) as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_120m_25m_hxtal(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable HXTAL */ + RCU_CTL |= RCU_CTL_HXTALEN; + + /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB); + }while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + + /* HXTAL is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB/2 */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB/4 */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 25, PLL_N = 240, PLL_P = 2, PLL_Q = 5 */ + RCU_PLL = (25U | (240U << 6U) | (((2U >> 1U) - 1U) << 16U) | + (RCU_PLLSRC_HXTAL) | (5U << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 120 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_168M_PLL_IRC16M) +/*! + \brief configure the system clock to 168M by PLL which selects IRC16M as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_168m_irc16m(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable IRC16M */ + RCU_CTL |= RCU_CTL_IRC16MEN; + + /* wait until IRC16M is stable or the startup time is longer than IRC16M_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_IRC16MSTB); + }while((0U == stab_flag) && (IRC16M_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_IRC16MSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + + /* IRC16M is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB/2 */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB/4 */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 16, PLL_N = 336, PLL_P = 2, PLL_Q = 7 */ + RCU_PLL = (16U | (336U << 6U) | (((2U >> 1U) - 1U) << 16U) | + (RCU_PLLSRC_IRC16M) | (7U << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 168 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_168M_PLL_8M_HXTAL) +/*! + \brief configure the system clock to 168M by PLL which selects HXTAL(8M) as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_168m_8m_hxtal(void) +{ + uint32_t timeout = 0U; + + /* enable HXTAL */ + RCU_CTL |= RCU_CTL_HXTALEN; + + /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */ + while((0U == (RCU_CTL & RCU_CTL_HXTALSTB)) && (HXTAL_STARTUP_TIMEOUT != timeout++)){ + } + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + /* HXTAL is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB/2 */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB/4 */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 8, PLL_N = 336, PLL_P = 2, PLL_Q = 7 */ + RCU_PLL = (8U | (336 << 6U) | (((2 >> 1U) -1U) << 16U) | + (RCU_PLLSRC_HXTAL) | (7 << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 168 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_168M_PLL_25M_HXTAL) +/*! + \brief configure the system clock to 168M by PLL which selects HXTAL(25M) as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_168m_25m_hxtal(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable HXTAL */ + RCU_CTL |= RCU_CTL_HXTALEN; + + /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB); + }while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + + /* HXTAL is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 25, PLL_N = 336, PLL_P = 2, PLL_Q = 7 */ + RCU_PLL = (25U | (336U << 6U) | (((2U >> 1U) - 1U) << 16U) | + (RCU_PLLSRC_HXTAL) | (7U << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 168 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_200M_PLL_IRC16M) +/*! + \brief configure the system clock to 200M by PLL which selects IRC16M as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_200m_irc16m(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable IRC16M */ + RCU_CTL |= RCU_CTL_IRC16MEN; + + /* wait until IRC16M is stable or the startup time is longer than IRC16M_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_IRC16MSTB); + }while((0U == stab_flag) && (IRC16M_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_IRC16MSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + + /* IRC16M is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB/2 */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB/4 */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 16, PLL_N = 400, PLL_P = 2, PLL_Q = 9 */ + RCU_PLL = (16U | (400U << 6U) | (((2U >> 1U) - 1U) << 16U) | + (RCU_PLLSRC_IRC16M) | (9U << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 200 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_200M_PLL_8M_HXTAL) +/*! + \brief configure the system clock to 200M by PLL which selects HXTAL(8M) as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_200m_8m_hxtal(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable HXTAL */ + RCU_CTL |= RCU_CTL_HXTALEN; + + /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB); + }while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + + /* HXTAL is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB/2 */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB/4 */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 8, PLL_N = 400, PLL_P = 2, PLL_Q = 9 */ + RCU_PLL = (8U | (400U << 6U) | (((2U >> 1U) - 1U) << 16U) | + (RCU_PLLSRC_HXTAL) | (9U << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 200 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} + +#elif defined (__SYSTEM_CLOCK_200M_PLL_25M_HXTAL) +/*! + \brief configure the system clock to 200M by PLL which selects HXTAL(25M) as its clock source + \param[in] none + \param[out] none + \retval none +*/ +static void system_clock_200m_25m_hxtal(void) +{ + uint32_t timeout = 0U; + uint32_t stab_flag = 0U; + + /* enable HXTAL */ + RCU_CTL |= RCU_CTL_HXTALEN; + + /* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */ + do{ + timeout++; + stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB); + }while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout)); + + /* if fail */ + if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){ + while(1){ + } + } + + RCU_APB1EN |= RCU_APB1EN_PMUEN; + PMU_CTL |= PMU_CTL_LDOVS; + + /* HXTAL is stable */ + /* AHB = SYSCLK */ + RCU_CFG0 |= RCU_AHB_CKSYS_DIV1; + /* APB2 = AHB/2 */ + RCU_CFG0 |= RCU_APB2_CKAHB_DIV2; + /* APB1 = AHB/4 */ + RCU_CFG0 |= RCU_APB1_CKAHB_DIV4; + + /* Configure the main PLL, PSC = 25, PLL_N = 400, PLL_P = 2, PLL_Q = 9 */ + RCU_PLL = (12U | (400U << 6U) | (((2U >> 1U) - 1U) << 16U) | + (RCU_PLLSRC_HXTAL) | (9U << 24U)); + + /* enable PLL */ + RCU_CTL |= RCU_CTL_PLLEN; + + /* wait until PLL is stable */ + while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){ + } + + /* Enable the high-drive to extend the clock frequency to 200 Mhz */ + PMU_CTL |= PMU_CTL_HDEN; + while(0U == (PMU_CS & PMU_CS_HDRF)){ + } + + /* select the high-drive mode */ + PMU_CTL |= PMU_CTL_HDS; + while(0U == (PMU_CS & PMU_CS_HDSRF)){ + } + + /* select PLL as system clock */ + RCU_CFG0 &= ~RCU_CFG0_SCS; + RCU_CFG0 |= RCU_CKSYSSRC_PLLP; + + /* wait until PLL is selected as system clock */ + while( RCU_SCSS_PLLP != (RCU_CFG0 & RCU_CFG0_SCSS)){ + } +} +#endif /* __SYSTEM_CLOCK_IRC16M */ +/*! + \brief update the SystemCoreClock with current core clock retrieved from cpu registers + \param[in] none + \param[out] none + \retval none +*/ +void SystemCoreClockUpdate(void) +{ + uint32_t sws; + uint32_t pllpsc, plln, pllsel, pllp, ck_src, idx, clk_exp; + + /* exponent of AHB, APB1 and APB2 clock divider */ + const uint8_t ahb_exp[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + + sws = GET_BITS(RCU_CFG0, 2, 3); + switch(sws){ + /* IRC16M is selected as CK_SYS */ + case SEL_IRC16M: + SystemCoreClock = IRC16M_VALUE; + break; + /* HXTAL is selected as CK_SYS */ + case SEL_HXTAL: + SystemCoreClock = HXTAL_VALUE; + break; + /* PLLP is selected as CK_SYS */ + case SEL_PLLP: + /* get the value of PLLPSC[5:0] */ + pllpsc = GET_BITS(RCU_PLL, 0U, 5U); + plln = GET_BITS(RCU_PLL, 6U, 14U); + pllp = (GET_BITS(RCU_PLL, 16U, 17U) + 1U) * 2U; + /* PLL clock source selection, HXTAL or IRC8M/2 */ + pllsel = (RCU_PLL & RCU_PLL_PLLSEL); + if (RCU_PLLSRC_HXTAL == pllsel) { + ck_src = HXTAL_VALUE; + } else { + ck_src = IRC16M_VALUE; + } + SystemCoreClock = ((ck_src / pllpsc) * plln) / pllp; + break; + /* IRC16M is selected as CK_SYS */ + default: + SystemCoreClock = IRC16M_VALUE; + break; + } + /* calculate AHB clock frequency */ + idx = GET_BITS(RCU_CFG0, 4, 7); + clk_exp = ahb_exp[idx]; + SystemCoreClock = SystemCoreClock >> clk_exp; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/LICENSE.TXT b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/LICENSE.TXT new file mode 100644 index 0000000..8dada3e --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/CMSIS/LICENSE.TXT @@ -0,0 +1,201 @@ + 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 {yyyy} {name of copyright owner} + + 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. diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_adc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_adc.h new file mode 100644 index 0000000..d3e4943 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_adc.h @@ -0,0 +1,513 @@ +/*! + \file gd32f5xx_adc.h + \brief definitions for the ADC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_ADC_H +#define GD32F5XX_ADC_H + +#include "gd32f5xx.h" + +/* ADC definitions */ +#define ADC0 ADC_BASE +#define ADC1 (ADC_BASE + 0x100U) +#define ADC2 (ADC_BASE + 0x200U) + +/* registers definitions */ +#define ADC_STAT(adcx) REG32((adcx) + 0x00U) /*!< ADC status register */ +#define ADC_CTL0(adcx) REG32((adcx) + 0x04U) /*!< ADC control register 0 */ +#define ADC_CTL1(adcx) REG32((adcx) + 0x08U) /*!< ADC control register 1 */ +#define ADC_SAMPT0(adcx) REG32((adcx) + 0x0CU) /*!< ADC sampling time register 0 */ +#define ADC_SAMPT1(adcx) REG32((adcx) + 0x10U) /*!< ADC sampling time register 1 */ +#define ADC_IOFF0(adcx) REG32((adcx) + 0x14U) /*!< ADC inserted channel data offset register 0 */ +#define ADC_IOFF1(adcx) REG32((adcx) + 0x18U) /*!< ADC inserted channel data offset register 1 */ +#define ADC_IOFF2(adcx) REG32((adcx) + 0x1CU) /*!< ADC inserted channel data offset register 2 */ +#define ADC_IOFF3(adcx) REG32((adcx) + 0x20U) /*!< ADC inserted channel data offset register 3 */ +#define ADC_WDHT(adcx) REG32((adcx) + 0x24U) /*!< ADC watchdog high threshold register */ +#define ADC_WDLT(adcx) REG32((adcx) + 0x28U) /*!< ADC watchdog low threshold register */ +#define ADC_RSQ0(adcx) REG32((adcx) + 0x2CU) /*!< ADC routine sequence register 0 */ +#define ADC_RSQ1(adcx) REG32((adcx) + 0x30U) /*!< ADC routine sequence register 1 */ +#define ADC_RSQ2(adcx) REG32((adcx) + 0x34U) /*!< ADC routine sequence register 2 */ +#define ADC_ISQ(adcx) REG32((adcx) + 0x38U) /*!< ADC inserted sequence register */ +#define ADC_IDATA0(adcx) REG32((adcx) + 0x3CU) /*!< ADC inserted data register 0 */ +#define ADC_IDATA1(adcx) REG32((adcx) + 0x40U) /*!< ADC inserted data register 1 */ +#define ADC_IDATA2(adcx) REG32((adcx) + 0x44U) /*!< ADC inserted data register 2 */ +#define ADC_IDATA3(adcx) REG32((adcx) + 0x48U) /*!< ADC inserted data register 3 */ +#define ADC_RDATA(adcx) REG32((adcx) + 0x4CU) /*!< ADC routine data register */ +#define ADC_OVSAMPCTL(adcx) REG32((adcx) + 0x80U) /*!< ADC oversampling control register */ +#define ADC_SSTAT REG32((ADC_BASE) + 0x300U) /*!< ADC summary status register */ +#define ADC_SYNCCTL REG32((ADC_BASE) + 0x304U) /*!< ADC synchronization control register */ +#define ADC_SYNCDATA REG32((ADC_BASE) + 0x308U) /*!< ADC synchronization routine data register */ + +/* bits definitions */ +/* ADC_STAT */ +#define ADC_STAT_WDE BIT(0) /*!< analog watchdog event flag */ +#define ADC_STAT_EOC BIT(1) /*!< end of conversion */ +#define ADC_STAT_EOIC BIT(2) /*!< inserted channel end of conversion */ +#define ADC_STAT_STIC BIT(3) /*!< inserted channel start flag */ +#define ADC_STAT_STRC BIT(4) /*!< routine channel start flag */ +#define ADC_STAT_ROVF BIT(5) /*!< routine data register overflow */ + +/* ADC_CTL0 */ +#define ADC_CTL0_WDCHSEL BITS(0,4) /*!< analog watchdog channel select bits */ +#define ADC_CTL0_EOCIE BIT(5) /*!< interrupt enable for EOC */ +#define ADC_CTL0_WDEIE BIT(6) /*!< analog watchdog interrupt enable */ +#define ADC_CTL0_EOICIE BIT(7) /*!< interrupt enable for inserted channels */ +#define ADC_CTL0_SM BIT(8) /*!< scan mode */ +#define ADC_CTL0_WDSC BIT(9) /*!< when in scan mode, analog watchdog is effective on a single channel */ +#define ADC_CTL0_ICA BIT(10) /*!< automatic inserted sequence conversion */ +#define ADC_CTL0_DISRC BIT(11) /*!< discontinuous mode on routine channels */ +#define ADC_CTL0_DISIC BIT(12) /*!< discontinuous mode on inserted channels */ +#define ADC_CTL0_DISNUM BITS(13,15) /*!< discontinuous mode channel count */ +#define ADC_CTL0_IWDEN BIT(22) /*!< analog watchdog enable on inserted channels */ +#define ADC_CTL0_RWDEN BIT(23) /*!< analog watchdog enable on routine channels */ +#define ADC_CTL0_DRES BITS(24,25) /*!< ADC data resolution */ +#define ADC_CTL0_ROVFIE BIT(26) /*!< interrupt enable for ROVF */ + +/* ADC_CTL1 */ +#define ADC_CTL1_ADCON BIT(0) /*!< ADC converter on */ +#define ADC_CTL1_CTN BIT(1) /*!< continuous conversion */ +#define ADC_CTL1_CLB BIT(2) /*!< ADC calibration */ +#define ADC_CTL1_RSTCLB BIT(3) /*!< reset calibration */ +#define ADC_CTL1_DMA BIT(8) /*!< direct memory access mode */ +#define ADC_CTL1_DDM BIT(9) /*!< DMA disable mode */ +#define ADC_CTL1_EOCM BIT(10) /*!< end of conversion mode */ +#define ADC_CTL1_DAL BIT(11) /*!< data alignment */ +#define ADC_CTL1_ETSIC BITS(16,19) /*!< external event select for inserted sequence */ +#define ADC_CTL1_ETMIC BITS(20,21) /*!< external trigger conversion mode for inserted channels */ +#define ADC_CTL1_SWICST BIT(22) /*!< start conversion of inserted channels */ +#define ADC_CTL1_ETSRC BITS(24,27) /*!< external event select for routine sequence */ +#define ADC_CTL1_ETMRC BITS(28,29) /*!< external trigger conversion mode for routine channels */ +#define ADC_CTL1_SWRCST BIT(30) /*!< start conversion of routine channels */ + +/* ADC_SAMPTx x=0..1 */ +#define ADC_SAMPTX_SPTN BITS(0,2) /*!< channel x sample time selection */ + +/* ADC_IOFFx x=0..3 */ +#define ADC_IOFFX_IOFF BITS(0,11) /*!< data offset for inserted channel x */ + +/* ADC_WDHT */ +#define ADC_WDHT_WDHT BITS(0,11) /*!< analog watchdog high threshold */ + +/* ADC_WDLT */ +#define ADC_WDLT_WDLT BITS(0,11) /*!< analog watchdog low threshold */ + +/* ADC_RSQx */ +#define ADC_RSQX_RSQN BITS(0,4) /*!< x conversion in routine sequence */ +#define ADC_RSQ0_RL BITS(20,23) /*!< routine channel sequence length */ + +/* ADC_ISQ */ +#define ADC_ISQ_ISQN BITS(0,4) /*!< x conversion in inserted sequence */ +#define ADC_ISQ_IL BITS(20,21) /*!< inserted sequence length */ + +/* ADC_IDATAx x=0..3*/ +#define ADC_IDATAX_IDATAN BITS(0,15) /*!< inserted data x */ + +/* ADC_RDATA */ +#define ADC_RDATA_RDATA BITS(0,15) /*!< routine data */ + +/* ADC_OVSAMPCTL */ +#define ADC_OVSAMPCTL_OVSEN BIT(0) /*!< oversampling enable */ +#define ADC_OVSAMPCTL_OVSR BITS(2,4) /*!< oversampling ratio */ +#define ADC_OVSAMPCTL_OVSS BITS(5,8) /*!< oversampling shift */ +#define ADC_OVSAMPCTL_TOVS BIT(9) /*!< triggered oversampling */ + +/* ADC_SSTAT */ +#define ADC_SSTAT_WDE0 BIT(0) /*!< the mirror image of the WDE bit of ADC0 */ +#define ADC_SSTAT_EOC0 BIT(1) /*!< the mirror image of the EOC bit of ADC0 */ +#define ADC_SSTAT_EOIC0 BIT(2) /*!< the mirror image of the EOIC bit of ADC0 */ +#define ADC_SSTAT_STIC0 BIT(3) /*!< the mirror image of the STIC bit of ADC0 */ +#define ADC_SSTAT_STRC0 BIT(4) /*!< the mirror image of the STRC bit of ADC0 */ +#define ADC_SSTAT_ROVF0 BIT(5) /*!< the mirror image of the ROVF bit of ADC0 */ +#define ADC_SSTAT_WDE1 BIT(8) /*!< the mirror image of the WDE bit of ADC1 */ +#define ADC_SSTAT_EOC1 BIT(9) /*!< the mirror image of the EOC bit of ADC1 */ +#define ADC_SSTAT_EOIC1 BIT(10) /*!< the mirror image of the EOIC bit of ADC1 */ +#define ADC_SSTAT_STIC1 BIT(11) /*!< the mirror image of the STIC bit of ADC1 */ +#define ADC_SSTAT_STRC1 BIT(12) /*!< the mirror image of the STRC bit of ADC1 */ +#define ADC_SSTAT_ROVF1 BIT(13) /*!< the mirror image of the ROVF bit of ADC1 */ +#define ADC_SSTAT_WDE2 BIT(16) /*!< the mirror image of the WDE bit of ADC2 */ +#define ADC_SSTAT_EOC2 BIT(17) /*!< the mirror image of the EOC bit of ADC2 */ +#define ADC_SSTAT_EOIC2 BIT(18) /*!< the mirror image of the EOIC bit of ADC2 */ +#define ADC_SSTAT_STIC2 BIT(19) /*!< the mirror image of the STIC bit of ADC2 */ +#define ADC_SSTAT_STRC2 BIT(20) /*!< the mirror image of the STRC bit of ADC2 */ +#define ADC_SSTAT_ROVF2 BIT(21) /*!< the mirror image of the ROVF bit of ADC2 */ + +/* ADC_SYNCCTL */ +#define ADC_SYNCCTL_SYNCM BITS(0,4) /*!< ADC synchronization mode */ +#define ADC_SYNCCTL_SYNCDLY BITS(8,11) /*!< ADC synchronization delay */ +#define ADC_SYNCCTL_SYNCDDM BIT(13) /*!< ADC synchronization DMA disable mode */ +#define ADC_SYNCCTL_SYNCDMA BITS(14,15) /*!< ADC synchronization DMA mode selection */ +#define ADC_SYNCCTL_ADCCK BITS(16,18) /*!< ADC clock */ +#define ADC_SYNCCTL_VBATEN BIT(22) /*!< channel 18 (1/4 voltate of external battery) enable of ADC0 */ +#define ADC_SYNCCTL_TSVREN BIT(23) /*!< channel 16 (temperature sensor) and 17 (internal reference voltage) enable of ADC0 */ + +/* ADC_SYNCDATA */ +#define ADC_SYNCDATA_SYNCDATA0 BITS(0,15) /*!< routine data1 in ADC synchronization mode */ +#define ADC_SYNCDATA_SYNCDATA1 BITS(16,31) /*!< routine data2 in ADC synchronization mode */ + +/* constants definitions */ +/* ADC status flag */ +#define ADC_FLAG_WDE ADC_STAT_WDE /*!< analog watchdog event flag */ +#define ADC_FLAG_EOC ADC_STAT_EOC /*!< end of conversion */ +#define ADC_FLAG_EOIC ADC_STAT_EOIC /*!< inserted channel end of conversion */ +#define ADC_FLAG_STIC ADC_STAT_STIC /*!< inserted channel start flag */ +#define ADC_FLAG_STRC ADC_STAT_STRC /*!< routine channel start flag */ +#define ADC_FLAG_ROVF ADC_STAT_ROVF /*!< routine data register overflow */ + +/* adc_ctl0 register value */ +#define CTL0_DISNUM(regval) (BITS(13,15) & ((uint32_t)(regval) << 13)) /*!< write value to ADC_CTL0_DISNUM bit field */ + +/* ADC special function definitions */ +#define ADC_SCAN_MODE ADC_CTL0_SM /*!< scan mode */ +#define ADC_INSERTED_CHANNEL_AUTO ADC_CTL0_ICA /*!< inserted sequence convert automatically */ +#define ADC_CONTINUOUS_MODE ADC_CTL1_CTN /*!< continuous mode */ + +/* temperature sensor channel, internal reference voltage channel, VBAT channel */ +#define ADC_VBAT_CHANNEL_SWITCH ADC_SYNCCTL_VBATEN /*!< VBAT channel */ +#define ADC_TEMP_VREF_CHANNEL_SWITCH ADC_SYNCCTL_TSVREN /*!< Vref and Vtemp channel */ + +/* ADC synchronization mode */ +#define SYNCCTL_SYNCM(regval) (BITS(0,4) & ((uint32_t)(regval))) /*!< write value to ADC_CTL0_SYNCM bit field */ +#define ADC_SYNC_MODE_INDEPENDENT SYNCCTL_SYNCM(0) /*!< ADC synchronization mode disabled.All the ADCs work independently */ +#define ADC_DAUL_ROUTINE_PARALLEL_INSERTED_PARALLEL SYNCCTL_SYNCM(1) /*!< ADC0 and ADC1 work in combined routine parallel & inserted parallel mode. ADC2 works independently */ +#define ADC_DAUL_ROUTINE_PARALLEL_INSERTED_ROTATION SYNCCTL_SYNCM(2) /*!< ADC0 and ADC1 work in combined routine parallel & trigger rotation mode. ADC2 works independently */ +#define ADC_DAUL_INSERTED_PARALLEL SYNCCTL_SYNCM(5) /*!< ADC0 and ADC1 work in inserted parallel mode. ADC2 works independently */ +#define ADC_DAUL_ROUTINE_PARALLEL SYNCCTL_SYNCM(6) /*!< ADC0 and ADC1 work in routine parallel mode. ADC2 works independently */ +#define ADC_DAUL_ROUTINE_FOLLOW_UP SYNCCTL_SYNCM(7) /*!< ADC0 and ADC1 work in follow-up mode. ADC2 works independently */ +#define ADC_DAUL_INSERTED_TRRIGGER_ROTATION SYNCCTL_SYNCM(9) /*!< ADC0 and ADC1 work in trigger rotation mode. ADC2 works independently */ +#define ADC_ALL_ROUTINE_PARALLEL_INSERTED_PARALLEL SYNCCTL_SYNCM(17) /*!< all ADCs work in combined routine parallel & inserted parallel mode */ +#define ADC_ALL_ROUTINE_PARALLEL_INSERTED_ROTATION SYNCCTL_SYNCM(18) /*!< all ADCs work in combined routine parallel & trigger rotation mode */ +#define ADC_ALL_INSERTED_PARALLEL SYNCCTL_SYNCM(21) /*!< all ADCs work in inserted parallel mode */ +#define ADC_ALL_ROUTINE_PARALLEL SYNCCTL_SYNCM(22) /*!< all ADCs work in routine parallel mode */ +#define ADC_ALL_ROUTINE_FOLLOW_UP SYNCCTL_SYNCM(23) /*!< all ADCs work in follow-up mode */ +#define ADC_ALL_INSERTED_TRRIGGER_ROTATION SYNCCTL_SYNCM(25) /*!< all ADCs work in trigger rotation mode */ + +/* ADC data alignment */ +#define ADC_DATAALIGN_RIGHT ((uint32_t)0x00000000U) /*!< LSB alignment */ +#define ADC_DATAALIGN_LEFT ADC_CTL1_DAL /*!< MSB alignment */ + +/* external trigger mode for routine and inserted channel */ +#define EXTERNAL_TRIGGER_DISABLE ((uint32_t)0x00000000U) /*!< external trigger disable */ +#define EXTERNAL_TRIGGER_RISING ((uint32_t)0x00000001U) /*!< rising edge of external trigger */ +#define EXTERNAL_TRIGGER_FALLING ((uint32_t)0x00000002U) /*!< falling edge of external trigger */ +#define EXTERNAL_TRIGGER_RISING_FALLING ((uint32_t)0x00000003U) /*!< rising and falling edge of external trigger */ + +/* ADC external trigger select for routine channel */ +#define CTL1_ETSRC(regval) (BITS(24,27) & ((uint32_t)(regval) << 24)) +#define ADC_EXTTRIG_ROUTINE_T0_CH0 CTL1_ETSRC(0) /*!< timer 0 CC0 event select */ +#define ADC_EXTTRIG_ROUTINE_T0_CH1 CTL1_ETSRC(1) /*!< timer 0 CC1 event select */ +#define ADC_EXTTRIG_ROUTINE_T0_CH2 CTL1_ETSRC(2) /*!< timer 0 CC2 event select */ +#define ADC_EXTTRIG_ROUTINE_T1_CH1 CTL1_ETSRC(3) /*!< timer 1 CC1 event select */ +#define ADC_EXTTRIG_ROUTINE_T1_CH2 CTL1_ETSRC(4) /*!< timer 1 CC2 event select */ +#define ADC_EXTTRIG_ROUTINE_T1_CH3 CTL1_ETSRC(5) /*!< timer 1 CC3 event select */ +#define ADC_EXTTRIG_ROUTINE_T1_TRGO CTL1_ETSRC(6) /*!< timer 1 TRGO event select */ +#define ADC_EXTTRIG_ROUTINE_T2_CH0 CTL1_ETSRC(7) /*!< timer 2 CC0 event select */ +#define ADC_EXTTRIG_ROUTINE_T2_TRGO CTL1_ETSRC(8) /*!< timer 2 TRGO event select */ +#define ADC_EXTTRIG_ROUTINE_T3_CH3 CTL1_ETSRC(9) /*!< timer 3 CC3 event select */ +#define ADC_EXTTRIG_ROUTINE_T4_CH0 CTL1_ETSRC(10) /*!< timer 4 CC0 event select */ +#define ADC_EXTTRIG_ROUTINE_T4_CH1 CTL1_ETSRC(11) /*!< timer 4 CC1 event select */ +#define ADC_EXTTRIG_ROUTINE_T4_CH2 CTL1_ETSRC(12) /*!< timer 4 CC2 event select */ +#define ADC_EXTTRIG_ROUTINE_T7_CH0 CTL1_ETSRC(13) /*!< timer 7 CC0 event select */ +#define ADC_EXTTRIG_ROUTINE_T7_TRGO CTL1_ETSRC(14) /*!< timer 7 TRGO event select */ +#define ADC_EXTTRIG_ROUTINE_EXTI_11 CTL1_ETSRC(15) /*!< extiline 11 select */ + +/* ADC external trigger select for inserted channel */ +#define CTL1_ETSIC(regval) (BITS(16,19) & ((uint32_t)(regval) << 16)) +#define ADC_EXTTRIG_INSERTED_T0_CH3 CTL1_ETSIC(0) /*!< timer0 capture compare 3 */ +#define ADC_EXTTRIG_INSERTED_T0_TRGO CTL1_ETSIC(1) /*!< timer0 TRGO event */ +#define ADC_EXTTRIG_INSERTED_T1_CH0 CTL1_ETSIC(2) /*!< timer1 capture compare 0 */ +#define ADC_EXTTRIG_INSERTED_T1_TRGO CTL1_ETSIC(3) /*!< timer1 TRGO event */ +#define ADC_EXTTRIG_INSERTED_T2_CH1 CTL1_ETSIC(4) /*!< timer2 capture compare 1 */ +#define ADC_EXTTRIG_INSERTED_T2_CH3 CTL1_ETSIC(5) /*!< timer2 capture compare 3 */ +#define ADC_EXTTRIG_INSERTED_T3_CH0 CTL1_ETSIC(6) /*!< timer3 capture compare 0 */ +#define ADC_EXTTRIG_INSERTED_T3_CH1 CTL1_ETSIC(7) /*!< timer3 capture compare 1 */ +#define ADC_EXTTRIG_INSERTED_T3_CH2 CTL1_ETSIC(8) /*!< timer3 capture compare 2 */ +#define ADC_EXTTRIG_INSERTED_T3_TRGO CTL1_ETSIC(9) /*!< timer3 capture compare TRGO */ +#define ADC_EXTTRIG_INSERTED_T4_CH3 CTL1_ETSIC(10) /*!< timer4 capture compare 3 */ +#define ADC_EXTTRIG_INSERTED_T4_TRGO CTL1_ETSIC(11) /*!< timer4 capture compare TRGO */ +#define ADC_EXTTRIG_INSERTED_T7_CH1 CTL1_ETSIC(12) /*!< timer7 capture compare 1 */ +#define ADC_EXTTRIG_INSERTED_T7_CH2 CTL1_ETSIC(13) /*!< timer7 capture compare 2 */ +#define ADC_EXTTRIG_INSERTED_T7_CH3 CTL1_ETSIC(14) /*!< timer7 capture compare 3 */ +#define ADC_EXTTRIG_INSERTED_EXTI_15 CTL1_ETSIC(15) /*!< external interrupt line 15 */ + +/* ADC channel sample time */ +#define SAMPTX_SPT(regval) (BITS(0,2) & ((uint32_t)(regval) << 0)) /*!< write value to ADC_SAMPTX_SPT bit field */ +#define ADC_SAMPLETIME_3 SAMPTX_SPT(0) /*!< 3 sampling cycles */ +#define ADC_SAMPLETIME_15 SAMPTX_SPT(1) /*!< 15 sampling cycles */ +#define ADC_SAMPLETIME_28 SAMPTX_SPT(2) /*!< 28 sampling cycles */ +#define ADC_SAMPLETIME_56 SAMPTX_SPT(3) /*!< 56 sampling cycles */ +#define ADC_SAMPLETIME_84 SAMPTX_SPT(4) /*!< 84 sampling cycles */ +#define ADC_SAMPLETIME_112 SAMPTX_SPT(5) /*!< 112 sampling cycles */ +#define ADC_SAMPLETIME_144 SAMPTX_SPT(6) /*!< 144 sampling cycles */ +#define ADC_SAMPLETIME_480 SAMPTX_SPT(7) /*!< 480 sampling cycles */ + +/* adc_ioffx register value */ +#define IOFFX_IOFF(regval) (BITS(0,11) & ((uint32_t)(regval) << 0)) /*!< write value to ADC_IOFFX_IOFF bit field */ + +/* adc_wdht register value */ +#define WDHT_WDHT(regval) (BITS(0,11) & ((uint32_t)(regval) << 0)) /*!< write value to ADC_WDHT_WDHT bit field */ + +/* adc_wdlt register value */ +#define WDLT_WDLT(regval) (BITS(0,11) & ((uint32_t)(regval) << 0)) /*!< write value to ADC_WDLT_WDLT bit field */ + +/* adc_rsqx register value */ +#define RSQ0_RL(regval) (BITS(20,23) & ((uint32_t)(regval) << 20)) /*!< write value to ADC_RSQ0_RL bit field */ + +/* adc_isq register value */ +#define ISQ_IL(regval) (BITS(20,21) & ((uint32_t)(regval) << 20)) /*!< write value to ADC_ISQ_IL bit field */ + +/* adc_ovsampctl register value */ +/* ADC resolution */ +#define CTL0_DRES(regval) (BITS(24,25) & ((uint32_t)(regval) << 24)) /*!< write value to ADC_CTL0_DRES bit field */ +#define ADC_RESOLUTION_12B CTL0_DRES(0) /*!< 12-bit ADC resolution */ +#define ADC_RESOLUTION_10B CTL0_DRES(1) /*!< 10-bit ADC resolution */ +#define ADC_RESOLUTION_8B CTL0_DRES(2) /*!< 8-bit ADC resolution */ +#define ADC_RESOLUTION_6B CTL0_DRES(3) /*!< 6-bit ADC resolution */ + +/* oversampling shift */ +#define OVSAMPCTL_OVSS(regval) (BITS(5,8) & ((uint32_t)(regval) << 5)) /*!< write value to ADC_OVSAMPCTL_OVSS bit field */ +#define ADC_OVERSAMPLING_SHIFT_NONE OVSAMPCTL_OVSS(0) /*!< no oversampling shift */ +#define ADC_OVERSAMPLING_SHIFT_1B OVSAMPCTL_OVSS(1) /*!< 1-bit oversampling shift */ +#define ADC_OVERSAMPLING_SHIFT_2B OVSAMPCTL_OVSS(2) /*!< 2-bit oversampling shift */ +#define ADC_OVERSAMPLING_SHIFT_3B OVSAMPCTL_OVSS(3) /*!< 3-bit oversampling shift */ +#define ADC_OVERSAMPLING_SHIFT_4B OVSAMPCTL_OVSS(4) /*!< 4-bit oversampling shift */ +#define ADC_OVERSAMPLING_SHIFT_5B OVSAMPCTL_OVSS(5) /*!< 5-bit oversampling shift */ +#define ADC_OVERSAMPLING_SHIFT_6B OVSAMPCTL_OVSS(6) /*!< 6-bit oversampling shift */ +#define ADC_OVERSAMPLING_SHIFT_7B OVSAMPCTL_OVSS(7) /*!< 7-bit oversampling shift */ +#define ADC_OVERSAMPLING_SHIFT_8B OVSAMPCTL_OVSS(8) /*!< 8-bit oversampling shift */ + +/* oversampling ratio */ +#define OVSAMPCTL_OVSR(regval) (BITS(2,4) & ((uint32_t)(regval) << 2)) /*!< write value to ADC_OVSAMPCTL_OVSR bit field */ +#define ADC_OVERSAMPLING_RATIO_MUL2 OVSAMPCTL_OVSR(0) /*!< oversampling ratio multiple 2 */ +#define ADC_OVERSAMPLING_RATIO_MUL4 OVSAMPCTL_OVSR(1) /*!< oversampling ratio multiple 4 */ +#define ADC_OVERSAMPLING_RATIO_MUL8 OVSAMPCTL_OVSR(2) /*!< oversampling ratio multiple 8 */ +#define ADC_OVERSAMPLING_RATIO_MUL16 OVSAMPCTL_OVSR(3) /*!< oversampling ratio multiple 16 */ +#define ADC_OVERSAMPLING_RATIO_MUL32 OVSAMPCTL_OVSR(4) /*!< oversampling ratio multiple 32 */ +#define ADC_OVERSAMPLING_RATIO_MUL64 OVSAMPCTL_OVSR(5) /*!< oversampling ratio multiple 64 */ +#define ADC_OVERSAMPLING_RATIO_MUL128 OVSAMPCTL_OVSR(6) /*!< oversampling ratio multiple 128 */ +#define ADC_OVERSAMPLING_RATIO_MUL256 OVSAMPCTL_OVSR(7) /*!< oversampling ratio multiple 256 */ + +/* triggered oversampling */ +#define ADC_OVERSAMPLING_ALL_CONVERT ((uint32_t)0x00000000U) /*!< all oversampled conversions for a channel are done consecutively after a trigger */ +#define ADC_OVERSAMPLING_ONE_CONVERT ADC_OVSAMPCTL_TOVS /*!< each oversampled conversion for a channel needs a trigger */ + +/* ADC channel sequence definitions */ +#define ADC_ROUTINE_CHANNEL ((uint8_t)0x01U) /*!< adc routine sequence */ +#define ADC_INSERTED_CHANNEL ((uint8_t)0x02U) /*!< adc inserted sequence */ +#define ADC_ROUTINE_INSERTED_CHANNEL ((uint8_t)0x03U) /*!< both routine and inserted sequence */ +#define ADC_CHANNEL_DISCON_DISABLE ((uint8_t)0x04U) /*!< disable discontinuous mode of routine & inserted sequence */ + +/* ADC inserted channel definitions */ +#define ADC_INSERTED_CHANNEL_0 ((uint8_t)0x00U) /*!< adc inserted channel 0 */ +#define ADC_INSERTED_CHANNEL_1 ((uint8_t)0x01U) /*!< adc inserted channel 1 */ +#define ADC_INSERTED_CHANNEL_2 ((uint8_t)0x02U) /*!< adc inserted channel 2 */ +#define ADC_INSERTED_CHANNEL_3 ((uint8_t)0x03U) /*!< adc inserted channel 3 */ + +/* ADC channel definitions */ +#define ADC_CHANNEL_0 ((uint8_t)0x00U) /*!< ADC channel 0 */ +#define ADC_CHANNEL_1 ((uint8_t)0x01U) /*!< ADC channel 1 */ +#define ADC_CHANNEL_2 ((uint8_t)0x02U) /*!< ADC channel 2 */ +#define ADC_CHANNEL_3 ((uint8_t)0x03U) /*!< ADC channel 3 */ +#define ADC_CHANNEL_4 ((uint8_t)0x04U) /*!< ADC channel 4 */ +#define ADC_CHANNEL_5 ((uint8_t)0x05U) /*!< ADC channel 5 */ +#define ADC_CHANNEL_6 ((uint8_t)0x06U) /*!< ADC channel 6 */ +#define ADC_CHANNEL_7 ((uint8_t)0x07U) /*!< ADC channel 7 */ +#define ADC_CHANNEL_8 ((uint8_t)0x08U) /*!< ADC channel 8 */ +#define ADC_CHANNEL_9 ((uint8_t)0x09U) /*!< ADC channel 9 */ +#define ADC_CHANNEL_10 ((uint8_t)0x0AU) /*!< ADC channel 10 */ +#define ADC_CHANNEL_11 ((uint8_t)0x0BU) /*!< ADC channel 11 */ +#define ADC_CHANNEL_12 ((uint8_t)0x0CU) /*!< ADC channel 12 */ +#define ADC_CHANNEL_13 ((uint8_t)0x0DU) /*!< ADC channel 13 */ +#define ADC_CHANNEL_14 ((uint8_t)0x0EU) /*!< ADC channel 14 */ +#define ADC_CHANNEL_15 ((uint8_t)0x0FU) /*!< ADC channel 15 */ +#define ADC_CHANNEL_16 ((uint8_t)0x10U) /*!< ADC channel 16 */ +#define ADC_CHANNEL_17 ((uint8_t)0x11U) /*!< ADC channel 17 */ +#define ADC_CHANNEL_18 ((uint8_t)0x12U) /*!< ADC channel 18 */ + +/* ADC interrupt flag */ +#define ADC_INT_WDE ADC_CTL0_WDEIE /*!< analog watchdog event interrupt */ +#define ADC_INT_EOC ADC_CTL0_EOCIE /*!< end of sequence conversion interrupt */ +#define ADC_INT_EOIC ADC_CTL0_EOICIE /*!< end of inserted sequence conversion interrupt */ +#define ADC_INT_ROVF ADC_CTL0_ROVFIE /*!< routine data register overflow */ + +/* ADC interrupt flag */ +#define ADC_INT_FLAG_WDE ADC_STAT_WDE /*!< analog watchdog event interrupt */ +#define ADC_INT_FLAG_EOC ADC_STAT_EOC /*!< end of sequence conversion interrupt */ +#define ADC_INT_FLAG_EOIC ADC_STAT_EOIC /*!< end of inserted sequence conversion interrupt */ +#define ADC_INT_FLAG_ROVF ADC_STAT_ROVF /*!< routine data register overflow */ + +/* configure the ADC clock for all the ADCs */ +#define SYNCCTL_ADCCK(regval) (BITS(16,18) & ((uint32_t)(regval) << 16)) +#define ADC_ADCCK_PCLK2_DIV2 SYNCCTL_ADCCK(0) /*!< PCLK2 div2 */ +#define ADC_ADCCK_PCLK2_DIV4 SYNCCTL_ADCCK(1) /*!< PCLK2 div4 */ +#define ADC_ADCCK_PCLK2_DIV6 SYNCCTL_ADCCK(2) /*!< PCLK2 div6 */ +#define ADC_ADCCK_PCLK2_DIV8 SYNCCTL_ADCCK(3) /*!< PCLK2 div8 */ +#define ADC_ADCCK_HCLK_DIV5 SYNCCTL_ADCCK(4) /*!< HCLK div5 */ +#define ADC_ADCCK_HCLK_DIV6 SYNCCTL_ADCCK(5) /*!< HCLK div6 */ +#define ADC_ADCCK_HCLK_DIV10 SYNCCTL_ADCCK(6) /*!< HCLK div10 */ +#define ADC_ADCCK_HCLK_DIV20 SYNCCTL_ADCCK(7) /*!< HCLK div20 */ + +/* ADC synchronization delay */ +#define ADC_SYNC_DELAY_5CYCLE ((uint32_t)0x00000000U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 5 ADC clock cycles. */ +#define ADC_SYNC_DELAY_6CYCLE ((uint32_t)0x00000100U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 6 ADC clock cycles. */ +#define ADC_SYNC_DELAY_7CYCLE ((uint32_t)0x00000200U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 7 ADC clock cycles. */ +#define ADC_SYNC_DELAY_8CYCLE ((uint32_t)0x00000300U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 8 ADC clock cycles. */ +#define ADC_SYNC_DELAY_9CYCLE ((uint32_t)0x00000400U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 9 ADC clock cycles. */ +#define ADC_SYNC_DELAY_10CYCLE ((uint32_t)0x00000500U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 10 ADC clock cycles. */ +#define ADC_SYNC_DELAY_11CYCLE ((uint32_t)0x00000600U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 11 ADC clock cycles. */ +#define ADC_SYNC_DELAY_12CYCLE ((uint32_t)0x00000700U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 12 ADC clock cycles. */ +#define ADC_SYNC_DELAY_13CYCLE ((uint32_t)0x00000800U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 13 ADC clock cycles. */ +#define ADC_SYNC_DELAY_14CYCLE ((uint32_t)0x00000900U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 14 ADC clock cycles. */ +#define ADC_SYNC_DELAY_15CYCLE ((uint32_t)0x00000A00U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 15 ADC clock cycles. */ +#define ADC_SYNC_DELAY_16CYCLE ((uint32_t)0x00000B00U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 16 ADC clock cycles. */ +#define ADC_SYNC_DELAY_17CYCLE ((uint32_t)0x00000C00U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 17 ADC clock cycles. */ +#define ADC_SYNC_DELAY_18CYCLE ((uint32_t)0x00000D00U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 18 ADC clock cycles. */ +#define ADC_SYNC_DELAY_19CYCLE ((uint32_t)0x00000E00U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 19 ADC clock cycles. */ +#define ADC_SYNC_DELAY_20CYCLE ((uint32_t)0x00000F00U) /*!< the delay between 2 sampling phases in ADC synchronization modes to 20 ADC clock cycles. */ + +/* ADC synchronization DMA mode selection */ +#define ADC_SYNC_DMA_DISABLE ((uint32_t)0x00000000U) /*!< ADC synchronization DMA disabled */ +#define ADC_SYNC_DMA_MODE0 ((uint32_t)0x00004000U) /*!< ADC synchronization DMA mode 0 */ +#define ADC_SYNC_DMA_MODE1 ((uint32_t)0x00008000U) /*!< ADC synchronization DMA mode 1 */ + +/* end of conversion mode */ +#define ADC_EOC_SET_SEQUENCE ((uint8_t)0x00U) /*!< only at the end of a sequence of routine conversions, the EOC bit is set */ +#define ADC_EOC_SET_CONVERSION ((uint8_t)0x01U) /*!< at the end of each routine conversion, the EOC bit is set */ + +/* function declarations */ +/* initialization config */ +/* reset ADC */ +void adc_deinit(void); +/* configure the ADC clock for all the ADCs */ +void adc_clock_config(uint32_t prescaler); +/* enable or disable ADC special function */ +void adc_special_function_config(uint32_t adc_periph , uint32_t function , ControlStatus newvalue); +/* configure ADC data alignment */ +void adc_data_alignment_config(uint32_t adc_periph , uint32_t data_alignment); +/* enable ADC interface */ +void adc_enable(uint32_t adc_periph); +/* disable ADC interface */ +void adc_disable(uint32_t adc_periph); +/* ADC calibration and reset calibration */ +void adc_calibration_enable(uint32_t adc_periph); +/* configure temperature sensor and internal reference voltage channel or VBAT channel function */ +void adc_channel_16_to_18(uint32_t function, ControlStatus newvalue); +/* configure ADC resolution */ +void adc_resolution_config(uint32_t adc_periph, uint32_t resolution); +/* configure ADC oversample mode */ +void adc_oversample_mode_config(uint32_t adc_periph, uint32_t mode, uint16_t shift, uint8_t ratio); +/* enable ADC oversample mode */ +void adc_oversample_mode_enable(uint32_t adc_periph); +/* disable ADC oversample mode */ +void adc_oversample_mode_disable(uint32_t adc_periph); + +/* DMA config */ +/* enable DMA request */ +void adc_dma_mode_enable(uint32_t adc_periph); +/* disable DMA request */ +void adc_dma_mode_disable(uint32_t adc_periph); +/* when DMA=1, the DMA engine issues a request at end of each routine conversion */ +void adc_dma_request_after_last_enable(uint32_t adc_periph); +/* the DMA engine is disabled after the end of transfer signal from DMA controller is detected */ +void adc_dma_request_after_last_disable(uint32_t adc_periph); + +/* routine sequence and inserted sequence config */ +/* configure ADC discontinuous mode */ +void adc_discontinuous_mode_config(uint32_t adc_periph , uint8_t adc_sequence , uint8_t length); +/* configure the length of routine sequence or inserted sequence */ +void adc_channel_length_config(uint32_t adc_periph , uint8_t adc_sequence , uint32_t length); +/* configure ADC routine channel */ +void adc_routine_channel_config(uint32_t adc_periph , uint8_t rank , uint8_t adc_channel , uint32_t sample_time); +/* configure ADC inserted channel */ +void adc_inserted_channel_config(uint32_t adc_periph , uint8_t rank , uint8_t adc_channel , uint32_t sample_time); +/* configure ADC inserted channel offset */ +void adc_inserted_channel_offset_config(uint32_t adc_periph , uint8_t inserted_channel , uint16_t offset); +/* configure ADC external trigger source */ +void adc_external_trigger_source_config(uint32_t adc_periph , uint8_t adc_sequence , uint32_t external_trigger_source); +/* enable ADC external trigger */ +void adc_external_trigger_config(uint32_t adc_periph , uint8_t adc_sequence , uint32_t trigger_mode); +/* enable ADC software trigger */ +void adc_software_trigger_enable(uint32_t adc_periph , uint8_t adc_sequence); +/* configure end of conversion mode */ +void adc_end_of_conversion_config(uint32_t adc_periph , uint8_t end_selection); + +/* get channel data */ +/* read ADC routine data register */ +uint16_t adc_routine_data_read(uint32_t adc_periph); +/* read ADC inserted data register */ +uint16_t adc_inserted_data_read(uint32_t adc_periph , uint8_t inserted_channel); + +/* watchdog config */ +/* disable ADC analog watchdog single channel */ +void adc_watchdog_single_channel_disable(uint32_t adc_periph ); +/* enable ADC analog watchdog single channel */ +void adc_watchdog_single_channel_enable(uint32_t adc_periph , uint8_t adc_channel); +/* configure ADC analog watchdog sequence */ +void adc_watchdog_sequence_channel_enable(uint32_t adc_periph , uint8_t adc_sequence); +/* disable ADC analog watchdog */ +void adc_watchdog_disable(uint32_t adc_periph , uint8_t adc_sequence); +/* configure ADC analog watchdog threshold */ +void adc_watchdog_threshold_config(uint32_t adc_periph , uint16_t low_threshold , uint16_t high_threshold); + +/* ADC synchronization */ +/* configure the ADC sync mode */ +void adc_sync_mode_config(uint32_t sync_mode); +/* configure the delay between 2 sampling phases in ADC sync modes */ +void adc_sync_delay_config(uint32_t sample_delay); +/* configure ADC sync DMA mode selection */ +void adc_sync_dma_config(uint32_t dma_mode ); +/* configure ADC sync DMA engine is disabled after the end of transfer signal from DMA controller is detected */ +void adc_sync_dma_request_after_last_enable(void); +/* configure ADC sync DMA engine issues requests according to the SYNCDMA bits */ +void adc_sync_dma_request_after_last_disable(void); +/* read ADC sync routine data register */ +uint32_t adc_sync_routine_data_read(void); + +/* interrupt & flag functions */ +/* get the bit state of ADCx software start conversion */ +FlagStatus adc_routine_software_startconv_flag_get(uint32_t adc_periph); +/* get the bit state of ADCx software inserted channel start conversion */ +FlagStatus adc_inserted_software_startconv_flag_get(uint32_t adc_periph); +/* get the ADC flag bits */ +FlagStatus adc_flag_get(uint32_t adc_periph , uint32_t adc_flag); +/* clear the ADC flag bits */ +void adc_flag_clear(uint32_t adc_periph , uint32_t adc_flag); +/* enable ADC interrupt */ +void adc_interrupt_enable(uint32_t adc_periph , uint32_t adc_interrupt); +/* disable ADC interrupt */ +void adc_interrupt_disable(uint32_t adc_periph , uint32_t adc_interrupt); +/* get the ADC interrupt bits */ +FlagStatus adc_interrupt_flag_get(uint32_t adc_periph , uint32_t adc_interrupt); +/* clear the ADC flag */ +void adc_interrupt_flag_clear(uint32_t adc_periph , uint32_t adc_interrupt); + +#endif /* GD32F5XX_ADC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_can.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_can.h new file mode 100644 index 0000000..2ed3fac --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_can.h @@ -0,0 +1,888 @@ +/*! + \file gd32f5xx_can.h + \brief definitions for the CAN + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_CAN_H +#define GD32F5XX_CAN_H + +#include "gd32f5xx.h" + +/* CAN definitions */ +#define CAN0 CAN_BASE /*!< CAN0 base address */ +#define CAN1 (CAN0 + 0x00000400U) /*!< CAN1 base address */ + +/* registers definitions */ +#define CAN_CTL(canx) REG32((canx) + 0x00000000U) /*!< CAN control register */ +#define CAN_STAT(canx) REG32((canx) + 0x00000004U) /*!< CAN status register */ +#define CAN_TSTAT(canx) REG32((canx) + 0x00000008U) /*!< CAN transmit status register*/ +#define CAN_RFIFO0(canx) REG32((canx) + 0x0000000CU) /*!< CAN receive FIFO0 register */ +#define CAN_RFIFO1(canx) REG32((canx) + 0x00000010U) /*!< CAN receive FIFO1 register */ +#define CAN_INTEN(canx) REG32((canx) + 0x00000014U) /*!< CAN interrupt enable register */ +#define CAN_ERR(canx) REG32((canx) + 0x00000018U) /*!< CAN error register */ +#define CAN_BT(canx) REG32((canx) + 0x0000001CU) /*!< CAN bit timing register */ +#define CAN_FDCTL(canx) REG32((canx) + 0x00000020U) /*!< CAN FD control register */ +#define CAN_FDSTAT(canx) REG32((canx) + 0x00000024U) /*!< CAN FD status register */ +#define CAN_FDTDC(canx) REG32((canx) + 0x00000028U) /*!< CAN FD transmitter delay compensation register */ +#define CAN_DBT(canx) REG32((canx) + 0x0000002CU) /*!< CAN date bit timing register */ +#define CAN_TMI0(canx) REG32((canx) + 0x00000180U) /*!< CAN transmit mailbox0 identifier register */ +#define CAN_TMP0(canx) REG32((canx) + 0x00000184U) /*!< CAN transmit mailbox0 property register */ +#define CAN_TMDATA00(canx) REG32((canx) + 0x00000188U) /*!< CAN transmit mailbox0 data0 register */ +#define CAN_TMDATA10(canx) REG32((canx) + 0x0000018CU) /*!< CAN transmit mailbox0 data1 register */ +#define CAN_TMI1(canx) REG32((canx) + 0x00000190U) /*!< CAN transmit mailbox1 identifier register */ +#define CAN_TMP1(canx) REG32((canx) + 0x00000194U) /*!< CAN transmit mailbox1 property register */ +#define CAN_TMDATA01(canx) REG32((canx) + 0x00000198U) /*!< CAN transmit mailbox1 data0 register */ +#define CAN_TMDATA11(canx) REG32((canx) + 0x0000019CU) /*!< CAN transmit mailbox1 data1 register */ +#define CAN_TMI2(canx) REG32((canx) + 0x000001A0U) /*!< CAN transmit mailbox2 identifier register */ +#define CAN_TMP2(canx) REG32((canx) + 0x000001A4U) /*!< CAN transmit mailbox2 property register */ +#define CAN_TMDATA02(canx) REG32((canx) + 0x000001A8U) /*!< CAN transmit mailbox2 data0 register */ +#define CAN_TMDATA12(canx) REG32((canx) + 0x000001ACU) /*!< CAN transmit mailbox2 data1 register */ +#define CAN_RFIFOMI0(canx) REG32((canx) + 0x000001B0U) /*!< CAN receive FIFO0 mailbox identifier register */ +#define CAN_RFIFOMP0(canx) REG32((canx) + 0x000001B4U) /*!< CAN receive FIFO0 mailbox property register */ +#define CAN_RFIFOMDATA00(canx) REG32((canx) + 0x000001B8U) /*!< CAN receive FIFO0 mailbox data0 register */ +#define CAN_RFIFOMDATA10(canx) REG32((canx) + 0x000001BCU) /*!< CAN receive FIFO0 mailbox data1 register */ +#define CAN_RFIFOMI1(canx) REG32((canx) + 0x000001C0U) /*!< CAN receive FIFO1 mailbox identifier register */ +#define CAN_RFIFOMP1(canx) REG32((canx) + 0x000001C4U) /*!< CAN receive FIFO1 mailbox property register */ +#define CAN_RFIFOMDATA01(canx) REG32((canx) + 0x000001C8U) /*!< CAN receive FIFO1 mailbox data0 register */ +#define CAN_RFIFOMDATA11(canx) REG32((canx) + 0x000001CCU) /*!< CAN receive FIFO1 mailbox data1 register */ +#define CAN_FCTL(canx) REG32((canx) + 0x00000200U) /*!< CAN filter control register */ +#define CAN_FMCFG(canx) REG32((canx) + 0x00000204U) /*!< CAN filter mode register */ +#define CAN_FSCFG(canx) REG32((canx) + 0x0000020CU) /*!< CAN filter scale register */ +#define CAN_FAFIFO(canx) REG32((canx) + 0x00000214U) /*!< CAN filter associated FIFO register */ +#define CAN_FW(canx) REG32((canx) + 0x0000021CU) /*!< CAN filter working register */ +#define CAN_F0DATA0(canx) REG32((canx) + 0x00000240U) /*!< CAN filter 0 data 0 register */ +#define CAN_F1DATA0(canx) REG32((canx) + 0x00000248U) /*!< CAN filter 1 data 0 register */ +#define CAN_F2DATA0(canx) REG32((canx) + 0x00000250U) /*!< CAN filter 2 data 0 register */ +#define CAN_F3DATA0(canx) REG32((canx) + 0x00000258U) /*!< CAN filter 3 data 0 register */ +#define CAN_F4DATA0(canx) REG32((canx) + 0x00000260U) /*!< CAN filter 4 data 0 register */ +#define CAN_F5DATA0(canx) REG32((canx) + 0x00000268U) /*!< CAN filter 5 data 0 register */ +#define CAN_F6DATA0(canx) REG32((canx) + 0x00000270U) /*!< CAN filter 6 data 0 register */ +#define CAN_F7DATA0(canx) REG32((canx) + 0x00000278U) /*!< CAN filter 7 data 0 register */ +#define CAN_F8DATA0(canx) REG32((canx) + 0x00000280U) /*!< CAN filter 8 data 0 register */ +#define CAN_F9DATA0(canx) REG32((canx) + 0x00000288U) /*!< CAN filter 9 data 0 register */ +#define CAN_F10DATA0(canx) REG32((canx) + 0x00000290U) /*!< CAN filter 10 data 0 register */ +#define CAN_F11DATA0(canx) REG32((canx) + 0x00000298U) /*!< CAN filter 11 data 0 register */ +#define CAN_F12DATA0(canx) REG32((canx) + 0x000002A0U) /*!< CAN filter 12 data 0 register */ +#define CAN_F13DATA0(canx) REG32((canx) + 0x000002A8U) /*!< CAN filter 13 data 0 register */ +#define CAN_F14DATA0(canx) REG32((canx) + 0x000002B0U) /*!< CAN filter 14 data 0 register */ +#define CAN_F15DATA0(canx) REG32((canx) + 0x000002B8U) /*!< CAN filter 15 data 0 register */ +#define CAN_F16DATA0(canx) REG32((canx) + 0x000002C0U) /*!< CAN filter 16 data 0 register */ +#define CAN_F17DATA0(canx) REG32((canx) + 0x000002C8U) /*!< CAN filter 17 data 0 register */ +#define CAN_F18DATA0(canx) REG32((canx) + 0x000002D0U) /*!< CAN filter 18 data 0 register */ +#define CAN_F19DATA0(canx) REG32((canx) + 0x000002D8U) /*!< CAN filter 19 data 0 register */ +#define CAN_F20DATA0(canx) REG32((canx) + 0x000002E0U) /*!< CAN filter 20 data 0 register */ +#define CAN_F21DATA0(canx) REG32((canx) + 0x000002E8U) /*!< CAN filter 21 data 0 register */ +#define CAN_F22DATA0(canx) REG32((canx) + 0x000002F0U) /*!< CAN filter 22 data 0 register */ +#define CAN_F23DATA0(canx) REG32((canx) + 0x000003F8U) /*!< CAN filter 23 data 0 register */ +#define CAN_F24DATA0(canx) REG32((canx) + 0x00000300U) /*!< CAN filter 24 data 0 register */ +#define CAN_F25DATA0(canx) REG32((canx) + 0x00000308U) /*!< CAN filter 25 data 0 register */ +#define CAN_F26DATA0(canx) REG32((canx) + 0x00000310U) /*!< CAN filter 26 data 0 register */ +#define CAN_F27DATA0(canx) REG32((canx) + 0x00000318U) /*!< CAN filter 27 data 0 register */ +#define CAN_F0DATA1(canx) REG32((canx) + 0x00000244U) /*!< CAN filter 0 data 1 register */ +#define CAN_F1DATA1(canx) REG32((canx) + 0x0000024CU) /*!< CAN filter 1 data 1 register */ +#define CAN_F2DATA1(canx) REG32((canx) + 0x00000254U) /*!< CAN filter 2 data 1 register */ +#define CAN_F3DATA1(canx) REG32((canx) + 0x0000025CU) /*!< CAN filter 3 data 1 register */ +#define CAN_F4DATA1(canx) REG32((canx) + 0x00000264U) /*!< CAN filter 4 data 1 register */ +#define CAN_F5DATA1(canx) REG32((canx) + 0x0000026CU) /*!< CAN filter 5 data 1 register */ +#define CAN_F6DATA1(canx) REG32((canx) + 0x00000274U) /*!< CAN filter 6 data 1 register */ +#define CAN_F7DATA1(canx) REG32((canx) + 0x0000027CU) /*!< CAN filter 7 data 1 register */ +#define CAN_F8DATA1(canx) REG32((canx) + 0x00000284U) /*!< CAN filter 8 data 1 register */ +#define CAN_F9DATA1(canx) REG32((canx) + 0x0000028CU) /*!< CAN filter 9 data 1 register */ +#define CAN_F10DATA1(canx) REG32((canx) + 0x00000294U) /*!< CAN filter 10 data 1 register */ +#define CAN_F11DATA1(canx) REG32((canx) + 0x0000029CU) /*!< CAN filter 11 data 1 register */ +#define CAN_F12DATA1(canx) REG32((canx) + 0x000002A4U) /*!< CAN filter 12 data 1 register */ +#define CAN_F13DATA1(canx) REG32((canx) + 0x000002ACU) /*!< CAN filter 13 data 1 register */ +#define CAN_F14DATA1(canx) REG32((canx) + 0x000002B4U) /*!< CAN filter 14 data 1 register */ +#define CAN_F15DATA1(canx) REG32((canx) + 0x000002BCU) /*!< CAN filter 15 data 1 register */ +#define CAN_F16DATA1(canx) REG32((canx) + 0x000002C4U) /*!< CAN filter 16 data 1 register */ +#define CAN_F17DATA1(canx) REG32((canx) + 0x0000024CU) /*!< CAN filter 17 data 1 register */ +#define CAN_F18DATA1(canx) REG32((canx) + 0x000002D4U) /*!< CAN filter 18 data 1 register */ +#define CAN_F19DATA1(canx) REG32((canx) + 0x000002DCU) /*!< CAN filter 19 data 1 register */ +#define CAN_F20DATA1(canx) REG32((canx) + 0x000002E4U) /*!< CAN filter 20 data 1 register */ +#define CAN_F21DATA1(canx) REG32((canx) + 0x000002ECU) /*!< CAN filter 21 data 1 register */ +#define CAN_F22DATA1(canx) REG32((canx) + 0x000002F4U) /*!< CAN filter 22 data 1 register */ +#define CAN_F23DATA1(canx) REG32((canx) + 0x000002FCU) /*!< CAN filter 23 data 1 register */ +#define CAN_F24DATA1(canx) REG32((canx) + 0x00000304U) /*!< CAN filter 24 data 1 register */ +#define CAN_F25DATA1(canx) REG32((canx) + 0x0000030CU) /*!< CAN filter 25 data 1 register */ +#define CAN_F26DATA1(canx) REG32((canx) + 0x00000314U) /*!< CAN filter 26 data 1 register */ +#define CAN_F27DATA1(canx) REG32((canx) + 0x0000031CU) /*!< CAN filter 27 data 1 register */ + +/* CAN transmit mailbox bank */ +#define CAN_TMI(canx, bank) REG32((canx) + 0x180U + ((bank) * 0x10U)) /*!< CAN transmit mailbox identifier register */ +#define CAN_TMP(canx, bank) REG32((canx) + 0x184U + ((bank) * 0x10U)) /*!< CAN transmit mailbox property register */ +#define CAN_TMDATA0(canx, bank) REG32((canx) + 0x188U + ((bank) * 0x10U)) /*!< CAN transmit mailbox data0 register */ +#define CAN_TMDATA1(canx, bank) REG32((canx) + 0x18CU + ((bank) * 0x10U)) /*!< CAN transmit mailbox data1 register */ + +/* CAN filter bank */ +#define CAN_FDATA0(canx, bank) REG32((canx) + 0x240U + ((bank) * 0x8U) + 0x0U) /*!< CAN filter data 0 register */ +#define CAN_FDATA1(canx, bank) REG32((canx) + 0x240U + ((bank) * 0x8U) + 0x4U) /*!< CAN filter data 1 register */ + +/* CAN receive FIFO mailbox bank */ +#define CAN_RFIFOMI(canx, bank) REG32((canx) + 0x1B0U + ((bank) * 0x10U)) /*!< CAN receive FIFO mailbox identifier register */ +#define CAN_RFIFOMP(canx, bank) REG32((canx) + 0x1B4U + ((bank) * 0x10U)) /*!< CAN receive FIFO mailbox property register */ +#define CAN_RFIFOMDATA0(canx, bank) REG32((canx) + 0x1B8U + ((bank) * 0x10U)) /*!< CAN receive FIFO mailbox data0 register */ +#define CAN_RFIFOMDATA1(canx, bank) REG32((canx) + 0x1BCU + ((bank) * 0x10U)) /*!< CAN receive FIFO mailbox data1 register */ + +/* bits definitions */ +/* CAN_CTL */ +#define CAN_CTL_IWMOD BIT(0) /*!< initial working mode */ +#define CAN_CTL_SLPWMOD BIT(1) /*!< sleep working mode */ +#define CAN_CTL_TFO BIT(2) /*!< transmit FIFO order */ +#define CAN_CTL_RFOD BIT(3) /*!< receive FIFO overwrite disable */ +#define CAN_CTL_ARD BIT(4) /*!< automatic retransmission disable */ +#define CAN_CTL_AWU BIT(5) /*!< automatic wakeup */ +#define CAN_CTL_ABOR BIT(6) /*!< automatic bus-off recovery */ +#define CAN_CTL_TTC BIT(7) /*!< time triggered communication */ +#define CAN_CTL_SWRST BIT(15) /*!< CAN software reset */ +#define CAN_CTL_DFZ BIT(16) /*!< CAN debug freeze */ + +/* CAN_STAT */ +#define CAN_STAT_IWS BIT(0) /*!< initial working state */ +#define CAN_STAT_SLPWS BIT(1) /*!< sleep working state */ +#define CAN_STAT_ERRIF BIT(2) /*!< error interrupt flag*/ +#define CAN_STAT_WUIF BIT(3) /*!< status change interrupt flag of wakeup from sleep working mode */ +#define CAN_STAT_SLPIF BIT(4) /*!< status change interrupt flag of sleep working mode entering */ +#define CAN_STAT_TS BIT(8) /*!< transmitting state */ +#define CAN_STAT_RS BIT(9) /*!< receiving state */ +#define CAN_STAT_LASTRX BIT(10) /*!< last sample value of rx pin */ +#define CAN_STAT_RXL BIT(11) /*!< CAN rx signal */ + +/* CAN_TSTAT */ +#define CAN_TSTAT_MTF0 BIT(0) /*!< mailbox0 transmit finished */ +#define CAN_TSTAT_MTFNERR0 BIT(1) /*!< mailbox0 transmit finished and no error */ +#define CAN_TSTAT_MAL0 BIT(2) /*!< mailbox0 arbitration lost */ +#define CAN_TSTAT_MTE0 BIT(3) /*!< mailbox0 transmit error */ +#define CAN_TSTAT_MST0 BIT(7) /*!< mailbox0 stop transmitting */ +#define CAN_TSTAT_MTF1 BIT(8) /*!< mailbox1 transmit finished */ +#define CAN_TSTAT_MTFNERR1 BIT(9) /*!< mailbox1 transmit finished and no error */ +#define CAN_TSTAT_MAL1 BIT(10) /*!< mailbox1 arbitration lost */ +#define CAN_TSTAT_MTE1 BIT(11) /*!< mailbox1 transmit error */ +#define CAN_TSTAT_MST1 BIT(15) /*!< mailbox1 stop transmitting */ +#define CAN_TSTAT_MTF2 BIT(16) /*!< mailbox2 transmit finished */ +#define CAN_TSTAT_MTFNERR2 BIT(17) /*!< mailbox2 transmit finished and no error */ +#define CAN_TSTAT_MAL2 BIT(18) /*!< mailbox2 arbitration lost */ +#define CAN_TSTAT_MTE2 BIT(19) /*!< mailbox2 transmit error */ +#define CAN_TSTAT_MST2 BIT(23) /*!< mailbox2 stop transmitting */ +#define CAN_TSTAT_NUM BITS(24,25) /*!< mailbox number */ +#define CAN_TSTAT_TME0 BIT(26) /*!< transmit mailbox0 empty */ +#define CAN_TSTAT_TME1 BIT(27) /*!< transmit mailbox1 empty */ +#define CAN_TSTAT_TME2 BIT(28) /*!< transmit mailbox2 empty */ +#define CAN_TSTAT_TMLS0 BIT(29) /*!< last sending priority flag for mailbox0 */ +#define CAN_TSTAT_TMLS1 BIT(30) /*!< last sending priority flag for mailbox1 */ +#define CAN_TSTAT_TMLS2 BIT(31) /*!< last sending priority flag for mailbox2 */ + +/* CAN_RFIFO0 */ +#define CAN_RFIFO0_RFL0 BITS(0,1) /*!< receive FIFO0 length */ +#define CAN_RFIFO0_RFF0 BIT(3) /*!< receive FIFO0 full */ +#define CAN_RFIFO0_RFO0 BIT(4) /*!< receive FIFO0 overfull */ +#define CAN_RFIFO0_RFD0 BIT(5) /*!< receive FIFO0 dequeue */ + +/* CAN_RFIFO1 */ +#define CAN_RFIFO1_RFL1 BITS(0,1) /*!< receive FIFO1 length */ +#define CAN_RFIFO1_RFF1 BIT(3) /*!< receive FIFO1 full */ +#define CAN_RFIFO1_RFO1 BIT(4) /*!< receive FIFO1 overfull */ +#define CAN_RFIFO1_RFD1 BIT(5) /*!< receive FIFO1 dequeue */ + +/* CAN_INTEN */ +#define CAN_INTEN_TMEIE BIT(0) /*!< transmit mailbox empty interrupt enable */ +#define CAN_INTEN_RFNEIE0 BIT(1) /*!< receive FIFO0 not empty interrupt enable */ +#define CAN_INTEN_RFFIE0 BIT(2) /*!< receive FIFO0 full interrupt enable */ +#define CAN_INTEN_RFOIE0 BIT(3) /*!< receive FIFO0 overfull interrupt enable */ +#define CAN_INTEN_RFNEIE1 BIT(4) /*!< receive FIFO1 not empty interrupt enable */ +#define CAN_INTEN_RFFIE1 BIT(5) /*!< receive FIFO1 full interrupt enable */ +#define CAN_INTEN_RFOIE1 BIT(6) /*!< receive FIFO1 overfull interrupt enable */ +#define CAN_INTEN_WERRIE BIT(8) /*!< warning error interrupt enable */ +#define CAN_INTEN_PERRIE BIT(9) /*!< passive error interrupt enable */ +#define CAN_INTEN_BOIE BIT(10) /*!< bus-off interrupt enable */ +#define CAN_INTEN_ERRNIE BIT(11) /*!< error number interrupt enable */ +#define CAN_INTEN_ERRIE BIT(15) /*!< error interrupt enable */ +#define CAN_INTEN_WIE BIT(16) /*!< wakeup interrupt enable */ +#define CAN_INTEN_SLPWIE BIT(17) /*!< sleep working interrupt enable */ + +/* CAN_ERR */ +#define CAN_ERR_WERR BIT(0) /*!< warning error */ +#define CAN_ERR_PERR BIT(1) /*!< passive error */ +#define CAN_ERR_BOERR BIT(2) /*!< bus-off error */ +#define CAN_ERR_ERRN BITS(4,6) /*!< error number */ +#define CAN_ERR_TECNT BITS(16,23) /*!< transmit error count */ +#define CAN_ERR_RECNT BITS(24,31) /*!< receive error count */ + +/* CAN_BT */ +#define CAN_BT_BAUDPSC BITS(0,9) /*!< baudrate prescaler */ +#define CAN_BT_BS1_6_4 BITS(10,12) /*!< bit segment 1 [6:4] */ +#define CAN_BT_BS2_4_3 BITS(13,14) /*!< bit segment 2 [4:3] */ +#define CAN_BT_BS1_3_0 BITS(16,19) /*!< bit segment 1 [3:0] */ +#define CAN_BT_BS2_2_0 BITS(20,22) /*!< bit segment 2 [2:0]*/ +#define CAN_BT_SJW BITS(24,28) /*!< resynchronization jump width */ +#define CAN_BT_LCMOD BIT(30) /*!< loopback communication mode */ +#define CAN_BT_SCMOD BIT(31) /*!< silent communication mode */ + +/* CAN_FDCTL */ +#define CAN_FDCTL_FDEN BIT(0) /*!< FD operation enable */ +#define CAN_FDCTL_PRED BIT(2) /*!< protocol exception event detection disable */ +#define CAN_FDCTL_NISO BIT(3) /*!< ISO/Bosch */ +#define CAN_FDCTL_TDCEN BIT(4) /*!< transmitter delay compensation enable */ +#define CAN_FDCTL_TDCMOD BIT(5) /*!< transmitter delay compensation mode */ +#define CAN_FDCTL_ESIMOD BIT(6) /*!< error state indicator mode */ + +/* CAN_FDSTAT */ +#define CAN_FDSTAT_TDCV BITS(0,6) /*!< transmitter delay compensation value */ +#define CAN_FDSTAT_PRE BIT(16) /*!< protocol exception event */ + +/* CAN_FDTDC */ +#define CAN_FDTDC_TDCF BITS(0,6) /*!< transmitter delay compensation filter */ +#define CAN_FDTDC_TDCO BITS(8,14) /*!< transmitter delay compensation offset */ + +/* CAN_DBT */ +#define CAN_DBT_DBAUDPSC BITS(0,9) /*!< baud rate prescaler */ +#define CAN_DBT_DBS1 BITS(16,19) /*!< bit segment 1 */ +#define CAN_DBT_DBS2 BITS(20,22) /*!< bit segment 2 */ +#define CAN_DBT_DSJW BITS(24,26) /*!< resynchronization jump width */ + +/* CAN_TMIx */ +#define CAN_TMI_TEN BIT(0) /*!< transmit enable */ +#define CAN_TMI_FT BIT(1) /*!< frame type */ +#define CAN_TMI_FF BIT(2) /*!< frame format */ +#define CAN_TMI_EFID BITS(3,31) /*!< the frame identifier */ +#define CAN_TMI_SFID BITS(21,31) /*!< the frame identifier */ + +/* CAN_TMPx */ +#define CAN_TMP_DLENC BITS(0,3) /*!< data length code */ +#define CAN_TMP_ESI BIT(4) /*!< error status indicator */ +#define CAN_TMP_BRS BIT(5) /*!< bit rate of data switch */ +#define CAN_TMP_FDF BIT(7) /*!< CAN FD frame flag */ +#define CAN_TMP_TSEN BIT(8) /*!< time stamp enable */ +#define CAN_TMP_TS BITS(16,31) /*!< time stamp */ + +/* CAN_TMDATA0x */ +#define CAN_TMDATA0_DB0 BITS(0,7) /*!< transmit data byte 0 */ +#define CAN_TMDATA0_DB1 BITS(8,15) /*!< transmit data byte 1 */ +#define CAN_TMDATA0_DB2 BITS(16,23) /*!< transmit data byte 2 */ +#define CAN_TMDATA0_DB3 BITS(24,31) /*!< transmit data byte 3 */ + +/* CAN_TMDATA1x */ +#define CAN_TMDATA1_DB4 BITS(0,7) /*!< transmit data byte 4 */ +#define CAN_TMDATA1_DB5 BITS(8,15) /*!< transmit data byte 5 */ +#define CAN_TMDATA1_DB6 BITS(16,23) /*!< transmit data byte 6 */ +#define CAN_TMDATA1_DB7 BITS(24,31) /*!< transmit data byte 7 */ + +/* CAN_RFIFOMIx */ +#define CAN_RFIFOMI_FT BIT(1) /*!< frame type */ +#define CAN_RFIFOMI_FF BIT(2) /*!< frame format */ +#define CAN_RFIFOMI_EFID BITS(3,31) /*!< the frame identifier */ +#define CAN_RFIFOMI_SFID BITS(21,31) /*!< the frame identifier */ + +/* CAN_RFIFOMPx */ +#define CAN_RFIFOMP_DLENC BITS(0,3) /*!< receive data length code */ +#define CAN_RFIFOMP_ESI BIT(4) /*!< error status indicator */ +#define CAN_RFIFOMP_BRS BIT(5) /*!< bit rate of data switch */ +#define CAN_RFIFOMP_FDF BIT(7) /*!< CAN FD frame flag */ +#define CAN_RFIFOMP_FI BITS(8,15) /*!< filter index */ +#define CAN_RFIFOMP_TS BITS(16,31) /*!< time stamp */ + +/* CAN_RFIFOMDATA0x */ +#define CAN_RFIFOMDATA0_DB0 BITS(0,7) /*!< receive data byte 0 */ +#define CAN_RFIFOMDATA0_DB1 BITS(8,15) /*!< receive data byte 1 */ +#define CAN_RFIFOMDATA0_DB2 BITS(16,23) /*!< receive data byte 2 */ +#define CAN_RFIFOMDATA0_DB3 BITS(24,31) /*!< receive data byte 3 */ + +/* CAN_RFIFOMDATA1x */ +#define CAN_RFIFOMDATA1_DB4 BITS(0,7) /*!< receive data byte 4 */ +#define CAN_RFIFOMDATA1_DB5 BITS(8,15) /*!< receive data byte 5 */ +#define CAN_RFIFOMDATA1_DB6 BITS(16,23) /*!< receive data byte 6 */ +#define CAN_RFIFOMDATA1_DB7 BITS(24,31) /*!< receive data byte 7 */ + +/* CAN_FCTL */ +#define CAN_FCTL_FLD BIT(0) /*!< filter lock disable */ +#define CAN_FCTL_HBC1F BITS(8,13) /*!< header bank of CAN1 filter */ + +/* CAN_FMCFG */ +#define CAN_FMCFG_FMOD(regval) BIT(regval) /*!< filter mode, list or mask */ + +/* CAN_FSCFG */ +#define CAN_FSCFG_FS(regval) BIT(regval) /*!< filter scale, 32 bits or 16 bits */ + +/* CAN_FAFIFO */ +#define CAN_FAFIFOR_FAF(regval) BIT(regval) /*!< filter associated with FIFO */ + +/* CAN_FW */ +#define CAN_FW_FW(regval) BIT(regval) /*!< filter working */ + +/* CAN_FxDATAy */ +#define CAN_FDATA_FD(regval) BIT(regval) /*!< filter data */ + +/* constants definitions */ +/* define the CAN bit position and its register index offset */ +#define CAN_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)) +#define CAN_REG_VAL(canx, offset) (REG32((canx) + ((uint32_t)(offset) >> 6))) +#define CAN_BIT_POS(val) ((uint32_t)(val) & 0x1FU) + +#define CAN_REGIDX_BITS(regidx, bitpos0, bitpos1) (((uint32_t)(regidx) << 12) | ((uint32_t)(bitpos0) << 6) | (uint32_t)(bitpos1)) +#define CAN_REG_VALS(canx, offset) (REG32((canx) + ((uint32_t)(offset) >> 12))) +#define CAN_BIT_POS0(val) (((uint32_t)(val) >> 6) & 0x1FU) +#define CAN_BIT_POS1(val) ((uint32_t)(val) & 0x1FU) + +/* register offset */ +#define STAT_REG_OFFSET ((uint8_t)0x04U) /*!< STAT register offset */ +#define TSTAT_REG_OFFSET ((uint8_t)0x08U) /*!< TSTAT register offset */ +#define RFIFO0_REG_OFFSET ((uint8_t)0x0CU) /*!< RFIFO0 register offset */ +#define RFIFO1_REG_OFFSET ((uint8_t)0x10U) /*!< RFIFO1 register offset */ +#define ERR_REG_OFFSET ((uint8_t)0x18U) /*!< ERR register offset */ + +/* CAN flags */ +typedef enum { + /* flags in STAT register */ + CAN_FLAG_RXL = CAN_REGIDX_BIT(STAT_REG_OFFSET, 11U), /*!< RX level */ + CAN_FLAG_LASTRX = CAN_REGIDX_BIT(STAT_REG_OFFSET, 10U), /*!< last sample value of RX pin */ + CAN_FLAG_RS = CAN_REGIDX_BIT(STAT_REG_OFFSET, 9U), /*!< receiving state */ + CAN_FLAG_TS = CAN_REGIDX_BIT(STAT_REG_OFFSET, 8U), /*!< transmitting state */ + CAN_FLAG_SLPIF = CAN_REGIDX_BIT(STAT_REG_OFFSET, 4U), /*!< status change flag of entering sleep working mode */ + CAN_FLAG_WUIF = CAN_REGIDX_BIT(STAT_REG_OFFSET, 3U), /*!< status change flag of wakeup from sleep working mode */ + CAN_FLAG_ERRIF = CAN_REGIDX_BIT(STAT_REG_OFFSET, 2U), /*!< error flag */ + CAN_FLAG_SLPWS = CAN_REGIDX_BIT(STAT_REG_OFFSET, 1U), /*!< sleep working state */ + CAN_FLAG_IWS = CAN_REGIDX_BIT(STAT_REG_OFFSET, 0U), /*!< initial working state */ + /* flags in TSTAT register */ + CAN_FLAG_TMLS2 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 31U), /*!< transmit mailbox 2 last sending in TX FIFO */ + CAN_FLAG_TMLS1 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 30U), /*!< transmit mailbox 1 last sending in TX FIFO */ + CAN_FLAG_TMLS0 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 29U), /*!< transmit mailbox 0 last sending in TX FIFO */ + CAN_FLAG_TME2 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 28U), /*!< transmit mailbox 2 empty */ + CAN_FLAG_TME1 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 27U), /*!< transmit mailbox 1 empty */ + CAN_FLAG_TME0 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 26U), /*!< transmit mailbox 0 empty */ + CAN_FLAG_MTE2 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 19U), /*!< mailbox 2 transmit error */ + CAN_FLAG_MTE1 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 11U), /*!< mailbox 1 transmit error */ + CAN_FLAG_MTE0 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 3U), /*!< mailbox 0 transmit error */ + CAN_FLAG_MAL2 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 18U), /*!< mailbox 2 arbitration lost */ + CAN_FLAG_MAL1 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 10U), /*!< mailbox 1 arbitration lost */ + CAN_FLAG_MAL0 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 2U), /*!< mailbox 0 arbitration lost */ + CAN_FLAG_MTFNERR2 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 17U), /*!< mailbox 2 transmit finished with no error */ + CAN_FLAG_MTFNERR1 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 9U), /*!< mailbox 1 transmit finished with no error */ + CAN_FLAG_MTFNERR0 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 1U), /*!< mailbox 0 transmit finished with no error */ + CAN_FLAG_MTF2 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 16U), /*!< mailbox 2 transmit finished */ + CAN_FLAG_MTF1 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 8U), /*!< mailbox 1 transmit finished */ + CAN_FLAG_MTF0 = CAN_REGIDX_BIT(TSTAT_REG_OFFSET, 0U), /*!< mailbox 0 transmit finished */ + /* flags in RFIFO0 register */ + CAN_FLAG_RFO0 = CAN_REGIDX_BIT(RFIFO0_REG_OFFSET, 4U), /*!< receive FIFO0 overfull */ + CAN_FLAG_RFF0 = CAN_REGIDX_BIT(RFIFO0_REG_OFFSET, 3U), /*!< receive FIFO0 full */ + /* flags in RFIFO1 register */ + CAN_FLAG_RFO1 = CAN_REGIDX_BIT(RFIFO1_REG_OFFSET, 4U), /*!< receive FIFO1 overfull */ + CAN_FLAG_RFF1 = CAN_REGIDX_BIT(RFIFO1_REG_OFFSET, 3U), /*!< receive FIFO1 full */ + /* flags in ERR register */ + CAN_FLAG_BOERR = CAN_REGIDX_BIT(ERR_REG_OFFSET, 2U), /*!< bus-off error */ + CAN_FLAG_PERR = CAN_REGIDX_BIT(ERR_REG_OFFSET, 1U), /*!< passive error */ + CAN_FLAG_WERR = CAN_REGIDX_BIT(ERR_REG_OFFSET, 0U), /*!< warning error */ +} can_flag_enum; + +/* CAN interrupt flags */ +typedef enum { + /* interrupt flags in STAT register */ + CAN_INT_FLAG_SLPIF = CAN_REGIDX_BITS(STAT_REG_OFFSET, 4U, 17U), /*!< status change interrupt flag of sleep working mode entering */ + CAN_INT_FLAG_WUIF = CAN_REGIDX_BITS(STAT_REG_OFFSET, 3U, 16), /*!< status change interrupt flag of wakeup from sleep working mode */ + CAN_INT_FLAG_ERRIF = CAN_REGIDX_BITS(STAT_REG_OFFSET, 2U, 15), /*!< error interrupt flag */ + /* interrupt flags in TSTAT register */ + CAN_INT_FLAG_MTF2 = CAN_REGIDX_BITS(TSTAT_REG_OFFSET, 16U, 0U), /*!< mailbox 2 transmit finished interrupt flag */ + CAN_INT_FLAG_MTF1 = CAN_REGIDX_BITS(TSTAT_REG_OFFSET, 8U, 0U), /*!< mailbox 1 transmit finished interrupt flag */ + CAN_INT_FLAG_MTF0 = CAN_REGIDX_BITS(TSTAT_REG_OFFSET, 0U, 0U), /*!< mailbox 0 transmit finished interrupt flag */ + /* interrupt flags in RFIFO0 register */ + CAN_INT_FLAG_RFO0 = CAN_REGIDX_BITS(RFIFO0_REG_OFFSET, 4U, 3U), /*!< receive FIFO0 overfull interrupt flag */ + CAN_INT_FLAG_RFF0 = CAN_REGIDX_BITS(RFIFO0_REG_OFFSET, 3U, 2U), /*!< receive FIFO0 full interrupt flag */ + CAN_INT_FLAG_RFL0 = CAN_REGIDX_BITS(RFIFO0_REG_OFFSET, 2U, 1U), /*!< receive FIFO0 not empty interrupt flag */ + /* interrupt flags in RFIFO0 register */ + CAN_INT_FLAG_RFO1 = CAN_REGIDX_BITS(RFIFO1_REG_OFFSET, 4U, 6U), /*!< receive FIFO1 overfull interrupt flag */ + CAN_INT_FLAG_RFF1 = CAN_REGIDX_BITS(RFIFO1_REG_OFFSET, 3U, 5U), /*!< receive FIFO1 full interrupt flag */ + CAN_INT_FLAG_RFL1 = CAN_REGIDX_BITS(RFIFO1_REG_OFFSET, 2U, 4U), /*!< receive FIFO1 not empty interrupt flag */ + /* interrupt flags in ERR register */ + CAN_INT_FLAG_ERRN = CAN_REGIDX_BITS(ERR_REG_OFFSET, 3U, 11U), /*!< error number interrupt flag */ + CAN_INT_FLAG_BOERR = CAN_REGIDX_BITS(ERR_REG_OFFSET, 2U, 10U), /*!< bus-off error interrupt flag */ + CAN_INT_FLAG_PERR = CAN_REGIDX_BITS(ERR_REG_OFFSET, 1U, 9U), /*!< passive error interrupt flag */ + CAN_INT_FLAG_WERR = CAN_REGIDX_BITS(ERR_REG_OFFSET, 0U, 8U), /*!< warning error interrupt flag */ +} can_interrupt_flag_enum; + +/* CAN FD transmitter delay compensation parameters struct */ +typedef struct { + uint32_t tdc_mode; /*!< transmitter delay compensation mode */ + uint8_t tdc_filter; /*!< transmitter delay compensation filter */ + uint8_t tdc_offset; /*!< transmitter delay compensation offset */ +} can_fd_tdc_struct; + +/* CAN initialize FD frame parameters struct */ +typedef struct { + ControlStatus fd_frame; /*!< FD operation function */ + ControlStatus excp_event_detect; /*!< protocol exception event detection function*/ + ControlStatus delay_compensation; /*!< transmitter delay compensation mode */ + can_fd_tdc_struct + *p_delay_compensation; /*!< pointer to the struct of the transmitter delay compensation */ + uint32_t iso_bosch; /*!< ISO/Bosch mode choice */ + uint32_t esi_mode; /*!< error state indicator mode */ + uint8_t data_resync_jump_width; /*!< CAN resynchronization jump width */ + uint8_t data_time_segment_1; /*!< time segment 1 */ + uint8_t data_time_segment_2; /*!< time segment 2 */ + uint16_t data_prescaler; /*!< baudrate prescaler */ +} can_fdframe_struct; + +/* CAN initialize parameters structure */ +typedef struct { + uint8_t working_mode; /*!< CAN working mode */ + uint8_t resync_jump_width; /*!< CAN resynchronization jump width */ + uint8_t time_segment_1; /*!< time segment 1 */ + uint8_t time_segment_2; /*!< time segment 2 */ + ControlStatus time_triggered; /*!< time triggered communication mode */ + ControlStatus auto_bus_off_recovery; /*!< automatic bus-off recovery */ + ControlStatus auto_wake_up; /*!< automatic wake-up mode */ + ControlStatus auto_retrans; /*!< automatic retransmission mode */ + ControlStatus rec_fifo_overwrite; /*!< receive FIFO overwrite mode */ + ControlStatus trans_fifo_order; /*!< transmit FIFO order */ + uint16_t prescaler; /*!< baudrate prescaler */ +} can_parameter_struct; + +/* CAN transmit message structure */ +typedef struct { + uint32_t tx_sfid; /*!< standard format frame identifier */ + uint32_t tx_efid; /*!< extended format frame identifier */ + uint8_t tx_ff; /*!< format of frame, standard or extended format */ + uint8_t tx_ft; /*!< type of frame, data or remote */ + uint8_t tx_dlen; /*!< data length */ + uint8_t tx_data[64]; /*!< transmit data */ + uint8_t fd_flag; /*!< CAN FD frame flag */ + uint8_t fd_brs; /*!< bit rate of data switch */ + uint8_t fd_esi; /*!< error status indicator */ +} can_trasnmit_message_struct; + +/* CAN receive message structure */ +typedef struct { + uint32_t rx_sfid; /*!< standard format frame identifier */ + uint32_t rx_efid; /*!< extended format frame identifier */ + uint8_t rx_ff; /*!< format of frame, standard or extended format */ + uint8_t rx_ft; /*!< type of frame, data or remote */ + uint8_t rx_dlen; /*!< data length */ + uint8_t rx_data[64]; /*!< receive data */ + uint8_t rx_fi; /*!< filtering index */ + uint8_t fd_flag; /*!< CAN FD frame flag */ + uint8_t fd_brs; /*!< bit rate of data switch */ + uint8_t fd_esi; /*!< error status indicator */ + +} can_receive_message_struct; + +/* CAN filter parameters structure */ +typedef struct { + uint16_t filter_list_high; /*!< filter list number high bits */ + uint16_t filter_list_low; /*!< filter list number low bits */ + uint16_t filter_mask_high; /*!< filter mask number high bits */ + uint16_t filter_mask_low; /*!< filter mask number low bits */ + uint16_t filter_fifo_number; /*!< receive FIFO associated with the filter */ + uint16_t filter_number; /*!< filter number */ + uint16_t filter_mode; /*!< filter mode, list or mask */ + uint16_t filter_bits; /*!< filter scale */ + ControlStatus filter_enable; /*!< filter work or not */ +} can_filter_parameter_struct; + +/* CAN errors */ +typedef enum { + CAN_ERROR_NONE = 0, /*!< no error */ + CAN_ERROR_FILL, /*!< fill error */ + CAN_ERROR_FORMATE, /*!< format error */ + CAN_ERROR_ACK, /*!< ACK error */ + CAN_ERROR_BITRECESSIVE, /*!< bit recessive error */ + CAN_ERROR_BITDOMINANTER, /*!< bit dominant error */ + CAN_ERROR_CRC, /*!< CRC error */ + CAN_ERROR_SOFTWARECFG, /*!< software configure */ +} can_error_enum; + +/* transmit states */ +typedef enum { + CAN_TRANSMIT_FAILED = 0U, /*!< CAN transmitted failure */ + CAN_TRANSMIT_OK = 1U, /*!< CAN transmitted success */ + CAN_TRANSMIT_PENDING = 2U, /*!< CAN transmitted pending */ + CAN_TRANSMIT_NOMAILBOX = 4U, /*!< no empty mailbox to be used for CAN */ +} can_transmit_state_enum; + +/* format and fifo states */ +typedef enum { + CAN_STANDARD_FIFO0 = 0U, /*!< standard frame and used FIFO0 */ + CAN_STANDARD_FIFO1, /*!< standard frame and used FIFO1 */ + CAN_EXTENDED_FIFO0, /*!< extended frame and used FIFO0 */ + CAN_EXTENDED_FIFO1, /*!< extended frame and used FIFO1 */ +} can_format_fifo_enum; + +typedef enum { + CAN_INIT_STRUCT = 0U, /* CAN initiliaze parameters struct */ + CAN_FILTER_STRUCT, /* CAN filter parameters struct */ + CAN_FD_FRAME_STRUCT, /* CAN initiliaze FD frame parameters struct */ + CAN_TX_MESSAGE_STRUCT, /* CAN transmit message struct */ + CAN_RX_MESSAGE_STRUCT, /* CAN receive message struct */ +} can_struct_type_enum; + +/* CAN baudrate prescaler */ +#define BT_BAUDPSC(regval) (BITS(0,9) & ((uint32_t)(regval) << 0)) + +/* CAN bit segment 1*/ +#define BT_BS1(regval) ((BITS(16,19) & ((uint32_t)(regval) << 16)) | (BITS(10,12) & ((uint32_t)(regval) << 6))) +#define BT_DBS1(regval) ((BITS(16,19) & ((uint32_t)(regval) << 16))) + +/* CAN bit segment 2*/ +#define BT_BS2(regval) ((BITS(20,22) & ((uint32_t)(regval) << 20)) | (BITS(13,14) & ((uint32_t)(regval) << 10))) +#define BT_DBS2(regval) ((BITS(20,22)) & ((uint32_t)(regval) << 20)) + +/* CAN resynchronization jump width*/ +#define BT_SJW(regval) (BITS(24,28) & ((uint32_t)(regval) << 24)) +#define BT_DSJW(regval) (BITS(24,26) & ((uint32_t)(regval) << 24)) + +#define FDTDC_TDCF(regval) (BITS(0,6) & ((uint32_t)(regval) << 0)) +#define FDTDC_TDCO(regval) (BITS(8,14) & ((uint32_t)(regval) << 8)) + +/* CAN communication mode*/ +#define BT_MODE(regval) (BITS(30,31) & ((uint32_t)(regval) << 30)) + +/* CAN FDATA high 16 bits */ +#define FDATA_MASK_HIGH(regval) (BITS(16,31) & ((uint32_t)(regval) << 16)) + +/* CAN FDATA low 16 bits */ +#define FDATA_MASK_LOW(regval) (BITS(0,15) & ((uint32_t)(regval) << 0)) + +/* CAN1 filter start bank_number */ +#define FCTL_HBC1F(regval) (BITS(8,13) & ((uint32_t)(regval) << 8)) + +/* CAN transmit mailbox extended identifier */ +#define TMI_EFID(regval) (BITS(3,31) & ((uint32_t)(regval) << 3)) + +/* CAN transmit mailbox standard identifier */ +#define TMI_SFID(regval) (BITS(21,31) & ((uint32_t)(regval) << 21)) + +/* transmit data byte 0 */ +#define TMDATA0_DB0(regval) (BITS(0,7) & ((uint32_t)(regval) << 0)) + +/* transmit data byte 1 */ +#define TMDATA0_DB1(regval) (BITS(8,15) & ((uint32_t)(regval) << 8)) + +/* transmit data byte 2 */ +#define TMDATA0_DB2(regval) (BITS(16,23) & ((uint32_t)(regval) << 16)) + +/* transmit data byte 3 */ +#define TMDATA0_DB3(regval) (BITS(24,31) & ((uint32_t)(regval) << 24)) + +/* transmit data byte 4 */ +#define TMDATA1_DB4(regval) (BITS(0,7) & ((uint32_t)(regval) << 0)) + +/* transmit data byte 5 */ +#define TMDATA1_DB5(regval) (BITS(8,15) & ((uint32_t)(regval) << 8)) + +/* transmit data byte 6 */ +#define TMDATA1_DB6(regval) (BITS(16,23) & ((uint32_t)(regval) << 16)) + +/* transmit data byte 7 */ +#define TMDATA1_DB7(regval) (BITS(24,31) & ((uint32_t)(regval) << 24)) + +/* receive mailbox extended identifier */ +#define GET_RFIFOMI_EFID(regval) GET_BITS((uint32_t)(regval), 3U, 31U) + +/* receive mailbox standard identifier */ +#define GET_RFIFOMI_SFID(regval) GET_BITS((uint32_t)(regval), 21U, 31U) + +/* receive data length */ +#define GET_RFIFOMP_DLENC(regval) GET_BITS((uint32_t)(regval), 0U, 3U) + +/* the index of the filter by which the frame is passed */ +#define GET_RFIFOMP_FI(regval) GET_BITS((uint32_t)(regval), 8U, 15U) + +/* receive data byte 0 */ +#define GET_RFIFOMDATA0_DB0(regval) GET_BITS((uint32_t)(regval), 0U, 7U) + +/* receive data byte 1 */ +#define GET_RFIFOMDATA0_DB1(regval) GET_BITS((uint32_t)(regval), 8U, 15U) + +/* receive data byte 2 */ +#define GET_RFIFOMDATA0_DB2(regval) GET_BITS((uint32_t)(regval), 16U, 23U) + +/* receive data byte 3 */ +#define GET_RFIFOMDATA0_DB3(regval) GET_BITS((uint32_t)(regval), 24U, 31U) + +/* receive data byte 4 */ +#define GET_RFIFOMDATA1_DB4(regval) GET_BITS((uint32_t)(regval), 0U, 7U) + +/* receive data byte 5 */ +#define GET_RFIFOMDATA1_DB5(regval) GET_BITS((uint32_t)(regval), 8U, 15U) + +/* receive data byte 6 */ +#define GET_RFIFOMDATA1_DB6(regval) GET_BITS((uint32_t)(regval), 16U, 23U) + +/* receive data byte 7 */ +#define GET_RFIFOMDATA1_DB7(regval) GET_BITS((uint32_t)(regval), 24U, 31U) + +/* error number */ +#define GET_ERR_ERRN(regval) GET_BITS((uint32_t)(regval), 4U, 6U) + +/* transmit error count */ +#define GET_ERR_TECNT(regval) GET_BITS((uint32_t)(regval), 16U, 23U) + +/* receive error count */ +#define GET_ERR_RECNT(regval) GET_BITS((uint32_t)(regval), 24U, 31U) + +/* CAN errors */ +#define ERR_ERRN(regval) (BITS(4,6) & ((uint32_t)(regval) << 4)) +#define CAN_ERRN_0 ERR_ERRN(0U) /*!< no error */ +#define CAN_ERRN_1 ERR_ERRN(1U) /*!< fill error */ +#define CAN_ERRN_2 ERR_ERRN(2U) /*!< format error */ +#define CAN_ERRN_3 ERR_ERRN(3U) /*!< ACK error */ +#define CAN_ERRN_4 ERR_ERRN(4U) /*!< bit recessive error */ +#define CAN_ERRN_5 ERR_ERRN(5U) /*!< bit dominant error */ +#define CAN_ERRN_6 ERR_ERRN(6U) /*!< CRC error */ +#define CAN_ERRN_7 ERR_ERRN(7U) /*!< software error */ + +#define CAN_STATE_PENDING ((uint32_t)0x00000000U) /*!< CAN pending */ + +/* CAN communication mode */ +#define CAN_NORMAL_MODE ((uint8_t)0x00U) /*!< normal communication mode */ +#define CAN_LOOPBACK_MODE ((uint8_t)0x01U) /*!< loopback communication mode */ +#define CAN_SILENT_MODE ((uint8_t)0x02U) /*!< silent communication mode */ +#define CAN_SILENT_LOOPBACK_MODE ((uint8_t)0x03U) /*!< loopback and silent communication mode */ + +/* CAN resynchronisation jump width */ +#define CAN_BT_SJW_1TQ ((uint8_t)0x00U) /*!< 1 time quanta */ +#define CAN_BT_SJW_2TQ ((uint8_t)0x01U) /*!< 2 time quanta */ +#define CAN_BT_SJW_3TQ ((uint8_t)0x02U) /*!< 3 time quanta */ +#define CAN_BT_SJW_4TQ ((uint8_t)0x03U) /*!< 4 time quanta */ + +/* CAN time segment 1 */ +#define CAN_BT_BS1_1TQ ((uint8_t)0x00U) /*!< 1 time quanta */ +#define CAN_BT_BS1_2TQ ((uint8_t)0x01U) /*!< 2 time quanta */ +#define CAN_BT_BS1_3TQ ((uint8_t)0x02U) /*!< 3 time quanta */ +#define CAN_BT_BS1_4TQ ((uint8_t)0x03U) /*!< 4 time quanta */ +#define CAN_BT_BS1_5TQ ((uint8_t)0x04U) /*!< 5 time quanta */ +#define CAN_BT_BS1_6TQ ((uint8_t)0x05U) /*!< 6 time quanta */ +#define CAN_BT_BS1_7TQ ((uint8_t)0x06U) /*!< 7 time quanta */ +#define CAN_BT_BS1_8TQ ((uint8_t)0x07U) /*!< 8 time quanta */ +#define CAN_BT_BS1_9TQ ((uint8_t)0x08U) /*!< 9 time quanta */ +#define CAN_BT_BS1_10TQ ((uint8_t)0x09U) /*!< 10 time quanta */ +#define CAN_BT_BS1_11TQ ((uint8_t)0x0AU) /*!< 11 time quanta */ +#define CAN_BT_BS1_12TQ ((uint8_t)0x0BU) /*!< 12 time quanta */ +#define CAN_BT_BS1_13TQ ((uint8_t)0x0CU) /*!< 13 time quanta */ +#define CAN_BT_BS1_14TQ ((uint8_t)0x0DU) /*!< 14 time quanta */ +#define CAN_BT_BS1_15TQ ((uint8_t)0x0EU) /*!< 15 time quanta */ +#define CAN_BT_BS1_16TQ ((uint8_t)0x0FU) /*!< 16 time quanta */ + +/* CAN time segment 2 */ +#define CAN_BT_BS2_1TQ ((uint8_t)0x00U) /*!< 1 time quanta */ +#define CAN_BT_BS2_2TQ ((uint8_t)0x01U) /*!< 2 time quanta */ +#define CAN_BT_BS2_3TQ ((uint8_t)0x02U) /*!< 3 time quanta */ +#define CAN_BT_BS2_4TQ ((uint8_t)0x03U) /*!< 4 time quanta */ +#define CAN_BT_BS2_5TQ ((uint8_t)0x04U) /*!< 5 time quanta */ +#define CAN_BT_BS2_6TQ ((uint8_t)0x05U) /*!< 6 time quanta */ +#define CAN_BT_BS2_7TQ ((uint8_t)0x06U) /*!< 7 time quanta */ +#define CAN_BT_BS2_8TQ ((uint8_t)0x07U) /*!< 8 time quanta */ +#define CAN_BT_BS2_9TQ ((uint8_t)0x08U) /*!< 9 time quanta */ +#define CAN_BT_BS2_10TQ ((uint8_t)0x09U) /*!< 10 time quanta */ +#define CAN_BT_BS2_11TQ ((uint8_t)0x0AU) /*!< 11 time quanta */ +#define CAN_BT_BS2_12TQ ((uint8_t)0x0BU) /*!< 12 time quanta */ +#define CAN_BT_BS2_13TQ ((uint8_t)0x0CU) /*!< 13 time quanta */ +#define CAN_BT_BS2_14TQ ((uint8_t)0x0DU) /*!< 14 time quanta */ +#define CAN_BT_BS2_15TQ ((uint8_t)0x0EU) /*!< 15 time quanta */ +#define CAN_BT_BS2_16TQ ((uint8_t)0x0FU) /*!< 16 time quanta */ +#define CAN_BT_BS2_17TQ ((uint8_t)0x10U) /*!< 17 time quanta */ +#define CAN_BT_BS2_18TQ ((uint8_t)0x11U) /*!< 18 time quanta */ +#define CAN_BT_BS2_19TQ ((uint8_t)0x12U) /*!< 19 time quanta */ +#define CAN_BT_BS2_20TQ ((uint8_t)0x13U) /*!< 20 time quanta */ +#define CAN_BT_BS2_21TQ ((uint8_t)0x14U) /*!< 21 time quanta */ +#define CAN_BT_BS2_22TQ ((uint8_t)0x15U) /*!< 22 time quanta */ +#define CAN_BT_BS2_23TQ ((uint8_t)0x16U) /*!< 23 time quanta */ +#define CAN_BT_BS2_24TQ ((uint8_t)0x17U) /*!< 24 time quanta */ +#define CAN_BT_BS2_25TQ ((uint8_t)0x18U) /*!< 25 time quanta */ +#define CAN_BT_BS2_26TQ ((uint8_t)0x19U) /*!< 26 time quanta */ +#define CAN_BT_BS2_27TQ ((uint8_t)0x1AU) /*!< 27 time quanta */ +#define CAN_BT_BS2_28TQ ((uint8_t)0x1BU) /*!< 28 time quanta */ +#define CAN_BT_BS2_29TQ ((uint8_t)0x1CU) /*!< 29 time quanta */ +#define CAN_BT_BS2_30TQ ((uint8_t)0x1DU) /*!< 30 time quanta */ +#define CAN_BT_BS2_31TQ ((uint8_t)0x1EU) /*!< 31 time quanta */ +#define CAN_BT_BS2_32TQ ((uint8_t)0x1FU) /*!< 32 time quanta */ + +/* CAN resynchronisation jump width */ +#define CAN_DBT_SWJ_1TQ ((uint8_t)0x00U) /*!< 1 time quanta */ +#define CAN_DBT_SWJ_2TQ ((uint8_t)0x01U) /*!< 2 time quanta */ +#define CAN_DBT_SWJ_3TQ ((uint8_t)0x02U) /*!< 3 time quanta */ +#define CAN_DBT_SWJ_4TQ ((uint8_t)0x03U) /*!< 4 time quanta */ +#define CAN_DBT_SWJ_5TQ ((uint8_t)0x04U) /*!< 5 time quanta */ +#define CAN_DBT_SWJ_6TQ ((uint8_t)0x05U) /*!< 6 time quanta */ +#define CAN_DBT_SWJ_7TQ ((uint8_t)0x06U) /*!< 7 time quanta */ +#define CAN_DBT_SWJ_8TQ ((uint8_t)0x07U) /*!< 8 time quanta */ + +/* CAN mailbox number */ +#define CAN_MAILBOX0 ((uint8_t)0x00U) /*!< mailbox0 */ +#define CAN_MAILBOX1 ((uint8_t)0x01U) /*!< mailbox1 */ +#define CAN_MAILBOX2 ((uint8_t)0x02U) /*!< mailbox2 */ +#define CAN_NOMAILBOX ((uint8_t)0x03U) /*!< no mailbox empty */ + +/* CAN frame format */ +#define CAN_FF_STANDARD ((uint32_t)0x00000000U) /*!< standard frame */ +#define CAN_FF_EXTENDED ((uint32_t)0x00000004U) /*!< extended frame */ + +/* CAN receive FIFO */ +#define CAN_FIFO0 ((uint8_t)0x00U) /*!< receive FIFO0 */ +#define CAN_FIFO1 ((uint8_t)0x01U) /*!< receive FIFO1 */ + +/* frame number of receive FIFO */ +#define CAN_RFIF_RFL_MASK ((uint32_t)0x00000003U) /*!< mask for frame number in receive FIFOx */ + +#define CAN_SFID_MASK ((uint32_t)0x000007FFU) /*!< mask of standard identifier */ +#define CAN_EFID_MASK ((uint32_t)0x1FFFFFFFU) /*!< mask of extended identifier */ + +/* CAN working mode */ +#define CAN_MODE_INITIALIZE ((uint8_t)0x01U) /*!< CAN initialize mode */ +#define CAN_MODE_NORMAL ((uint8_t)0x02U) /*!< CAN normal mode */ +#define CAN_MODE_SLEEP ((uint8_t)0x04U) /*!< CAN sleep mode */ + +/* filter bits */ +#define CAN_FILTERBITS_16BIT ((uint8_t)0x00U) /*!< CAN filter 16 bits */ +#define CAN_FILTERBITS_32BIT ((uint8_t)0x01U) /*!< CAN filter 32 bits */ + +/* filter mode */ +#define CAN_FILTERMODE_MASK ((uint8_t)0x00U) /*!< mask mode */ +#define CAN_FILTERMODE_LIST ((uint8_t)0x01U) /*!< list mode */ + +/* filter 16 bits mask */ +#define CAN_FILTER_MASK_16BITS ((uint32_t)0x0000FFFFU) /*!< can filter 16 bits mask */ + +/* frame type */ +#define CAN_FT_DATA ((uint32_t)0x00000000U) /*!< data frame */ +#define CAN_FT_REMOTE ((uint32_t)0x00000002U) /*!< remote frame */ + +#define CAN_ESIMOD_HARDWARE ((uint32_t)0x00000000U) /*!< displays the node error state by hardware */ +#define CAN_ESIMOD_SOFTWARE CAN_FDCTL_ESIMOD /*!< displays the node error state by software */ + +#define CAN_TDCMOD_CALC_AND_OFFSET ((uint32_t)0x00000000U) /*!< measurement and offset */ +#define CAN_TDCMOD_OFFSET CAN_FDCTL_TDCMOD /*!< only offset */ + +#define CAN_FDMOD_ISO ((uint32_t)0x00000000U) /*!< ISO mode */ +#define CAN_FDMOD_BOSCH CAN_FDCTL_NISO /*!< BOSCH mode */ + +/* CAN FD frame flag */ +#define CAN_FDF_CLASSIC (0U) /*!< classical frames */ +#define CAN_FDF_FDFRAME (1U) /*!< FD frames */ + +/* bit rate of data switch */ +#define CAN_BRS_DISABLE (0U) /*!< bit rate not switch */ +#define CAN_BRS_ENABLE (1U) /*!< the bit rate shall be switched */ + +/* error status indicator */ +#define CAN_ESI_DOMINANT (0U) /*!< transmit the dominant bit in ESI phase */ +#define CAN_ESI_RECESSIVE (1U) /*!< transmit the recessive bit in ESI phase */ + +/* CAN timeout */ +#define CAN_TIMEOUT ((uint32_t)0x0000FFFFU) /*!< timeout value */ + +/* interrupt enable bits */ +#define CAN_INT_TME CAN_INTEN_TMEIE /*!< transmit mailbox empty interrupt enable */ +#define CAN_INT_RFNE0 CAN_INTEN_RFNEIE0 /*!< receive FIFO0 not empty interrupt enable */ +#define CAN_INT_RFF0 CAN_INTEN_RFFIE0 /*!< receive FIFO0 full interrupt enable */ +#define CAN_INT_RFO0 CAN_INTEN_RFOIE0 /*!< receive FIFO0 overfull interrupt enable */ +#define CAN_INT_RFNE1 CAN_INTEN_RFNEIE1 /*!< receive FIFO1 not empty interrupt enable */ +#define CAN_INT_RFF1 CAN_INTEN_RFFIE1 /*!< receive FIFO1 full interrupt enable */ +#define CAN_INT_RFO1 CAN_INTEN_RFOIE1 /*!< receive FIFO1 overfull interrupt enable */ +#define CAN_INT_WERR CAN_INTEN_WERRIE /*!< warning error interrupt enable */ +#define CAN_INT_PERR CAN_INTEN_PERRIE /*!< passive error interrupt enable */ +#define CAN_INT_BO CAN_INTEN_BOIE /*!< bus-off interrupt enable */ +#define CAN_INT_ERRN CAN_INTEN_ERRNIE /*!< error number interrupt enable */ +#define CAN_INT_ERR CAN_INTEN_ERRIE /*!< error interrupt enable */ +#define CAN_INT_WAKEUP CAN_INTEN_WIE /*!< wakeup interrupt enable */ +#define CAN_INT_SLPW CAN_INTEN_SLPWIE /*!< sleep working interrupt enable */ + +/* function declarations */ +/* initialization functions */ +/* deinitialize CAN */ +void can_deinit(uint32_t can_periph); +/* initialize CAN structure */ +void can_struct_para_init(can_struct_type_enum type, void *p_struct); +/* initialize CAN */ +ErrStatus can_init(uint32_t can_periph, can_parameter_struct *can_parameter_init); +/* initialize CAN FD function */ +ErrStatus can_fd_init(uint32_t can_periph, can_fdframe_struct *can_fdframe_init); +/* CAN filter init */ +void can_filter_init(can_filter_parameter_struct *can_filter_parameter_init); +/* CAN filter mask mode initialization */ +void can_filter_mask_mode_init(uint32_t id, uint32_t mask, can_format_fifo_enum format_fifo, uint16_t filter_number); +/* CAN communication mode configure */ +ErrStatus can_monitor_mode_set(uint32_t can_periph, uint8_t mode); +/* CAN FD frame function enable */ +void can_fd_function_enable(uint32_t can_periph); +/* CAN FD frame function disable */ +void can_fd_function_disable(uint32_t can_periph); + +/* set can1 filter start bank number */ +void can1_filter_start_bank(uint8_t start_bank); +/* enable functions */ +/* CAN debug freeze enable */ +void can_debug_freeze_enable(uint32_t can_periph); +/* CAN debug freeze disable */ +void can_debug_freeze_disable(uint32_t can_periph); +/* CAN time trigger mode enable */ +void can_time_trigger_mode_enable(uint32_t can_periph); +/* CAN time trigger mode disable */ +void can_time_trigger_mode_disable(uint32_t can_periph); + +/* transmit functions */ +/* transmit CAN message */ +uint8_t can_message_transmit(uint32_t can_periph, can_trasnmit_message_struct *transmit_message); +/* get CAN transmit state */ +can_transmit_state_enum can_transmit_states(uint32_t can_periph, uint8_t mailbox_number); +/* stop CAN transmission */ +void can_transmission_stop(uint32_t can_periph, uint8_t mailbox_number); +/* CAN receive message */ +void can_message_receive(uint32_t can_periph, uint8_t fifo_number, can_receive_message_struct *receive_message); +/* CAN release FIFO */ +void can_fifo_release(uint32_t can_periph, uint8_t fifo_number); +/* CAN receive message length */ +uint8_t can_receive_message_length_get(uint32_t can_periph, uint8_t fifo_number); +/* CAN working mode */ +ErrStatus can_working_mode_set(uint32_t can_periph, uint8_t working_mode); +/* CAN wakeup from sleep mode */ +ErrStatus can_wakeup(uint32_t can_periph); + +/* CAN get error type */ +can_error_enum can_error_get(uint32_t can_periph); +/* get CAN receive error number */ +uint8_t can_receive_error_number_get(uint32_t can_periph); +/* get CAN transmit error number */ +uint8_t can_transmit_error_number_get(uint32_t can_periph); + +/* interrupt & flag functions */ +/* CAN get flag state */ +FlagStatus can_flag_get(uint32_t can_periph, can_flag_enum flag); +/* CAN clear flag state */ +void can_flag_clear(uint32_t can_periph, can_flag_enum flag); +/* CAN interrupt enable */ +void can_interrupt_enable(uint32_t can_periph, uint32_t interrupt); +/* CAN interrupt disable */ +void can_interrupt_disable(uint32_t can_periph, uint32_t interrupt); +/* CAN get interrupt flag state */ +FlagStatus can_interrupt_flag_get(uint32_t can_periph, can_interrupt_flag_enum flag); +/* CAN clear interrupt flag state */ +void can_interrupt_flag_clear(uint32_t can_periph, can_interrupt_flag_enum flag); + +#endif /* GD32F5XX_CAN_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_cau.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_cau.h new file mode 100644 index 0000000..eaa1f01 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_cau.h @@ -0,0 +1,317 @@ +/*! + \file gd32f5xx_cau.h + \brief definitions for the CAU + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_CAU_H +#define GD32F5XX_CAU_H + +#include "gd32f5xx.h" + + +/* CAU definitions */ +#define CAU CAU_BASE /*!< CAU base address */ + +/* registers definitions */ +#define CAU_CTL REG32(CAU + 0x00000000U) /*!< control register */ +#define CAU_STAT0 REG32(CAU + 0x00000004U) /*!< status register 0 */ +#define CAU_DI REG32(CAU + 0x00000008U) /*!< data input register */ +#define CAU_DO REG32(CAU + 0x0000000CU) /*!< data output register */ +#define CAU_DMAEN REG32(CAU + 0x00000010U) /*!< DMA enable register */ +#define CAU_INTEN REG32(CAU + 0x00000014U) /*!< interrupt enable register */ +#define CAU_STAT1 REG32(CAU + 0x00000018U) /*!< status register 1 */ +#define CAU_INTF REG32(CAU + 0x0000001CU) /*!< interrupt flag register */ +#define CAU_KEY0H REG32(CAU + 0x00000020U) /*!< key 0 high register */ +#define CAU_KEY0L REG32(CAU + 0x00000024U) /*!< key 0 low register */ +#define CAU_KEY1H REG32(CAU + 0x00000028U) /*!< key 1 high register */ +#define CAU_KEY1L REG32(CAU + 0x0000002CU) /*!< key 1 low register */ +#define CAU_KEY2H REG32(CAU + 0x00000030U) /*!< key 2 high register */ +#define CAU_KEY2L REG32(CAU + 0x00000034U) /*!< key 2 low register */ +#define CAU_KEY3H REG32(CAU + 0x00000038U) /*!< key 3 high register */ +#define CAU_KEY3L REG32(CAU + 0x0000003CU) /*!< key 3 low register */ +#define CAU_IV0H REG32(CAU + 0x00000040U) /*!< initial vector 0 high register */ +#define CAU_IV0L REG32(CAU + 0x00000044U) /*!< initial vector 0 low register */ +#define CAU_IV1H REG32(CAU + 0x00000048U) /*!< initial vector 1 high register */ +#define CAU_IV1L REG32(CAU + 0x0000004CU) /*!< initial vector 1 low register */ +#define CAU_GCMCCMCTXSx(x) REG32(CAU + 0x00000050U + (uint32_t)(4U * (x))) /*!< GCM or CCM mode context switch register, x = 0...7 */ +#define CAU_GCMCTXSx(x) REG32(CAU + 0x00000070U + (uint32_t)(4U * (x))) /*!< GCM mode context switch register, x = 0...7 */ + +/* bits definitions */ +/* CAU_CTL */ +#define CAU_CTL_CAUDIR BIT(2) /*!< algorithm direction */ +#define CAU_CTL_ALGM (BITS(3,5) | BIT(19)) /*!< cryptographic algorithm mode */ +#define CAU_CTL_DATAM BITS(6,7) /*!< data swapping selection */ +#define CAU_CTL_KEYM BITS(8,9) /*!< key length selection when aes mode */ +#define CAU_CTL_FFLUSH BIT(14) /*!< FIFO flush */ +#define CAU_CTL_CAUEN BIT(15) /*!< cryptographic module enable */ +#define CAU_CTL_GCM_CCMPH BITS(16,17) /*!< GCM CCM phase */ +#define CAU_CTL_NBPILB BITS(20,23) /*!< number of bytes padding in last block */ + +/* CAU_STAT0 */ +#define CAU_STAT0_IEM BIT(0) /*!< IN FIFO empty flag */ +#define CAU_STAT0_INF BIT(1) /*!< IN FIFO not full flag */ +#define CAU_STAT0_ONE BIT(2) /*!< OUT FIFO not empty flag */ +#define CAU_STAT0_OFU BIT(3) /*!< OUT FIFO full flag */ +#define CAU_STAT0_BUSY BIT(4) /*!< busy flag */ + +/* CAU_DI */ +#define CAU_DI_DI BITS(0,31) /*!< data input */ + +/* CAU_DO */ +#define CAU_DO_DO BITS(0,31) /*!< data output */ + +/* CAU_DMAEN */ +#define CAU_DMAEN_DMAIEN BIT(0) /*!< IN FIFO DMA enable */ +#define CAU_DMAEN_DMAOEN BIT(1) /*!< OUT FIFO DMA enable */ + +/* CAU_INTEN */ +#define CAU_INTEN_IINTEN BIT(0) /*!< IN FIFO interrupt enable */ +#define CAU_INTEN_OINTEN BIT(1) /*!< OUT FIFO interrupt enable */ + +/* CAU_STAT1 */ +#define CAU_STAT1_ISTA BIT(0) /*!< flag set when there is less than 4 words in IN FIFO */ +#define CAU_STAT1_OSTA BIT(1) /*!< flag set when there is one or more word in OUT FIFO */ + +/* CAU_INTF */ +#define CAU_INTF_IINTF BIT(0) /*!< IN FIFO interrupt flag */ +#define CAU_INTF_OINTF BIT(1) /*!< OUT FIFO interrupt flag */ + +/* CAU_KEYxH x=0..3 */ +#define CAU_KEYXH_KEYXH BITS(0,31) /*!< the key for des, tdes, aes */ + +/* CAU_KEYxL x=0..3 */ +#define CAU_KEYXL_KEYXL BITS(0,31) /*!< the key for des, tdes, aes */ + +/* CAU_IVxH x=0..1 */ +#define CAU_IVXH_IVXH BITS(0,31) /*!< the initialization vector for des, tdes, aes */ + +/* CAU_IVxL x=0..1 */ +#define CAU_IVXL_IVXL BITS(0,31) /*!< the initialization vector for des, tdes, aes */ + +/* constants definitions */ +/* structure for keys initialization of the cau */ +typedef struct { + uint32_t key_0_high; /*!< key 0 high */ + uint32_t key_0_low; /*!< key 0 low */ + uint32_t key_1_high; /*!< key 1 high */ + uint32_t key_1_low; /*!< key 1 low */ + uint32_t key_2_high; /*!< key 2 high */ + uint32_t key_2_low; /*!< key 2 low */ + uint32_t key_3_high; /*!< key 3 high */ + uint32_t key_3_low; /*!< key 3 low */ +} cau_key_parameter_struct; + +/* structure for vectors initialization of the cau */ +typedef struct { + uint32_t iv_0_high; /*!< init vector 0 high */ + uint32_t iv_0_low; /*!< init vector 0 low */ + uint32_t iv_1_high; /*!< init vector 1 high */ + uint32_t iv_1_low; /*!< init vector 1 low */ +} cau_iv_parameter_struct; + +/* structure for cau context swapping */ +typedef struct { + uint32_t ctl_config; /*!< current configuration */ + uint32_t iv_0_high; /*!< init vector 0 high */ + uint32_t iv_0_low; /*!< init vector 0 low */ + uint32_t iv_1_high; /*!< init vector 1 high */ + uint32_t iv_1_low; /*!< init vector 1 low */ + uint32_t key_0_high; /*!< key 0 high */ + uint32_t key_0_low; /*!< key 0 low */ + uint32_t key_1_high; /*!< key 1 high */ + uint32_t key_1_low; /*!< key 1 low */ + uint32_t key_2_high; /*!< key 2 high */ + uint32_t key_2_low; /*!< key 2 low */ + uint32_t key_3_high; /*!< key 3 high */ + uint32_t key_3_low; /*!< key 3 low */ + uint32_t gcmccmctxs[8]; /*!< GCM or CCM mode context switch */ + uint32_t gcmctxs[8]; /*!< GCM mode context switch */ +} cau_context_parameter_struct; + +/* structure for encrypt and decrypt parameters */ +typedef struct { + uint32_t alg_dir; /*!< algorithm direction */ + uint8_t *key; /*!< key */ + uint32_t key_size; /*!< key size in bytes */ + uint8_t *iv; /*!< initialization vector */ + uint32_t iv_size; /*!< iv size in bytes */ + uint8_t *input; /*!< input data */ + uint32_t in_length; /*!< input data length in bytes */ + uint8_t *aad; /*!< additional authentication data */ + uint32_t aad_size; /*!< aad size */ +} cau_parameter_struct; + +/* cau_ctl register value */ +#define CAU_ENCRYPT ((uint32_t)0x00000000U) /*!< encrypt */ +#define CAU_DECRYPT CAU_CTL_CAUDIR /*!< decrypt */ + +#define CTL_ALGM(regval) ((BITS(3,5) & ((uint32_t)(regval) << 3U)) | \ + (BIT(19) & ((uint32_t)(regval) << 16U))) /*!< write value to CAU_CTL_ALGM bit field */ +#define CAU_MODE_TDES_ECB CTL_ALGM(0) /*!< TDES-ECB (3DES Electronic codebook) */ +#define CAU_MODE_TDES_CBC CTL_ALGM(1) /*!< TDES-CBC (3DES Cipher block chaining) */ +#define CAU_MODE_DES_ECB CTL_ALGM(2) /*!< DES-ECB (simple DES Electronic codebook) */ +#define CAU_MODE_DES_CBC CTL_ALGM(3) /*!< DES-CBC (simple DES Cipher block chaining) */ +#define CAU_MODE_AES_ECB CTL_ALGM(4) /*!< AES-ECB (AES Electronic codebook) */ +#define CAU_MODE_AES_CBC CTL_ALGM(5) /*!< AES-CBC (AES Cipher block chaining) */ +#define CAU_MODE_AES_CTR CTL_ALGM(6) /*!< AES-CTR (AES counter mode) */ +#define CAU_MODE_AES_KEY CTL_ALGM(7) /*!< AES decryption key preparation mode */ +#define CAU_MODE_AES_GCM CTL_ALGM(8) /*!< AES-GCM (AES Galois/counter mode) */ +#define CAU_MODE_AES_CCM CTL_ALGM(9) /*!< AES-CCM (AES combined cipher machine mode) */ +#define CAU_MODE_AES_CFB CTL_ALGM(10) /*!< AES-CFB (cipher feedback mode) */ +#define CAU_MODE_AES_OFB CTL_ALGM(11) /*!< AES-OFB (output feedback mode) */ + +#define CTL_DATAM(regval) (BITS(6,7) & ((uint32_t)(regval) << 6U)) /*!< write value to CAU_CTL_DATAM bit field */ +#define CAU_SWAPPING_32BIT CTL_DATAM(0) /*!< no swapping */ +#define CAU_SWAPPING_16BIT CTL_DATAM(1) /*!< half-word swapping */ +#define CAU_SWAPPING_8BIT CTL_DATAM(2) /*!< bytes swapping */ +#define CAU_SWAPPING_1BIT CTL_DATAM(3) /*!< bit swapping */ + +#define CTL_KEYM(regval) (BITS(8,9) & ((uint32_t)(regval) << 8U)) /*!< write value to CAU_CTL_KEYM bit field */ +#define CAU_KEYSIZE_128BIT CTL_KEYM(0) /*!< 128 bit key length */ +#define CAU_KEYSIZE_192BIT CTL_KEYM(1) /*!< 192 bit key length */ +#define CAU_KEYSIZE_256BIT CTL_KEYM(2) /*!< 256 bit key length */ + +#define CTL_GCM_CCMPH(regval) (BITS(16,17) & ((uint32_t)(regval) << 16U)) /*!< write value to CAU_CTL_GCM_CCMPH bit field */ +#define CAU_PREPARE_PHASE CTL_GCM_CCMPH(0) /*!< prepare phase */ +#define CAU_AAD_PHASE CTL_GCM_CCMPH(1) /*!< AAD phase */ +#define CAU_ENCRYPT_DECRYPT_PHASE CTL_GCM_CCMPH(2) /*!< encryption/decryption phase */ +#define CAU_TAG_PHASE CTL_GCM_CCMPH(3) /*!< tag phase */ + +#define CAU_PADDING_BYTES(regval) (BITS(20, 23) & ((uint32_t)(regval) << 20U)) + +/* cau_stat0 register value */ +#define CAU_FLAG_INFIFO_EMPTY CAU_STAT0_IEM /*!< IN FIFO empty */ +#define CAU_FLAG_INFIFO_NO_FULL CAU_STAT0_INF /*!< IN FIFO is not full */ +#define CAU_FLAG_OUTFIFO_NO_EMPTY CAU_STAT0_ONE /*!< OUT FIFO not empty */ +#define CAU_FLAG_OUTFIFO_FULL CAU_STAT0_OFU /*!< OUT FIFO is full */ +#define CAU_FLAG_BUSY CAU_STAT0_BUSY /*!< the CAU core is busy */ + +/* cau_dmaen register value */ +#define CAU_DMA_INFIFO CAU_DMAEN_DMAIEN /*!< DMA input enable */ +#define CAU_DMA_OUTFIFO CAU_DMAEN_DMAOEN /*!< DMA output enable */ + +/* cau_inten register value */ +#define CAU_INT_INFIFO CAU_INTEN_IINTEN /*!< IN FIFO Interrupt */ +#define CAU_INT_OUTFIFO CAU_INTEN_OINTEN /*!< OUT FIFO Interrupt */ + +/* cau_stat1 register value */ +#define CAU_FLAG_INFIFO CAU_STAT1_ISTA /*!< IN FIFO flag status */ +#define CAU_FLAG_OUTFIFO CAU_STAT1_OSTA /*!< OUT FIFO flag status */ + +/* cau_intf register value */ +#define CAU_INT_FLAG_INFIFO CAU_INTF_IINTF /*!< IN FIFO interrupt status */ +#define CAU_INT_FLAG_OUTFIFO CAU_INTF_OINTF /*!< OUT FIFO interrupt status */ + +/* function declarations */ +/* initialization functions */ +/* reset the CAU peripheral */ +void cau_deinit(void); +/* initialize the CAU encrypt and decrypt parameter struct with the default values */ +void cau_struct_para_init(cau_parameter_struct *cau_parameter); +/* initialize the key parameter struct with the default values */ +void cau_key_struct_para_init(cau_key_parameter_struct *key_initpara); +/* initialize the vectors parameter struct with the default values */ +void cau_iv_struct_para_init(cau_iv_parameter_struct *iv_initpara); +/* initialize the context parameter struct with the default values */ +void cau_context_struct_para_init(cau_context_parameter_struct *cau_context); + +/* configuration functions */ +/* enable the CAU peripheral */ +void cau_enable(void); +/* disable the CAU peripheral */ +void cau_disable(void); +/* enable the CAU DMA interface */ +void cau_dma_enable(uint32_t dma_req); +/* disable the CAU DMA interface */ +void cau_dma_disable(uint32_t dma_req); +/* initialize the CAU peripheral */ +void cau_init(uint32_t alg_dir, uint32_t algo_mode, uint32_t swapping); +/* configure key size if use AES algorithm */ +void cau_aes_keysize_config(uint32_t key_size); +/* initialize the key parameters */ +void cau_key_init(cau_key_parameter_struct *key_initpara); +/* initialize the vectors parameters */ +void cau_iv_init(cau_iv_parameter_struct *iv_initpara); +/* configure phase */ +void cau_phase_config(uint32_t phase); +/* flush the IN and OUT FIFOs */ +void cau_fifo_flush(void); +/* return whether CAU peripheral is enabled or disabled */ +ControlStatus cau_enable_state_get(void); + +/* read and write functions */ +/* write data to the IN FIFO */ +void cau_data_write(uint32_t data); +/* return the last data entered into the output FIFO */ +uint32_t cau_data_read(void); + +/* context switch functions */ +/* save context before context switching */ +void cau_context_save(cau_context_parameter_struct *cau_context, cau_key_parameter_struct *key_initpara); +/* restore context after context switching */ +void cau_context_restore(cau_context_parameter_struct *cau_context); + +/* encrypt and decrypt functions */ +/* encrypt and decrypt using AES in ECB mode */ +ErrStatus cau_aes_ecb(cau_parameter_struct *cau_parameter, uint8_t *output); +/* encrypt and decrypt using AES in CBC mode */ +ErrStatus cau_aes_cbc(cau_parameter_struct *cau_parameter, uint8_t *output); +/* encrypt and decrypt using AES in CTR mode */ +ErrStatus cau_aes_ctr(cau_parameter_struct *cau_parameter, uint8_t *output); +/* encrypt and decrypt using AES in CFB mode */ +ErrStatus cau_aes_cfb(cau_parameter_struct *cau_parameter, uint8_t *output); +/* encrypt and decrypt using AES in OFB mode */ +ErrStatus cau_aes_ofb(cau_parameter_struct *cau_parameter, uint8_t *output); +/* encrypt and decrypt using AES in GCM mode */ +ErrStatus cau_aes_gcm(cau_parameter_struct *cau_parameter, uint8_t *output, uint8_t *tag); +/* encrypt and decrypt using AES in CCM mode */ +ErrStatus cau_aes_ccm(cau_parameter_struct *cau_parameter, uint8_t *output, uint8_t tag[], uint32_t tag_size, uint8_t aad_buf[]); +/* encrypt and decrypt using TDES in ECB mode */ +ErrStatus cau_tdes_ecb(cau_parameter_struct *cau_parameter, uint8_t *output); +/* encrypt and decrypt using TDES in CBC mode */ +ErrStatus cau_tdes_cbc(cau_parameter_struct *cau_parameter, uint8_t *output); +/* encrypt and decrypt using DES in ECB mode */ +ErrStatus cau_des_ecb(cau_parameter_struct *cau_parameter, uint8_t *output); +/* encrypt and decrypt using DES in CBC mode */ +ErrStatus cau_des_cbc(cau_parameter_struct *cau_parameter, uint8_t *output); + +/* interrupt & flag functions */ +/* get the CAU flag status */ +FlagStatus cau_flag_get(uint32_t flag); +/* enable the CAU interrupts */ +void cau_interrupt_enable(uint32_t interrupt); +/* disable the CAU interrupts */ +void cau_interrupt_disable(uint32_t interrupt); +/* get the interrupt flag */ +FlagStatus cau_interrupt_flag_get(uint32_t interrupt); + +#endif /* GD32F5XX_CAU_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_crc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_crc.h new file mode 100644 index 0000000..4e90d09 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_crc.h @@ -0,0 +1,78 @@ +/*! + \file gd32f5xx_crc.h + \brief definitions for the CRC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_CRC_H +#define GD32F5XX_CRC_H + +#include "gd32f5xx.h" + +/* CRC definitions */ +#define CRC CRC_BASE /*!< CRC base address */ + +/* registers definitions */ +#define CRC_DATA REG32(CRC + 0x00000000U) /*!< CRC data register */ +#define CRC_FDATA REG32(CRC + 0x00000004U) /*!< CRC free data register */ +#define CRC_CTL REG32(CRC + 0x00000008U) /*!< CRC control register */ + +/* bits definitions */ +/* CRC_DATA */ +#define CRC_DATA_DATA BITS(0,31) /*!< CRC calculation result bits */ + +/* CRC_FDATA */ +#define CRC_FDATA_FDATA BITS(0,7) /*!< CRC free data bits */ + +/* CRC_CTL */ +#define CRC_CTL_RST BIT(0) /*!< CRC reset CRC_DATA register bit */ + + +/* function declarations */ +/* deinit CRC calculation unit */ +void crc_deinit(void); + +/* reset data register(CRC_DATA) to the value of 0xFFFFFFFF */ +void crc_data_register_reset(void); +/* read the value of the data register */ +uint32_t crc_data_register_read(void); + +/* read the value of the free data register */ +uint8_t crc_free_data_register_read(void); +/* write data to the free data register */ +void crc_free_data_register_write(uint8_t free_data); + +/* calculate the CRC value of a 32-bit data */ +uint32_t crc_single_data_calculate(uint32_t sdata); +/* calculate the CRC value of an array of 32-bit values */ +uint32_t crc_block_data_calculate(uint32_t array[], uint32_t size); + +#endif /* GD32F5XX_CRC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_ctc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_ctc.h new file mode 100644 index 0000000..8db7e9c --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_ctc.h @@ -0,0 +1,182 @@ +/*! + \file gd32f5xx_ctc.h + \brief definitions for the CTC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_CTC_H +#define GD32F5XX_CTC_H + +#include "gd32f5xx.h" + +/* CTC definitions */ +#define CTC CTC_BASE + +/* registers definitions */ +#define CTC_CTL0 REG32((CTC) + 0x00U) /*!< CTC control register 0 */ +#define CTC_CTL1 REG32((CTC) + 0x04U) /*!< CTC control register 1 */ +#define CTC_STAT REG32((CTC) + 0x08U) /*!< CTC status register */ +#define CTC_INTC REG32((CTC) + 0x0CU) /*!< CTC interrupt clear register */ + +/* bits definitions */ +/* CTC_CTL0 */ +#define CTC_CTL0_CKOKIE BIT(0) /*!< clock trim OK(CKOKIF) interrupt enable */ +#define CTC_CTL0_CKWARNIE BIT(1) /*!< clock trim warning(CKWARNIF) interrupt enable */ +#define CTC_CTL0_ERRIE BIT(2) /*!< error(ERRIF) interrupt enable */ +#define CTC_CTL0_EREFIE BIT(3) /*!< EREFIF interrupt enable */ +#define CTC_CTL0_CNTEN BIT(5) /*!< CTC counter enable */ +#define CTC_CTL0_AUTOTRIM BIT(6) /*!< hardware automatically trim mode */ +#define CTC_CTL0_SWREFPUL BIT(7) /*!< software reference source sync pulse */ +#define CTC_CTL0_TRIMVALUE BITS(8,13) /*!< IRC48M trim value */ + +/* CTC_CTL1 */ +#define CTC_CTL1_RLVALUE BITS(0,15) /*!< CTC counter reload value */ +#define CTC_CTL1_CKLIM BITS(16,23) /*!< clock trim base limit value */ +#define CTC_CTL1_REFPSC BITS(24,26) /*!< reference signal source prescaler */ +#define CTC_CTL1_REFSEL BITS(28,29) /*!< reference signal source selection */ +#define CTC_CTL1_REFPOL BIT(31) /*!< reference signal source polarity */ + +/* CTC_STAT */ +#define CTC_STAT_CKOKIF BIT(0) /*!< clock trim OK interrupt flag */ +#define CTC_STAT_CKWARNIF BIT(1) /*!< clock trim warning interrupt flag */ +#define CTC_STAT_ERRIF BIT(2) /*!< error interrupt flag */ +#define CTC_STAT_EREFIF BIT(3) /*!< expect reference interrupt flag */ +#define CTC_STAT_CKERR BIT(8) /*!< clock trim error bit */ +#define CTC_STAT_REFMISS BIT(9) /*!< reference sync pulse miss */ +#define CTC_STAT_TRIMERR BIT(10) /*!< trim value error bit */ +#define CTC_STAT_REFDIR BIT(15) /*!< CTC trim counter direction when reference sync pulse occurred */ +#define CTC_STAT_REFCAP BITS(16,31) /*!< CTC counter capture when reference sync pulse occurred */ + +/* CTC_INTC */ +#define CTC_INTC_CKOKIC BIT(0) /*!< CKOKIF interrupt clear bit */ +#define CTC_INTC_CKWARNIC BIT(1) /*!< CKWARNIF interrupt clear bit */ +#define CTC_INTC_ERRIC BIT(2) /*!< ERRIF interrupt clear bit */ +#define CTC_INTC_EREFIC BIT(3) /*!< EREFIF interrupt clear bit */ + +/* constants definitions */ +/* hardware automatically trim mode definitions */ +#define CTC_HARDWARE_TRIM_MODE_ENABLE CTC_CTL0_AUTOTRIM /*!< hardware automatically trim mode enable*/ +#define CTC_HARDWARE_TRIM_MODE_DISABLE ((uint32_t)0x00000000U) /*!< hardware automatically trim mode disable*/ + +/* reference signal source polarity definitions */ +#define CTC_REFSOURCE_POLARITY_FALLING CTC_CTL1_REFPOL /*!< reference signal source polarity is falling edge*/ +#define CTC_REFSOURCE_POLARITY_RISING ((uint32_t)0x00000000U) /*!< reference signal source polarity is rising edge*/ + +/* reference signal source selection definitions */ +#define CTL1_REFSEL(regval) (BITS(28,29) & ((uint32_t)(regval) << 28)) +#define CTC_REFSOURCE_GPIO CTL1_REFSEL(0) /*!< GPIO is selected */ +#define CTC_REFSOURCE_LXTAL CTL1_REFSEL(1) /*!< LXTAL is clock selected */ + +/* reference signal source prescaler definitions */ +#define CTL1_REFPSC(regval) (BITS(24,26) & ((uint32_t)(regval) << 24)) +#define CTC_REFSOURCE_PSC_OFF CTL1_REFPSC(0) /*!< reference signal not divided */ +#define CTC_REFSOURCE_PSC_DIV2 CTL1_REFPSC(1) /*!< reference signal divided by 2 */ +#define CTC_REFSOURCE_PSC_DIV4 CTL1_REFPSC(2) /*!< reference signal divided by 4 */ +#define CTC_REFSOURCE_PSC_DIV8 CTL1_REFPSC(3) /*!< reference signal divided by 8 */ +#define CTC_REFSOURCE_PSC_DIV16 CTL1_REFPSC(4) /*!< reference signal divided by 16 */ +#define CTC_REFSOURCE_PSC_DIV32 CTL1_REFPSC(5) /*!< reference signal divided by 32 */ +#define CTC_REFSOURCE_PSC_DIV64 CTL1_REFPSC(6) /*!< reference signal divided by 64 */ +#define CTC_REFSOURCE_PSC_DIV128 CTL1_REFPSC(7) /*!< reference signal divided by 128 */ + +/* CTC interrupt enable definitions */ +#define CTC_INT_CKOK CTC_CTL0_CKOKIE /*!< clock trim OK interrupt enable */ +#define CTC_INT_CKWARN CTC_CTL0_CKWARNIE /*!< clock trim warning interrupt enable */ +#define CTC_INT_ERR CTC_CTL0_ERRIE /*!< error interrupt enable */ +#define CTC_INT_EREF CTC_CTL0_EREFIE /*!< expect reference interrupt enable */ + +/* CTC interrupt source definitions */ +#define CTC_INT_FLAG_CKOK CTC_STAT_CKOKIF /*!< clock trim OK interrupt flag */ +#define CTC_INT_FLAG_CKWARN CTC_STAT_CKWARNIF /*!< clock trim warning interrupt flag */ +#define CTC_INT_FLAG_ERR CTC_STAT_ERRIF /*!< error interrupt flag */ +#define CTC_INT_FLAG_EREF CTC_STAT_EREFIF /*!< expect reference interrupt flag */ +#define CTC_INT_FLAG_CKERR CTC_STAT_CKERR /*!< clock trim error bit */ +#define CTC_INT_FLAG_REFMISS CTC_STAT_REFMISS /*!< reference sync pulse miss */ +#define CTC_INT_FLAG_TRIMERR CTC_STAT_TRIMERR /*!< trim value error */ + +/* CTC flag definitions */ +#define CTC_FLAG_CKOK CTC_STAT_CKOKIF /*!< clock trim OK flag */ +#define CTC_FLAG_CKWARN CTC_STAT_CKWARNIF /*!< clock trim warning flag */ +#define CTC_FLAG_ERR CTC_STAT_ERRIF /*!< error flag */ +#define CTC_FLAG_EREF CTC_STAT_EREFIF /*!< expect reference flag */ +#define CTC_FLAG_CKERR CTC_STAT_CKERR /*!< clock trim error bit */ +#define CTC_FLAG_REFMISS CTC_STAT_REFMISS /*!< reference sync pulse miss */ +#define CTC_FLAG_TRIMERR CTC_STAT_TRIMERR /*!< trim value error bit */ + +/* function declarations */ +/* reset ctc clock trim controller */ +void ctc_deinit(void); +/* enable CTC trim counter */ +void ctc_counter_enable(void); +/* disable CTC trim counter */ +void ctc_counter_disable(void); + +/* configure the IRC48M trim value */ +void ctc_irc48m_trim_value_config(uint8_t trim_value); +/* generate software reference source sync pulse */ +void ctc_software_refsource_pulse_generate(void); +/* configure hardware automatically trim mode */ +void ctc_hardware_trim_mode_config(uint32_t hardmode); + +/* configure reference signal source polarity */ +void ctc_refsource_polarity_config(uint32_t polarity); +/* select reference signal source */ +void ctc_refsource_signal_select(uint32_t refs); +/* configure reference signal source prescaler */ +void ctc_refsource_prescaler_config(uint32_t prescaler); +/* configure clock trim base limit value */ +void ctc_clock_limit_value_config(uint8_t limit_value); +/* configure CTC counter reload value */ +void ctc_counter_reload_value_config(uint16_t reload_value); + +/* read CTC counter capture value when reference sync pulse occurred */ +uint16_t ctc_counter_capture_value_read(void); +/* read CTC trim counter direction when reference sync pulse occurred */ +FlagStatus ctc_counter_direction_read(void); +/* read CTC counter reload value */ +uint16_t ctc_counter_reload_value_read(void); +/* read the IRC48M trim value */ +uint8_t ctc_irc48m_trim_value_read(void); + +/* interrupt & flag functions */ +/* enable the CTC interrupt */ +void ctc_interrupt_enable(uint32_t interrupt); +/* disable the CTC interrupt */ +void ctc_interrupt_disable(uint32_t interrupt); +/* get CTC interrupt flag */ +FlagStatus ctc_interrupt_flag_get(uint32_t int_flag); +/* clear CTC interrupt flag */ +void ctc_interrupt_flag_clear(uint32_t int_flag); +/* get CTC flag */ +FlagStatus ctc_flag_get(uint32_t flag); +/* clear CTC flag */ +void ctc_flag_clear(uint32_t flag); + +#endif /* GD32F5XX_CTC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dac.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dac.h new file mode 100644 index 0000000..6e05254 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dac.h @@ -0,0 +1,277 @@ +/*! + \file gd32f5xx_dac.h + \brief definitions for the DAC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_DAC_H +#define GD32F5XX_DAC_H + +#include "gd32f5xx.h" + +/* DACx(x=0) definitions */ +#define DAC0 (DAC_BASE) + +/* registers definitions */ +#define DAC_CTL0(dacx) REG32((dacx) + 0x00000000U) /*!< DACx control register 0 */ +#define DAC_SWT(dacx) REG32((dacx) + 0x00000004U) /*!< DACx software trigger register */ +#define DAC_OUT0_R12DH(dacx) REG32((dacx) + 0x00000008U) /*!< DACx_OUT0 12-bit right-aligned data holding register */ +#define DAC_OUT0_L12DH(dacx) REG32((dacx) + 0x0000000CU) /*!< DACx_OUT0 12-bit left-aligned data holding register */ +#define DAC_OUT0_R8DH(dacx) REG32((dacx) + 0x00000010U) /*!< DACx_OUT0 8-bit right-aligned data holding register */ +#define DAC_OUT1_R12DH(dacx) REG32((dacx) + 0x00000014U) /*!< DACx_OUT1 12-bit right-aligned data holding register */ +#define DAC_OUT1_L12DH(dacx) REG32((dacx) + 0x00000018U) /*!< DACx_OUT1 12-bit left-aligned data holding register */ +#define DAC_OUT1_R8DH(dacx) REG32((dacx) + 0x0000001CU) /*!< DACx_OUT1 8-bit right-aligned data holding register */ +#define DACC_R12DH(dacx) REG32((dacx) + 0x00000020U) /*!< DACx concurrent mode 12-bit right-aligned data holding register */ +#define DACC_L12DH(dacx) REG32((dacx) + 0x00000024U) /*!< DACx concurrent mode 12-bit left-aligned data holding register */ +#define DACC_R8DH(dacx) REG32((dacx) + 0x00000028U) /*!< DACx concurrent mode 8-bit right-aligned data holding register */ +#define DAC_OUT0_DO(dacx) REG32((dacx) + 0x0000002CU) /*!< DACx_OUT0 data output register */ +#define DAC_OUT1_DO(dacx) REG32((dacx) + 0x00000030U) /*!< DACx_OUT1 data output register */ +#define DAC_STAT0(dacx) REG32((dacx) + 0x00000034U) /*!< DACx status register 0 */ + +/* bits definitions */ +/* DAC_CTL0 */ +#define DAC_CTL0_DEN0 BIT(0) /*!< DACx_OUT0 enable */ +#define DAC_CTL0_DBOFF0 BIT(1) /*!< DACx_OUT0 output buffer turn off */ +#define DAC_CTL0_DTEN0 BIT(2) /*!< DACx_OUT0 trigger enable */ +#define DAC_CTL0_DTSEL0 BITS(3,5) /*!< DACx_OUT0 trigger selection */ +#define DAC_CTL0_DWM0 BITS(6,7) /*!< DACx_OUT0 noise wave mode */ +#define DAC_CTL0_DWBW0 BITS(8,11) /*!< DACx_OUT0 noise wave bit width */ +#define DAC_CTL0_DDMAEN0 BIT(12) /*!< DACx_OUT0 DMA enable */ +#define DAC_CTL0_DDUDRIE0 BIT(13) /*!< DACx_OUT0 DMA underrun interrupt enable */ + +#define DAC_CTL0_DEN1 BIT(16) /*!< DACx_OUT1 enable */ +#define DAC_CTL0_DBOFF1 BIT(17) /*!< DACx_OUT1 output buffer turn off */ +#define DAC_CTL0_DTEN1 BIT(18) /*!< DACx_OUT1 trigger enable */ +#define DAC_CTL0_DTSEL1 BITS(19,21) /*!< DACx_OUT1 trigger selection */ +#define DAC_CTL0_DWM1 BITS(22,23) /*!< DACx_OUT1 noise wave mode */ +#define DAC_CTL0_DWBW1 BITS(24,27) /*!< DACx_OUT1 noise wave bit width */ +#define DAC_CTL0_DDMAEN1 BIT(28) /*!< DACx_OUT1 DMA enable */ +#define DAC_CTL0_DDUDRIE1 BIT(29) /*!< DACx_OUT1 DMA underrun interrupt enable */ + +/* DAC_SWT */ +#define DAC_SWT_SWTR0 BIT(0) /*!< DACx_OUT0 software trigger */ +#define DAC_SWT_SWTR1 BIT(1) /*!< DACx_OUT1 software trigger */ + +/* DAC0_OUT0_R12DH */ +#define DAC_OUT0_DH_R12 BITS(0,11) /*!< DACx_OUT0 12-bit right-aligned data */ + +/* DAC0_OUT0_L12DH */ +#define DAC_OUT0_DH_L12 BITS(4,15) /*!< DACx_OUT0 12-bit left-aligned data */ + +/* DAC0_OUT0_R8DH */ +#define DAC_OUT0_DH_R8 BITS(0,7) /*!< DACx_OUT0 8-bit right-aligned data */ + +/* DAC1_OUT1_R12DH */ +#define DAC_OUT1_DH_R12 BITS(0,11) /*!< DACx_OUT1 12-bit right-aligned data */ + +/* DAC1_OUT1_L12DH */ +#define DAC_OUT1_DH_L12 BITS(4,15) /*!< DACx_OUT1 12-bit left-aligned data */ + +/* DAC1_OUT1_R8DH */ +#define DAC_OUT1_DH_R8 BITS(0,7) /*!< DACx_OUT1 8-bit right-aligned data */ + +/* DACC_R12DH */ +#define DACC_OUT0_DH_R12 BITS(0,11) /*!< DAC concurrent mode DACx_OUT0 12-bit right-aligned data */ +#define DACC_OUT1_DH_R12 BITS(16,27) /*!< DAC concurrent mode DACx_OUT1 12-bit right-aligned data */ + +/* DACC_L12DH */ +#define DACC_OUT0_DH_L12 BITS(4,15) /*!< DAC concurrent mode DACx_OUT0 12-bit left-aligned data */ +#define DACC_OUT1_DH_L12 BITS(20,31) /*!< DAC concurrent mode DACx_OUT1 12-bit left-aligned data */ + +/* DACC_R8DH */ +#define DACC_OUT0_DH_R8 BITS(0,7) /*!< DAC concurrent mode DACx_OUT0 8-bit right-aligned data */ +#define DACC_OUT1_DH_R8 BITS(8,15) /*!< DAC concurrent mode DACx_OUT1 8-bit right-aligned data */ + +/* DAC0_OUT0_DO */ +#define DAC_OUT0_DO_BITS BITS(0,11) /*!< DACx_OUT0 12-bit output data */ + +/* DAC1_OUT1_DO */ +#define DAC_OUT1_DO_BITS BITS(0,11) /*!< DACx_OUT1 12-bit output data */ + +/* DAC_STAT0 */ +#define DAC_STAT0_DDUDR0 BIT(13) /*!< DACx_OUT0 DMA underrun flag */ +#define DAC_STAT0_DDUDR1 BIT(29) /*!< DACx_OUT1 DMA underrun flag */ + +/* constants definitions */ +/* DAC trigger source */ +#define CTL0_DTSEL(regval) (BITS(3,5) & ((uint32_t)(regval) << 3)) +#define DAC_TRIGGER_T5_TRGO CTL0_DTSEL(0) /*!< TIMER5 TRGO */ +#define DAC_TRIGGER_T7_TRGO CTL0_DTSEL(1) /*!< TIMER7 TRGO */ +#define DAC_TRIGGER_T6_TRGO CTL0_DTSEL(2) /*!< TIMER6 TRGO */ +#define DAC_TRIGGER_T4_TRGO CTL0_DTSEL(3) /*!< TIMER4 TRGO */ +#define DAC_TRIGGER_T1_TRGO CTL0_DTSEL(4) /*!< TIMER1 TRGO */ +#define DAC_TRIGGER_T3_TRGO CTL0_DTSEL(5) /*!< TIMER3 TRGO */ +#define DAC_TRIGGER_EXTI_9 CTL0_DTSEL(6) /*!< EXTI interrupt line9 event */ +#define DAC_TRIGGER_SOFTWARE CTL0_DTSEL(7) /*!< software trigger */ + +/* DAC noise wave mode */ +#define CTL0_DWM(regval) (BITS(6,7) & ((uint32_t)(regval) << 6)) +#define DAC_WAVE_DISABLE CTL0_DWM(0) /*!< wave disabled */ +#define DAC_WAVE_MODE_LFSR CTL0_DWM(1) /*!< LFSR noise mode */ +#define DAC_WAVE_MODE_TRIANGLE CTL0_DWM(2) /*!< triangle noise mode */ + +/* DAC noise wave bit width */ +#define DWBW(regval) (BITS(8,11) & ((uint32_t)(regval) << 8)) +#define DAC_WAVE_BIT_WIDTH_1 DWBW(0) /*!< bit width of the wave signal is 1 */ +#define DAC_WAVE_BIT_WIDTH_2 DWBW(1) /*!< bit width of the wave signal is 2 */ +#define DAC_WAVE_BIT_WIDTH_3 DWBW(2) /*!< bit width of the wave signal is 3 */ +#define DAC_WAVE_BIT_WIDTH_4 DWBW(3) /*!< bit width of the wave signal is 4 */ +#define DAC_WAVE_BIT_WIDTH_5 DWBW(4) /*!< bit width of the wave signal is 5 */ +#define DAC_WAVE_BIT_WIDTH_6 DWBW(5) /*!< bit width of the wave signal is 6 */ +#define DAC_WAVE_BIT_WIDTH_7 DWBW(6) /*!< bit width of the wave signal is 7 */ +#define DAC_WAVE_BIT_WIDTH_8 DWBW(7) /*!< bit width of the wave signal is 8 */ +#define DAC_WAVE_BIT_WIDTH_9 DWBW(8) /*!< bit width of the wave signal is 9 */ +#define DAC_WAVE_BIT_WIDTH_10 DWBW(9) /*!< bit width of the wave signal is 10 */ +#define DAC_WAVE_BIT_WIDTH_11 DWBW(10) /*!< bit width of the wave signal is 11 */ +#define DAC_WAVE_BIT_WIDTH_12 DWBW(11) /*!< bit width of the wave signal is 12 */ + +/* unmask LFSR bits in DAC LFSR noise mode */ +#define DAC_LFSR_BIT0 DAC_WAVE_BIT_WIDTH_1 /*!< unmask the LFSR bit0 */ +#define DAC_LFSR_BITS1_0 DAC_WAVE_BIT_WIDTH_2 /*!< unmask the LFSR bits[1:0] */ +#define DAC_LFSR_BITS2_0 DAC_WAVE_BIT_WIDTH_3 /*!< unmask the LFSR bits[2:0] */ +#define DAC_LFSR_BITS3_0 DAC_WAVE_BIT_WIDTH_4 /*!< unmask the LFSR bits[3:0] */ +#define DAC_LFSR_BITS4_0 DAC_WAVE_BIT_WIDTH_5 /*!< unmask the LFSR bits[4:0] */ +#define DAC_LFSR_BITS5_0 DAC_WAVE_BIT_WIDTH_6 /*!< unmask the LFSR bits[5:0] */ +#define DAC_LFSR_BITS6_0 DAC_WAVE_BIT_WIDTH_7 /*!< unmask the LFSR bits[6:0] */ +#define DAC_LFSR_BITS7_0 DAC_WAVE_BIT_WIDTH_8 /*!< unmask the LFSR bits[7:0] */ +#define DAC_LFSR_BITS8_0 DAC_WAVE_BIT_WIDTH_9 /*!< unmask the LFSR bits[8:0] */ +#define DAC_LFSR_BITS9_0 DAC_WAVE_BIT_WIDTH_10 /*!< unmask the LFSR bits[9:0] */ +#define DAC_LFSR_BITS10_0 DAC_WAVE_BIT_WIDTH_11 /*!< unmask the LFSR bits[10:0] */ +#define DAC_LFSR_BITS11_0 DAC_WAVE_BIT_WIDTH_12 /*!< unmask the LFSR bits[11:0] */ + +/* triangle amplitude in DAC triangle noise mode */ +#define DAC_TRIANGLE_AMPLITUDE_1 DAC_WAVE_BIT_WIDTH_1 /*!< triangle amplitude is 1 */ +#define DAC_TRIANGLE_AMPLITUDE_3 DAC_WAVE_BIT_WIDTH_2 /*!< triangle amplitude is 3 */ +#define DAC_TRIANGLE_AMPLITUDE_7 DAC_WAVE_BIT_WIDTH_3 /*!< triangle amplitude is 7 */ +#define DAC_TRIANGLE_AMPLITUDE_15 DAC_WAVE_BIT_WIDTH_4 /*!< triangle amplitude is 15 */ +#define DAC_TRIANGLE_AMPLITUDE_31 DAC_WAVE_BIT_WIDTH_5 /*!< triangle amplitude is 31 */ +#define DAC_TRIANGLE_AMPLITUDE_63 DAC_WAVE_BIT_WIDTH_6 /*!< triangle amplitude is 63 */ +#define DAC_TRIANGLE_AMPLITUDE_127 DAC_WAVE_BIT_WIDTH_7 /*!< triangle amplitude is 127 */ +#define DAC_TRIANGLE_AMPLITUDE_255 DAC_WAVE_BIT_WIDTH_8 /*!< triangle amplitude is 255 */ +#define DAC_TRIANGLE_AMPLITUDE_511 DAC_WAVE_BIT_WIDTH_9 /*!< triangle amplitude is 511 */ +#define DAC_TRIANGLE_AMPLITUDE_1023 DAC_WAVE_BIT_WIDTH_10 /*!< triangle amplitude is 1023 */ +#define DAC_TRIANGLE_AMPLITUDE_2047 DAC_WAVE_BIT_WIDTH_11 /*!< triangle amplitude is 2047 */ +#define DAC_TRIANGLE_AMPLITUDE_4095 DAC_WAVE_BIT_WIDTH_12 /*!< triangle amplitude is 4095 */ + +/* DAC data alignment */ +#define DATA_ALIGN(regval) (BITS(0,1) & ((uint32_t)(regval) << 0)) +#define DAC_ALIGN_12B_R DATA_ALIGN(0) /*!< 12-bit right-aligned data */ +#define DAC_ALIGN_12B_L DATA_ALIGN(1) /*!< 12-bit left-aligned data */ +#define DAC_ALIGN_8B_R DATA_ALIGN(2) /*!< 8-bit right-aligned data */ + +/* DAC output channel definitions */ +#define DAC_OUT0 ((uint8_t)0x00U) /*!< DACx_OUT0 channel */ +#define DAC_OUT1 ((uint8_t)0x01U) /*!< DACx_OUT1 channel */ + +/* DAC interrupt */ +#define DAC_INT_DDUDR0 DAC_CTL0_DDUDRIE0 /*!< DACx_OUT0 DMA underrun interrupt */ +#define DAC_INT_DDUDR1 DAC_CTL0_DDUDRIE1 /*!< DACx_OUT1 DMA underrun interrupt */ + +/* DAC interrupt flag */ +#define DAC_INT_FLAG_DDUDR0 DAC_STAT0_DDUDR0 /*!< DACx_OUT0 DMA underrun interrupt flag */ +#define DAC_INT_FLAG_DDUDR1 DAC_STAT0_DDUDR1 /*!< DACx_OUT1 DMA underrun interrupt flag */ + +/* DAC flags */ +#define DAC_FLAG_DDUDR0 DAC_STAT0_DDUDR0 /*!< DACx_OUT0 DMA underrun flag */ +#define DAC_FLAG_DDUDR1 DAC_STAT0_DDUDR1 /*!< DACx_OUT1 DMA underrun flag */ + +/* function declarations */ +/* DAC initialization functions */ +/* deinitialize DAC */ +void dac_deinit(uint32_t dac_periph); +/* enable DAC */ +void dac_enable(uint32_t dac_periph, uint8_t dac_out); +/* disable DAC */ +void dac_disable(uint32_t dac_periph, uint8_t dac_out); +/* enable DAC DMA function */ +void dac_dma_enable(uint32_t dac_periph, uint8_t dac_out); +/* disable DAC DMA function */ +void dac_dma_disable(uint32_t dac_periph, uint8_t dac_out); + +/* DAC buffer functions */ +/* enable DAC output buffer */ +void dac_output_buffer_enable(uint32_t dac_periph, uint8_t dac_out); +/* disable DAC output buffer */ +void dac_output_buffer_disable(uint32_t dac_periph, uint8_t dac_out); + +/* read and write operation functions */ +/* get DAC output value */ +uint16_t dac_output_value_get(uint32_t dac_periph, uint8_t dac_out); +/* set DAC data holding register value */ +void dac_data_set(uint32_t dac_periph, uint8_t dac_out, uint32_t dac_align, uint16_t data); + +/* DAC trigger configuration */ +/* enable DAC trigger */ +void dac_trigger_enable(uint32_t dac_periph, uint8_t dac_out); +/* disable DAC trigger */ +void dac_trigger_disable(uint32_t dac_periph, uint8_t dac_out); +/* configure DAC trigger source */ +void dac_trigger_source_config(uint32_t dac_periph, uint8_t dac_out, uint32_t triggersource); +/* enable DAC software trigger */ +void dac_software_trigger_enable(uint32_t dac_periph, uint8_t dac_out); + +/* DAC wave mode configuration */ +/* configure DAC wave mode */ +void dac_wave_mode_config(uint32_t dac_periph, uint8_t dac_out, uint32_t wave_mode); +/* configure DAC LFSR noise mode */ +void dac_lfsr_noise_config(uint32_t dac_periph, uint8_t dac_out, uint32_t unmask_bits); +/* configure DAC triangle noise mode */ +void dac_triangle_noise_config(uint32_t dac_periph, uint8_t dac_out, uint32_t amplitude); + +/* DAC concurrent mode configuration */ +/* enable DAC concurrent mode */ +void dac_concurrent_enable(uint32_t dac_periph); +/* disable DAC concurrent mode */ +void dac_concurrent_disable(uint32_t dac_periph); +/* enable DAC concurrent software trigger */ +void dac_concurrent_software_trigger_enable(uint32_t dac_periph); +/* enable DAC concurrent buffer function */ +void dac_concurrent_output_buffer_enable(uint32_t dac_periph); +/* disable DAC concurrent buffer function */ +void dac_concurrent_output_buffer_disable(uint32_t dac_periph); +/* set DAC concurrent mode data holding register value */ +void dac_concurrent_data_set(uint32_t dac_periph, uint32_t dac_align, uint16_t data0, uint16_t data1); + +/* DAC interrupt and flag functions */ +/* get DAC flag */ +FlagStatus dac_flag_get(uint32_t dac_periph, uint32_t flag); +/* clear DAC flag */ +void dac_flag_clear(uint32_t dac_periph, uint32_t flag); +/* enable DAC interrupt */ +void dac_interrupt_enable(uint32_t dac_periph, uint32_t interrupt); +/* disable DAC interrupt */ +void dac_interrupt_disable(uint32_t dac_periph, uint32_t interrupt); +/* get DAC interrupt flag */ +FlagStatus dac_interrupt_flag_get(uint32_t dac_periph, uint32_t int_flag); +/* clear DAC interrupt flag */ +void dac_interrupt_flag_clear(uint32_t dac_periph, uint32_t int_flag); + +#endif /* GD32F5XX_DAC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dbg.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dbg.h new file mode 100644 index 0000000..e75a5d7 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dbg.h @@ -0,0 +1,165 @@ +/*! + \file gd32f5xx_dbg.h + \brief definitions for the DBG + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_DBG_H +#define GD32F5XX_DBG_H + +#include "gd32f5xx.h" + +/* DBG definitions */ +#define DBG DBG_BASE + +/* registers definitions */ +#define DBG_ID REG32(DBG + 0x00U) /*!< DBG_ID code register */ +#define DBG_CTL0 REG32(DBG + 0x04U) /*!< DBG control register 0 */ +#define DBG_CTL1 REG32(DBG + 0x08U) /*!< DBG control register 1 */ +#define DBG_CTL2 REG32(DBG + 0x0CU) /*!< DBG control register 2 */ +#define DBG_CTL3 REG32(DBG + 0x10U) /*!< DBG control register 3 */ + +/* bits definitions */ +/* DBG_ID */ +#define DBG_ID_ID_CODE BITS(0,31) /*!< DBG ID code values */ + +/* DBG_CTL0 */ +#define DBG_CTL0_SLP_HOLD BIT(0) /*!< keep debugger connection during sleep mode */ +#define DBG_CTL0_DSLP_HOLD BIT(1) /*!< keep debugger connection during deepsleep mode */ +#define DBG_CTL0_STB_HOLD BIT(2) /*!< keep debugger connection during standby mode */ +#define DBG_CTL0_TRACE_IOEN BIT(5) /*!< enable trace pin assignment */ + +/* DBG_CTL1 */ +#define DBG_CTL1_TIMER1_HOLD BIT(0) /*!< hold TIMER1 counter when core is halted */ +#define DBG_CTL1_TIMER2_HOLD BIT(1) /*!< hold TIMER2 counter when core is halted */ +#define DBG_CTL1_TIMER3_HOLD BIT(2) /*!< hold TIMER3 counter when core is halted */ +#define DBG_CTL1_TIMER4_HOLD BIT(3) /*!< hold TIMER4 counter when core is halted */ +#define DBG_CTL1_TIMER5_HOLD BIT(4) /*!< hold TIMER5 counter when core is halted */ +#define DBG_CTL1_TIMER6_HOLD BIT(5) /*!< hold TIMER6 counter when core is halted */ +#define DBG_CTL1_TIMER11_HOLD BIT(6) /*!< hold TIMER11 counter when core is halted */ +#define DBG_CTL1_TIMER12_HOLD BIT(7) /*!< hold TIMER12 counter when core is halted */ +#define DBG_CTL1_TIMER13_HOLD BIT(8) /*!< hold TIMER13 counter when core is halted */ +#define DBG_CTL1_RTC_HOLD BIT(10) /*!< hold RTC calendar and wakeup counter when core is halted */ +#define DBG_CTL1_WWDGT_HOLD BIT(11) /*!< debug WWDGT kept when core is halted */ +#define DBG_CTL1_FWDGT_HOLD BIT(12) /*!< debug FWDGT kept when core is halted */ +#define DBG_CTL1_I2C3_HOLD BIT(18) /*!< hold I2C3 smbus when core is halted */ +#define DBG_CTL1_I2C4_HOLD BIT(19) /*!< hold I2C4 smbus when core is halted */ +#define DBG_CTL1_I2C5_HOLD BIT(20) /*!< hold I2C5 smbus when core is halted */ +#define DBG_CTL1_I2C0_HOLD BIT(21) /*!< hold I2C0 smbus when core is halted */ +#define DBG_CTL1_I2C1_HOLD BIT(22) /*!< hold I2C1 smbus when core is halted */ +#define DBG_CTL1_I2C2_HOLD BIT(23) /*!< hold I2C2 smbus when core is halted */ +#define DBG_CTL1_CAN0_HOLD BIT(25) /*!< debug CAN0 kept when core is halted */ +#define DBG_CTL1_CAN1_HOLD BIT(26) /*!< debug CAN1 kept when core is halted */ + +/* DBG_CTL2 */ +#define DBG_CTL2_TIMER0_HOLD BIT(0) /*!< hold TIMER0 counter when core is halted */ +#define DBG_CTL2_TIMER7_HOLD BIT(1) /*!< hold TIMER7 counter when core is halted */ +#define DBG_CTL2_TIMER8_HOLD BIT(16) /*!< hold TIMER8 counter when core is halted */ +#define DBG_CTL2_TIMER9_HOLD BIT(17) /*!< hold TIMER9 counter when core is halted */ +#define DBG_CTL2_TIMER10_HOLD BIT(18) /*!< hold TIMER10 counter when core is halted */ + +/* DBG_CTL3 */ +#define DBG_CTL3_DEVICEID BITS(0,3) /*!< device ID */ + +/* constants definitions */ +#define DBG_LOW_POWER_SLEEP DBG_CTL0_SLP_HOLD /*!< keep debugger connection during sleep mode */ +#define DBG_LOW_POWER_DEEPSLEEP DBG_CTL0_DSLP_HOLD /*!< keep debugger connection during deepsleep mode */ +#define DBG_LOW_POWER_STANDBY DBG_CTL0_STB_HOLD /*!< keep debugger connection during standby mode */ + +/* define the peripheral debug hold bit position and its register index offset */ +#define DBG_REGIDX_BIT(regidx, bitpos) (((regidx) << 6) | (bitpos)) +#define DBG_REG_VAL(periph) (REG32(DBG + ((uint32_t)(periph) >> 6))) +#define DBG_BIT_POS(val) ((uint32_t)(val) & 0x1FU) + +/* register index */ +enum dbg_reg_idx +{ + DBG_IDX_CTL0 = 0x04U, + DBG_IDX_CTL1 = 0x08U, + DBG_IDX_CTL2 = 0x0CU +}; + +typedef enum +{ + DBG_TIMER1_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 0U), /*!< hold TIMER1 counter when core is halted */ + DBG_TIMER2_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 1U), /*!< hold TIMER2 counter when core is halted */ + DBG_TIMER3_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 2U), /*!< hold TIMER3 counter when core is halted */ + DBG_TIMER4_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 3U), /*!< hold TIMER4 counter when core is halted */ + DBG_TIMER5_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 4U), /*!< hold TIMER5 counter when core is halted */ + DBG_TIMER6_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 5U), /*!< hold TIMER6 counter when core is halted */ + DBG_TIMER11_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 6U), /*!< hold TIMER11 counter when core is halted */ + DBG_TIMER12_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 7U), /*!< hold TIMER12 counter when core is halted */ + DBG_TIMER13_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 8U), /*!< hold TIMER13 counter when core is halted */ + DBG_RTC_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 10U), /*!< hold RTC calendar and wakeup counter when core is halted */ + DBG_WWDGT_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 11U), /*!< debug WWDGT kept when core is halted */ + DBG_FWDGT_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 12U), /*!< debug FWDGT kept when core is halted */ + DBG_I2C3_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 18U), /*!< hold I2C3 smbus when core is halted */ + DBG_I2C4_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 19U), /*!< hold I2C4 smbus when core is halted */ + DBG_I2C5_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 20U), /*!< hold I2C5 smbus when core is halted */ + DBG_I2C0_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 21U), /*!< hold I2C0 smbus when core is halted */ + DBG_I2C1_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 22U), /*!< hold I2C1 smbus when core is halted */ + DBG_I2C2_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 23U), /*!< hold I2C2 smbus when core is halted */ + DBG_CAN0_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 25U), /*!< debug CAN0 kept when core is halted */ + DBG_CAN1_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL1, 26U), /*!< debug CAN1 kept when core is halted */ + DBG_TIMER0_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL2, 0U), /*!< hold TIMER0 counter when core is halted */ + DBG_TIMER7_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL2, 1U), /*!< hold TIMER7 counter when core is halted */ + DBG_TIMER8_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL2, 16U), /*!< hold TIMER8 counter when core is halted */ + DBG_TIMER9_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL2, 17U), /*!< hold TIMER9 counter when core is halted */ + DBG_TIMER10_HOLD = DBG_REGIDX_BIT(DBG_IDX_CTL2, 18U) /*!< hold TIMER10 counter when core is halted */ +}dbg_periph_enum; + +/* function declarations */ +/* deinitialize the DBG */ +void dbg_deinit(void); +/* read DBG_ID code register */ +uint32_t dbg_id_get(void); + +/* enable low power behavior when the MCU is in debug mode */ +void dbg_low_power_enable(uint32_t dbg_low_power); +/* disable low power behavior when the MCU is in debug mode */ +void dbg_low_power_disable(uint32_t dbg_low_power); + +/* enable peripheral behavior when the MCU is in debug mode */ +void dbg_periph_enable(dbg_periph_enum dbg_periph); +/* disable peripheral behavior when the MCU is in debug mode */ +void dbg_periph_disable(dbg_periph_enum dbg_periph); + +/* enable trace pin assignment */ +void dbg_trace_pin_enable(void); +/* disable trace pin assignment */ +void dbg_trace_pin_disable(void); + +/* read DBG DEVICE ID */ +uint32_t dbg_deviceid_get(void); +/* write DBG DEVICEID */ +void dbg_deviceid_set(uint32_t deviceid); + +#endif /* GD32F5XX_DBG_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dci.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dci.h new file mode 100644 index 0000000..18376ce --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dci.h @@ -0,0 +1,236 @@ +/*! + \file gd32f5xx_dci.h + \brief definitions for the DCI + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_DCI_H +#define GD32F5XX_DCI_H + +#include "gd32f5xx.h" + +/* DCI definitions */ +#define DCI DCI_BASE + +/* registers definitions */ +#define DCI_CTL REG32(DCI + 0x00U) /*!< DCI control register */ +#define DCI_STAT0 REG32(DCI + 0x04U) /*!< DCI status register 0 */ +#define DCI_STAT1 REG32(DCI + 0x08U) /*!< DCI status register 1 */ +#define DCI_INTEN REG32(DCI + 0x0CU) /*!< DCI interrupt enable register */ +#define DCI_INTF REG32(DCI + 0x10U) /*!< DCI interrupt flag register */ +#define DCI_INTC REG32(DCI + 0x14U) /*!< DCI interrupt clear register */ +#define DCI_SC REG32(DCI + 0x18U) /*!< DCI synchronization codes register */ +#define DCI_SCUMSK REG32(DCI + 0x1CU) /*!< DCI synchronization codes unmask register */ +#define DCI_CWSPOS REG32(DCI + 0x20U) /*!< DCI cropping window start position register */ +#define DCI_CWSZ REG32(DCI + 0x24U) /*!< DCI cropping window size register */ +#define DCI_DATA REG32(DCI + 0x28U) /*!< DCI data register */ + +/* bits definitions */ +/* DCI_CTL */ +#define DCI_CTL_CAP BIT(0) /*!< capture enable */ +#define DCI_CTL_SNAP BIT(1) /*!< snapshot mode */ +#define DCI_CTL_WDEN BIT(2) /*!< window enable */ +#define DCI_CTL_JM BIT(3) /*!< JPEG mode */ +#define DCI_CTL_ESM BIT(4) /*!< embedded synchronous mode */ +#define DCI_CTL_CKS BIT(5) /*!< clock polarity selection */ +#define DCI_CTL_HPS BIT(6) /*!< horizontal polarity selection */ +#define DCI_CTL_VPS BIT(7) /*!< vertical polarity selection */ +#define DCI_CTL_FR BITS(8,9) /*!< frame rate */ +#define DCI_CTL_DCIF BITS(10,11) /*!< digital camera interface format */ +#define DCI_CTL_DCIEN BIT(14) /*!< DCI enable */ + +/* DCI_STAT0 */ +#define DCI_STAT0_HS BIT(0) /*!< HS line status */ +#define DCI_STAT0_VS BIT(1) /*!< VS line status */ +#define DCI_STAT0_FV BIT(2) /*!< FIFO valid */ + +/* DCI_STAT1 */ +#define DCI_STAT1_EFF BIT(0) /*!< end of frame flag */ +#define DCI_STAT1_OVRF BIT(1) /*!< FIFO overrun flag */ +#define DCI_STAT1_ESEF BIT(2) /*!< embedded synchronous error flag */ +#define DCI_STAT1_VSF BIT(3) /*!< vsync flag */ +#define DCI_STAT1_ELF BIT(4) /*!< end of line flag */ + +/* DCI_INTEN */ +#define DCI_INTEN_EFIE BIT(0) /*!< end of frame interrupt enable */ +#define DCI_INTEN_OVRIE BIT(1) /*!< FIFO overrun interrupt enable */ +#define DCI_INTEN_ESEIE BIT(2) /*!< embedded synchronous error interrupt enable */ +#define DCI_INTEN_VSIE BIT(3) /*!< vsync interrupt enable */ +#define DCI_INTEN_ELIE BIT(4) /*!< end of line interrupt enable */ + +/* DCI_INTF */ +#define DCI_INTF_EFIF BIT(0) /*!< end of frame interrupt flag */ +#define DCI_INTF_OVRIF BIT(1) /*!< FIFO overrun interrupt flag */ +#define DCI_INTF_ESEIF BIT(2) /*!< embedded synchronous error interrupt flag */ +#define DCI_INTF_VSIF BIT(3) /*!< vsync interrupt flag */ +#define DCI_INTF_ELIF BIT(4) /*!< end of line interrupt flag */ + +/* DCI_INTC */ +#define DCI_INTC_EFFC BIT(0) /*!< clear end of frame flag */ +#define DCI_INTC_OVRFC BIT(1) /*!< clear FIFO overrun flag */ +#define DCI_INTC_ESEFC BIT(2) /*!< clear embedded synchronous error flag */ +#define DCI_INTC_VSFC BIT(3) /*!< vsync flag clear */ +#define DCI_INTC_ELFC BIT(4) /*!< end of line flag clear */ + +/* DCI_SC */ +#define DCI_SC_FS BITS(0,7) /*!< frame start code in embedded synchronous mode */ +#define DCI_SC_LS BITS(8,15) /*!< line start code in embedded synchronous mode */ +#define DCI_SC_LE BITS(16,23) /*!< line end code in embedded synchronous mode */ +#define DCI_SC_FE BITS(24,31) /*!< frame end code in embedded synchronous mode */ + +/* DCI_SCUNMSK */ +#define DCI_SCUMSK_FSM BITS(0,7) /*!< frame start code unmask bits in embedded synchronous mode */ +#define DCI_SCUMSK_LSM BITS(8,15) /*!< line start code unmask bits in embedded synchronous mode */ +#define DCI_SCUMSK_LEM BITS(16,23) /*!< line end code unmask bits in embedded synchronous mode */ +#define DCI_SCUMSK_FEM BITS(24,31) /*!< frame end code unmask bits in embedded synchronous mode */ + +/* DCI_CWSPOS */ +#define DCI_CWSPOS_WHSP BITS(0,13) /*!< window horizontal start position */ +#define DCI_CWSPOS_WVSP BITS(16,28) /*!< window vertical start position */ + +/* DCI_CWSZ */ +#define DCI_CWSZ_WHSZ BITS(0,13) /*!< window horizontal size */ +#define DCI_CWSZ_WVSZ BITS(16,29) /*!< window vertical size */ + +/* constants definitions */ +/* DCI parameter structure definitions */ +typedef struct +{ + uint32_t capture_mode; /*!< DCI capture mode: continuous or snapshot */ + uint32_t clock_polarity; /*!< clock polarity selection */ + uint32_t hsync_polarity; /*!< horizontal polarity selection */ + uint32_t vsync_polarity; /*!< vertical polarity selection */ + uint32_t frame_rate; /*!< frame capture rate */ + uint32_t interface_format; /*!< digital camera interface format */ +}dci_parameter_struct; + +#define DCI_CAPTURE_MODE_CONTINUOUS ((uint32_t)0x00000000U) /*!< continuous capture mode */ +#define DCI_CAPTURE_MODE_SNAPSHOT DCI_CTL_SNAP /*!< snapshot capture mode */ + +#define DCI_CK_POLARITY_FALLING ((uint32_t)0x00000000U) /*!< capture at falling edge */ +#define DCI_CK_POLARITY_RISING DCI_CTL_CKS /*!< capture at rising edge */ + +#define DCI_HSYNC_POLARITY_LOW ((uint32_t)0x00000000U) /*!< low level during blanking period */ +#define DCI_HSYNC_POLARITY_HIGH DCI_CTL_HPS /*!< high level during blanking period */ + +#define DCI_VSYNC_POLARITY_LOW ((uint32_t)0x00000000U) /*!< low level during blanking period */ +#define DCI_VSYNC_POLARITY_HIGH DCI_CTL_VPS /*!< high level during blanking period*/ + +#define CTL_FR(regval) (BITS(8,9)&((uint32_t)(regval) << 8U)) +#define DCI_FRAME_RATE_ALL CTL_FR(0) /*!< capture all frames */ +#define DCI_FRAME_RATE_1_2 CTL_FR(1) /*!< capture one in 2 frames */ +#define DCI_FRAME_RATE_1_4 CTL_FR(2) /*!< capture one in 4 frames */ + +#define CTL_DCIF(regval) (BITS(10,11)&((uint32_t)(regval) << 10U)) +#define DCI_INTERFACE_FORMAT_8BITS CTL_DCIF(0) /*!< 8-bit data on every pixel clock */ +#define DCI_INTERFACE_FORMAT_10BITS CTL_DCIF(1) /*!< 10-bit data on every pixel clock */ +#define DCI_INTERFACE_FORMAT_12BITS CTL_DCIF(2) /*!< 12-bit data on every pixel clock */ +#define DCI_INTERFACE_FORMAT_14BITS CTL_DCIF(3) /*!< 14-bit data on every pixel clock */ + +/* DCI interrupt constants definitions */ +#define DCI_INT_EF BIT(0) /*!< end of frame interrupt */ +#define DCI_INT_OVR BIT(1) /*!< FIFO overrun interrupt */ +#define DCI_INT_ESE BIT(2) /*!< embedded synchronous error interrupt */ +#define DCI_INT_VSYNC BIT(3) /*!< vsync interrupt */ +#define DCI_INT_EL BIT(4) /*!< end of line interrupt */ + +/* DCI interrupt flag definitions */ +#define DCI_INT_FLAG_EF BIT(0) /*!< end of frame interrupt flag */ +#define DCI_INT_FLAG_OVR BIT(1) /*!< FIFO overrun interrupt flag */ +#define DCI_INT_FLAG_ESE BIT(2) /*!< embedded synchronous error interrupt flag */ +#define DCI_INT_FLAG_VSYNC BIT(3) /*!< vsync interrupt flag */ +#define DCI_INT_FLAG_EL BIT(4) /*!< end of line interrupt flag */ + +/* DCI flag definitions */ +#define DCI_FLAG_HS DCI_STAT0_HS /*!< HS line status */ +#define DCI_FLAG_VS DCI_STAT0_VS /*!< VS line status */ +#define DCI_FLAG_FV DCI_STAT0_FV /*!< FIFO valid */ +#define DCI_FLAG_EF (DCI_STAT1_EFF | BIT(31)) /*!< end of frame flag */ +#define DCI_FLAG_OVR (DCI_STAT1_OVRF | BIT(31)) /*!< FIFO overrun flag */ +#define DCI_FLAG_ESE (DCI_STAT1_ESEF | BIT(31)) /*!< embedded synchronous error flag */ +#define DCI_FLAG_VSYNC (DCI_STAT1_VSF | BIT(31)) /*!< vsync flag */ +#define DCI_FLAG_EL (DCI_STAT1_ELF | BIT(31)) /*!< end of line flag */ + +/* function declarations */ +/* initialization functions */ +/* DCI deinit */ +void dci_deinit(void); +/* initialize DCI registers */ +void dci_init(dci_parameter_struct* dci_struct); + +/* enable DCI function */ +void dci_enable(void); +/* disable DCI function */ +void dci_disable(void); +/* enable DCI capture */ +void dci_capture_enable(void); +/* disable DCI capture */ +void dci_capture_disable(void); +/* enable DCI jpeg mode */ +void dci_jpeg_enable(void); +/* disable DCI jpeg mode */ +void dci_jpeg_disable(void); + +/* function configuration */ +/* enable cropping window function */ +void dci_crop_window_enable(void); +/* disable cropping window function */ +void dci_crop_window_disable(void); +/* configure DCI cropping window */ +void dci_crop_window_config(uint16_t start_x, uint16_t start_y, uint16_t size_width, uint16_t size_height); + +/* enable embedded synchronous mode */ +void dci_embedded_sync_enable(void); +/* disable embedded synchronous mode */ +void dci_embedded_sync_disable(void); +/* configure synchronous codes in embedded synchronous mode */ +void dci_sync_codes_config(uint8_t frame_start, uint8_t line_start, uint8_t line_end, uint8_t frame_end); +/* configure synchronous codes unmask in embedded synchronous mode */ +void dci_sync_codes_unmask_config(uint8_t frame_start, uint8_t line_start, uint8_t line_end, uint8_t frame_end); + +/* read DCI data register */ +uint32_t dci_data_read(void); + +/* interrupt & flag functions */ +/* get specified flag */ +FlagStatus dci_flag_get(uint32_t flag); +/* enable specified DCI interrupt */ +void dci_interrupt_enable(uint32_t interrupt); +/* disable specified DCI interrupt */ +void dci_interrupt_disable(uint32_t interrupt); + + +/* get specified interrupt flag */ +FlagStatus dci_interrupt_flag_get(uint32_t int_flag); +/* clear specified interrupt flag */ +void dci_interrupt_flag_clear(uint32_t int_flag); + +#endif /* GD32F5XX_DCI_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dma.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dma.h new file mode 100644 index 0000000..d46b240 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_dma.h @@ -0,0 +1,433 @@ +/*! + \file gd32f5xx_dma.h + \brief definitions for the DMA + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_DMA_H +#define GD32F5XX_DMA_H + +#include "gd32f5xx.h" + +/* DMA definitions */ +#define DMA0 (DMA_BASE) /*!< DMA0 base address */ +#define DMA1 (DMA_BASE + 0x00000400U) /*!< DMA1 base address */ + +/* registers definitions */ +#define DMA_INTF0(dmax) REG32((dmax) + 0x00000000U) /*!< DMA interrupt flag register 0 */ +#define DMA_INTF1(dmax) REG32((dmax) + 0x00000004U) /*!< DMA interrupt flag register 1 */ +#define DMA_INTC0(dmax) REG32((dmax) + 0x00000008U) /*!< DMA interrupt flag clear register 0 */ +#define DMA_INTC1(dmax) REG32((dmax) + 0x0000000CU) /*!< DMA interrupt flag clear register 1 */ + +#define DMA_CH0CTL(dmax) REG32((dmax) + 0x00000010U) /*!< DMA channel 0 control register */ +#define DMA_CH0CNT(dmax) REG32((dmax) + 0x00000014U) /*!< DMA channel 0 counter register */ +#define DMA_CH0PADDR(dmax) REG32((dmax) + 0x00000018U) /*!< DMA channel 0 peripheral base address register */ +#define DMA_CH0M0ADDR(dmax) REG32((dmax) + 0x0000001CU) /*!< DMA channel 0 memory 0 base address register */ +#define DMA_CH0M1ADDR(dmax) REG32((dmax) + 0x00000020U) /*!< DMA channel 0 memory 1 base address register */ +#define DMA_CH0FCTL(dmax) REG32((dmax) + 0x00000024U) /*!< DMA channel 0 FIFO control register */ + +#define DMA_CH1CTL(dmax) REG32((dmax) + 0x00000028U) /*!< DMA channel 1 control register */ +#define DMA_CH1CNT(dmax) REG32((dmax) + 0x0000002CU) /*!< DMA channel 1 counter register */ +#define DMA_CH1PADDR(dmax) REG32((dmax) + 0x00000030U) /*!< DMA channel 1 peripheral base address register */ +#define DMA_CH1M0ADDR(dmax) REG32((dmax) + 0x00000034U) /*!< DMA channel 1 memory 0 base address register */ +#define DMA_CH1M1ADDR(dmax) REG32((dmax) + 0x00000038U) /*!< DMA channel 1 memory 1 base address register */ +#define DMA_CH1FCTL(dmax) REG32((dmax) + 0x0000003CU) /*!< DMA channel 1 FIFO control register */ + +#define DMA_CH2CTL(dmax) REG32((dmax) + 0x00000040U) /*!< DMA channel 2 control register */ +#define DMA_CH2CNT(dmax) REG32((dmax) + 0x00000044U) /*!< DMA channel 2 counter register */ +#define DMA_CH2PADDR(dmax) REG32((dmax) + 0x00000048U) /*!< DMA channel 2 peripheral base address register */ +#define DMA_CH2M0ADDR(dmax) REG32((dmax) + 0x0000004CU) /*!< DMA channel 2 memory 0 base address register */ +#define DMA_CH2M1ADDR(dmax) REG32((dmax) + 0x00000050U) /*!< DMA channel 2 memory 1 base address register */ +#define DMA_CH2FCTL(dmax) REG32((dmax) + 0x00000054U) /*!< DMA channel 2 FIFO control register */ + +#define DMA_CH3CTL(dmax) REG32((dmax) + 0x00000058U) /*!< DMA channel 3 control register */ +#define DMA_CH3CNT(dmax) REG32((dmax) + 0x0000005CU) /*!< DMA channel 3 counter register */ +#define DMA_CH3PADDR(dmax) REG32((dmax) + 0x00000060U) /*!< DMA channel 3 peripheral base address register */ +#define DMA_CH3M0ADDR(dmax) REG32((dmax) + 0x00000064U) /*!< DMA channel 3 memory 0 base address register */ +#define DMA_CH3M1ADDR(dmax) REG32((dmax) + 0x00000068U) /*!< DMA channel 3 memory 1 base address register */ +#define DMA_CH3FCTL(dmax) REG32((dmax) + 0x0000006CU) /*!< DMA channel 3 FIFO control register */ + +#define DMA_CH4CTL(dmax) REG32((dmax) + 0x00000070U) /*!< DMA channel 4 control register */ +#define DMA_CH4CNT(dmax) REG32((dmax) + 0x00000074U) /*!< DMA channel 4 counter register */ +#define DMA_CH4PADDR(dmax) REG32((dmax) + 0x00000078U) /*!< DMA channel 4 peripheral base address register */ +#define DMA_CH4M0ADDR(dmax) REG32((dmax) + 0x0000007CU) /*!< DMA channel 4 memory 0 base address register */ +#define DMA_CH4M1ADDR(dmax) REG32((dmax) + 0x00000080U) /*!< DMA channel 4 memory 1 base address register */ +#define DMA_CH4FCTL(dmax) REG32((dmax) + 0x00000084U) /*!< DMA channel 4 FIFO control register */ + +#define DMA_CH5CTL(dmax) REG32((dmax) + 0x00000088U) /*!< DMA channel 5 control register */ +#define DMA_CH5CNT(dmax) REG32((dmax) + 0x0000008CU) /*!< DMA channel 5 counter register */ +#define DMA_CH5PADDR(dmax) REG32((dmax) + 0x00000090U) /*!< DMA channel 5 peripheral base address register */ +#define DMA_CH5M0ADDR(dmax) REG32((dmax) + 0x00000094U) /*!< DMA channel 5 memory 0 base address register */ +#define DMA_CH5M1ADDR(dmax) REG32((dmax) + 0x00000098U) /*!< DMA channel 5 memory 1 base address register */ +#define DMA_CH5FCTL(dmax) REG32((dmax) + 0x0000009CU) /*!< DMA channel 5 FIFO control register */ + +#define DMA_CH6CTL(dmax) REG32((dmax) + 0x000000A0U) /*!< DMA channel 6 control register */ +#define DMA_CH6CNT(dmax) REG32((dmax) + 0x000000A4U) /*!< DMA channel 6 counter register */ +#define DMA_CH6PADDR(dmax) REG32((dmax) + 0x000000A8U) /*!< DMA channel 6 peripheral base address register */ +#define DMA_CH6M0ADDR(dmax) REG32((dmax) + 0x000000ACU) /*!< DMA channel 6 memory 0 base address register */ +#define DMA_CH6M1ADDR(dmax) REG32((dmax) + 0x000000B0U) /*!< DMA channel 6 memory 1 base address register */ +#define DMA_CH6FCTL(dmax) REG32((dmax) + 0x000000B4U) /*!< DMA channel 6 FIFO control register */ + +#define DMA_CH7CTL(dmax) REG32((dmax) + 0x000000B8U) /*!< DMA channel 7 control register */ +#define DMA_CH7CNT(dmax) REG32((dmax) + 0x000000BCU) /*!< DMA channel 7 counter register */ +#define DMA_CH7PADDR(dmax) REG32((dmax) + 0x000000C0U) /*!< DMA channel 7 peripheral base address register */ +#define DMA_CH7M0ADDR(dmax) REG32((dmax) + 0x000000C4U) /*!< DMA channel 7 memory 0 base address register */ +#define DMA_CH7M1ADDR(dmax) REG32((dmax) + 0x000000C8U) /*!< DMA channel 7 memory 1 base address register */ +#define DMA_CH7FCTL(dmax) REG32((dmax) + 0x000000CCU) /*!< DMA channel 7 FIFO control register */ + +/* bits definitions */ +/* DMA_INTF */ +#define DMA_INTF_FEEIF BIT(0) /*!< FIFO error and exception flag */ +#define DMA_INTF_SDEIF BIT(2) /*!< single data mode exception flag */ +#define DMA_INTF_TAEIF BIT(3) /*!< transfer access error flag */ +#define DMA_INTF_HTFIF BIT(4) /*!< half transfer finish flag */ +#define DMA_INTF_FTFIF BIT(5) /*!< full transger finish flag */ + +/* DMA_INTC */ +#define DMA_INTC_FEEIFC BIT(0) /*!< clear FIFO error and exception flag */ +#define DMA_INTC_SDEIFC BIT(2) /*!< clear single data mode exception flag */ +#define DMA_INTC_TAEIFC BIT(3) /*!< clear single data mode exception flag */ +#define DMA_INTC_HTFIFC BIT(4) /*!< clear half transfer finish flag */ +#define DMA_INTC_FTFIFC BIT(5) /*!< clear full transger finish flag */ + +/* DMA_CHxCTL,x=0..7 */ +#define DMA_CHXCTL_CHEN BIT(0) /*!< channel x enable */ +#define DMA_CHXCTL_SDEIE BIT(1) /*!< enable bit for channel x single data mode exception interrupt */ +#define DMA_CHXCTL_TAEIE BIT(2) /*!< enable bit for channel x tranfer access error interrupt */ +#define DMA_CHXCTL_HTFIE BIT(3) /*!< enable bit for channel x half transfer finish interrupt */ +#define DMA_CHXCTL_FTFIE BIT(4) /*!< enable bit for channel x full transfer finish interrupt */ +#define DMA_CHXCTL_TFCS BIT(5) /*!< transfer flow controller select */ +#define DMA_CHXCTL_TM BITS(6,7) /*!< transfer mode */ +#define DMA_CHXCTL_CMEN BIT(8) /*!< circulation mode */ +#define DMA_CHXCTL_PNAGA BIT(9) /*!< next address generation algorithm of peripheral */ +#define DMA_CHXCTL_MNAGA BIT(10) /*!< next address generation algorithm of memory */ +#define DMA_CHXCTL_PWIDTH BITS(11,12) /*!< transfer width of peipheral */ +#define DMA_CHXCTL_MWIDTH BITS(13,14) /*!< transfer width of memory */ +#define DMA_CHXCTL_PAIF BIT(15) /*!< peripheral address increment fixed */ +#define DMA_CHXCTL_PRIO BITS(16,17) /*!< priority level */ +#define DMA_CHXCTL_SBMEN BIT(18) /*!< switch-buffer mode enable */ +#define DMA_CHXCTL_MBS BIT(19) /*!< memory buffer select */ +#define DMA_CHXCTL_PBURST BITS(21,22) /*!< transfer burst type of peripheral */ +#define DMA_CHXCTL_MBURST BITS(23,24) /*!< transfer burst type of memory */ +#define DMA_CHXCTL_PERIEN BITS(25,27) /*!< peripheral enable */ + +/* DMA_CHxCNT,x=0..7 */ +#define DMA_CHXCNT_CNT BITS(0,15) /*!< transfer counter */ + +/* DMA_CHxPADDR,x=0..7 */ +#define DMA_CHXPADDR_PADDR BITS(0,31) /*!< peripheral base address */ + +/* DMA_CHxM0ADDR,x=0..7 */ +#define DMA_CHXM0ADDR_M0ADDR BITS(0,31) /*!< memory 0 base address */ + +/* DMA_CHxM1ADDR,x=0..7 */ +#define DMA_CHXM1ADDR_M0ADDR BITS(0,31) /*!< memory 1 base address */ + +/* DMA_CHxFCTL,x=0..7 */ +#define DMA_CHXFCTL_FCCV BITS(0,1) /*!< FIFO counter critical value */ +#define DMA_CHXFCTL_MDMEN BIT(2) /*!< multi-data mode enable */ +#define DMA_CHXFCTL_FCNT BITS(3,5) /*!< FIFO counter */ +#define DMA_CHXFCTL_FEEIE BIT(7) /*!< FIFO exception interrupt enable */ + +/* constants definitions */ +/* DMA channel select */ +typedef enum +{ + DMA_CH0 = 0, /*!< DMA Channel 0 */ + DMA_CH1, /*!< DMA Channel 1 */ + DMA_CH2, /*!< DMA Channel 2 */ + DMA_CH3, /*!< DMA Channel 3 */ + DMA_CH4, /*!< DMA Channel 4 */ + DMA_CH5, /*!< DMA Channel 5 */ + DMA_CH6, /*!< DMA Channel 6 */ + DMA_CH7 /*!< DMA Channel 7 */ +} dma_channel_enum; + +/* DMA peripheral select */ +typedef enum +{ + DMA_SUBPERI0 = 0, /*!< DMA Peripheral 0 */ + DMA_SUBPERI1, /*!< DMA Peripheral 1 */ + DMA_SUBPERI2, /*!< DMA Peripheral 2 */ + DMA_SUBPERI3, /*!< DMA Peripheral 3 */ + DMA_SUBPERI4, /*!< DMA Peripheral 4 */ + DMA_SUBPERI5, /*!< DMA Peripheral 5 */ + DMA_SUBPERI6, /*!< DMA Peripheral 6 */ + DMA_SUBPERI7 /*!< DMA Peripheral 7 */ +} dma_subperipheral_enum; + +/* DMA multidata mode initialize struct */ +typedef struct +{ + uint32_t periph_addr; /*!< peripheral base address */ + uint32_t periph_width; /*!< transfer data size of peripheral */ + uint32_t periph_inc; /*!< peripheral increasing mode */ + + uint32_t memory0_addr; /*!< memory 0 base address */ + uint32_t memory_width; /*!< transfer data size of memory */ + uint32_t memory_inc; /*!< memory increasing mode */ + + uint32_t memory_burst_width; /*!< multi data mode enable */ + uint32_t periph_burst_width; /*!< multi data mode enable */ + uint32_t critical_value; /*!< FIFO critical */ + + uint32_t circular_mode; /*!< DMA circular mode */ + uint32_t direction; /*!< channel data transfer direction */ + uint32_t number; /*!< channel transfer number */ + uint32_t priority; /*!< channel priority level */ +}dma_multi_data_parameter_struct; + +/* DMA singledata mode initialize struct */ +typedef struct +{ + uint32_t periph_addr; /*!< peripheral base address */ + uint32_t periph_inc; /*!< peripheral increasing mode */ + + uint32_t memory0_addr; /*!< memory 0 base address */ + uint32_t memory_inc; /*!< memory increasing mode */ + + uint32_t periph_memory_width; /*!< transfer data size of peripheral */ + + uint32_t circular_mode; /*!< DMA circular mode */ + uint32_t direction; /*!< channel data transfer direction */ + uint32_t number; /*!< channel transfer number */ + uint32_t priority; /*!< channel priority level */ +} dma_single_data_parameter_struct; + +#define DMA_FLAG_ADD(flag,channel) ((uint32_t)((flag)<<((((uint32_t)(channel)*6U))+((uint32_t)(((uint32_t)(channel)) >> 1U)&0x01U)*4U))) /*!< DMA channel flag shift */ + +/* DMA_register address */ +#define DMA_CHCTL(dma,channel) REG32(((dma) + 0x10U) + 0x18U*(channel)) /*!< the address of DMA channel CHXCTL register */ +#define DMA_CHCNT(dma,channel) REG32(((dma) + 0x14U) + 0x18U*(channel)) /*!< the address of DMA channel CHXCNT register */ +#define DMA_CHPADDR(dma,channel) REG32(((dma) + 0x18U) + 0x18U*(channel)) /*!< the address of DMA channel CHXPADDR register */ +#define DMA_CHM0ADDR(dma,channel) REG32(((dma) + 0x1CU) + 0x18U*(channel)) /*!< the address of DMA channel CHXM0ADDR register */ +#define DMA_CHM1ADDR(dma,channel) REG32(((dma) + 0x20U) + 0x18U*(channel)) /*!< the address of DMA channel CHXM1ADDR register */ +#define DMA_CHFCTL(dma,channel) REG32(((dma) + 0x24U) + 0x18U*(channel)) /*!< the address of DMA channel CHXMADDR register */ + +/* peripheral select */ +#define CHCTL_PERIEN(regval) (BITS(25,27) & ((uint32_t)(regval) << 25)) +#define DMA_PERIPH_0_SELECT CHCTL_PERIEN(0) /*!< peripheral 0 select */ +#define DMA_PERIPH_1_SELECT CHCTL_PERIEN(1) /*!< peripheral 1 select */ +#define DMA_PERIPH_2_SELECT CHCTL_PERIEN(2) /*!< peripheral 2 select */ +#define DMA_PERIPH_3_SELECT CHCTL_PERIEN(3) /*!< peripheral 3 select */ +#define DMA_PERIPH_4_SELECT CHCTL_PERIEN(4) /*!< peripheral 4 select */ +#define DMA_PERIPH_5_SELECT CHCTL_PERIEN(5) /*!< peripheral 5 select */ +#define DMA_PERIPH_6_SELECT CHCTL_PERIEN(6) /*!< peripheral 6 select */ +#define DMA_PERIPH_7_SELECT CHCTL_PERIEN(7) /*!< peripheral 7 select */ + +/* burst type of memory */ +#define CHCTL_MBURST(regval) (BITS(23,24) & ((uint32_t)(regval) << 23)) +#define DMA_MEMORY_BURST_SINGLE CHCTL_MBURST(0) /*!< single burst */ +#define DMA_MEMORY_BURST_4_BEAT CHCTL_MBURST(1) /*!< 4-beat burst */ +#define DMA_MEMORY_BURST_8_BEAT CHCTL_MBURST(2) /*!< 8-beat burst */ +#define DMA_MEMORY_BURST_16_BEAT CHCTL_MBURST(3) /*!< 16-beat burst */ + +/* burst type of peripheral */ +#define CHCTL_PBURST(regval) (BITS(21,22) & ((uint32_t)(regval) << 21)) +#define DMA_PERIPH_BURST_SINGLE CHCTL_PBURST(0) /*!< single burst */ +#define DMA_PERIPH_BURST_4_BEAT CHCTL_PBURST(1) /*!< 4-beat burst */ +#define DMA_PERIPH_BURST_8_BEAT CHCTL_PBURST(2) /*!< 8-beat burst */ +#define DMA_PERIPH_BURST_16_BEAT CHCTL_PBURST(3) /*!< 16-beat burst */ + +/* channel priority level */ +#define CHCTL_PRIO(regval) (BITS(16,17) & ((uint32_t)(regval) << 16)) +#define DMA_PRIORITY_LOW CHCTL_PRIO(0) /*!< low priority */ +#define DMA_PRIORITY_MEDIUM CHCTL_PRIO(1) /*!< medium priority */ +#define DMA_PRIORITY_HIGH CHCTL_PRIO(2) /*!< high priority */ +#define DMA_PRIORITY_ULTRA_HIGH CHCTL_PRIO(3) /*!< ultra high priority */ + +/* transfer data width of memory */ +#define CHCTL_MWIDTH(regval) (BITS(13,14) & ((uint32_t)(regval) << 13)) +#define DMA_MEMORY_WIDTH_8BIT CHCTL_MWIDTH(0) /*!< transfer data width of memory is 8-bit */ +#define DMA_MEMORY_WIDTH_16BIT CHCTL_MWIDTH(1) /*!< transfer data width of memory is 16-bit */ +#define DMA_MEMORY_WIDTH_32BIT CHCTL_MWIDTH(2) /*!< transfer data width of memory is 32-bit */ + +/* transfer data width of peripheral */ +#define CHCTL_PWIDTH(regval) (BITS(11,12) & ((uint32_t)(regval) << 11)) +#define DMA_PERIPH_WIDTH_8BIT CHCTL_PWIDTH(0) /*!< transfer data width of peripheral is 8-bit */ +#define DMA_PERIPH_WIDTH_16BIT CHCTL_PWIDTH(1) /*!< transfer data width of peripheral is 16-bit */ +#define DMA_PERIPH_WIDTH_32BIT CHCTL_PWIDTH(2) /*!< transfer data width of peripheral is 32-bit */ + +/* channel transfer mode */ +#define CHCTL_TM(regval) (BITS(6,7) & ((uint32_t)(regval) << 6)) +#define DMA_PERIPH_TO_MEMORY CHCTL_TM(0) /*!< read from peripheral and write to memory */ +#define DMA_MEMORY_TO_PERIPH CHCTL_TM(1) /*!< read from memory and write to peripheral */ +#define DMA_MEMORY_TO_MEMORY CHCTL_TM(2) /*!< read from memory and write to memory */ + +/* FIFO counter critical value */ +#define CHFCTL_FCCV(regval) (BITS(0,1) & ((uint32_t)(regval) << 0)) +#define DMA_FIFO_1_WORD CHFCTL_FCCV(0) /*!< critical value 1 word */ +#define DMA_FIFO_2_WORD CHFCTL_FCCV(1) /*!< critical value 2 word */ +#define DMA_FIFO_3_WORD CHFCTL_FCCV(2) /*!< critical value 3 word */ +#define DMA_FIFO_4_WORD CHFCTL_FCCV(3) /*!< critical value 4 word */ + +/* memory select */ +#define DMA_MEMORY_0 ((uint32_t)0x00000000U) /*!< select memory 0 */ +#define DMA_MEMORY_1 ((uint32_t)0x00000001U) /*!< select memory 1 */ + +/* DMA circular mode */ +#define DMA_CIRCULAR_MODE_ENABLE ((uint32_t)0x00000000U) /*!< circular mode enable */ +#define DMA_CIRCULAR_MODE_DISABLE ((uint32_t)0x00000001U) /*!< circular mode disable */ + +/* DMA flow controller select */ +#define DMA_FLOW_CONTROLLER_DMA ((uint32_t)0x00000000U) /*!< DMA is the flow controler */ +#define DMA_FLOW_CONTROLLER_PERI ((uint32_t)0x00000001U) /*!< peripheral is the flow controler */ + +/* peripheral increasing mode */ +#define DMA_PERIPH_INCREASE_ENABLE ((uint32_t)0x00000000U) /*!< next address of peripheral is increasing address mode */ +#define DMA_PERIPH_INCREASE_DISABLE ((uint32_t)0x00000001U) /*!< next address of peripheral is fixed address mode */ +#define DMA_PERIPH_INCREASE_FIX ((uint32_t)0x00000002U) /*!< next address of peripheral is increasing fixed */ + +/* memory increasing mode */ +#define DMA_MEMORY_INCREASE_ENABLE ((uint32_t)0x00000000U) /*!< next address of memory is increasing address mode */ +#define DMA_MEMORY_INCREASE_DISABLE ((uint32_t)0x00000001U) /*!< next address of memory is fixed address mode */ + +/* FIFO status */ +#define DMA_FIFO_STATUS_NODATA ((uint32_t)0x00000000U) /*!< the data in the FIFO less than 1 word */ +#define DMA_FIFO_STATUS_1_WORD ((uint32_t)0x00000001U) /*!< the data in the FIFO more than 1 word, less than 2 words */ +#define DMA_FIFO_STATUS_2_WORD ((uint32_t)0x00000002U) /*!< the data in the FIFO more than 2 word, less than 3 words */ +#define DMA_FIFO_STATUS_3_WORD ((uint32_t)0x00000003U) /*!< the data in the FIFO more than 3 word, less than 4 words */ +#define DMA_FIFO_STATUS_EMPTY ((uint32_t)0x00000004U) /*!< the data in the FIFO is empty */ +#define DMA_FIFO_STATUS_FULL ((uint32_t)0x00000005U) /*!< the data in the FIFO is full */ + +/* DMA reset value */ +#define DMA_CHCTL_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXCTL register */ +#define DMA_CHCNT_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXCNT register */ +#define DMA_CHPADDR_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXPADDR register */ +#define DMA_CHMADDR_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXMADDR register */ +#define DMA_CHINTF_RESET_VALUE ((uint32_t)0x0000003DU) /*!< clear DMA channel CHXINTFS register */ +#define DMA_CHFCTL_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXFCTL register */ + +/* DMA_INTF register */ +/* interrupt flag bits */ +#define DMA_INT_FLAG_FEE DMA_INTF_FEEIF /*!< FIFO error and exception flag */ +#define DMA_INT_FLAG_SDE DMA_INTF_SDEIF /*!< single data mode exception flag */ +#define DMA_INT_FLAG_TAE DMA_INTF_TAEIF /*!< transfer access error flag */ +#define DMA_INT_FLAG_HTF DMA_INTF_HTFIF /*!< half transfer finish flag */ +#define DMA_INT_FLAG_FTF DMA_INTF_FTFIF /*!< full transfer finish flag */ + +/* flag bits */ +#define DMA_FLAG_FEE DMA_INTF_FEEIF /*!< FIFO error and exception flag */ +#define DMA_FLAG_SDE DMA_INTF_SDEIF /*!< single data mode exception flag */ +#define DMA_FLAG_TAE DMA_INTF_TAEIF /*!< transfer access error flag */ +#define DMA_FLAG_HTF DMA_INTF_HTFIF /*!< half transfer finish flag */ +#define DMA_FLAG_FTF DMA_INTF_FTFIF /*!< full transfer finish flag */ + +/* DMA_CHxCTL register */ +/* interrupt enable bits */ +#define DMA_INT_SDE DMA_CHXCTL_SDEIE /*!< enable bit for channel x single data mode exception interrupt */ +#define DMA_INT_TAE DMA_CHXCTL_TAEIE /*!< enable bit for channel x tranfer access error interrupt */ +#define DMA_INT_HTF DMA_CHXCTL_HTFIE /*!< enable bit for channel x half transfer finish interrupt */ +#define DMA_INT_FTF DMA_CHXCTL_FTFIE /*!< enable bit for channel x full transfer finish interrupt */ +#define DMA_INT_FEE DMA_CHXFCTL_FEEIE /*!< FIFO exception interrupt enable */ + +/* function declarations */ +/* DMA deinitialization and initialization functions */ +/* deinitialize DMA a channel registers */ +void dma_deinit(uint32_t dma_periph, dma_channel_enum channelx); +/* initialize the DMA single data mode parameters struct with the default values */ +void dma_single_data_para_struct_init(dma_single_data_parameter_struct* init_struct); +/* initialize the DMA multi data mode parameters struct with the default values */ +void dma_multi_data_para_struct_init(dma_multi_data_parameter_struct* init_struct); +/* DMA single data mode initialize */ +void dma_single_data_mode_init(uint32_t dma_periph, dma_channel_enum channelx, dma_single_data_parameter_struct* init_struct); +/* DMA multi data mode initialize */ +void dma_multi_data_mode_init(uint32_t dma_periph, dma_channel_enum channelx, dma_multi_data_parameter_struct* init_struct); + +/* DMA configuration functions */ +/* set DMA peripheral base address */ +void dma_periph_address_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t address); +/* set DMA Memory base address */ +void dma_memory_address_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t memory_flag, uint32_t address); + +/* set the number of remaining data to be transferred by the DMA */ +void dma_transfer_number_config(uint32_t dma_periph,dma_channel_enum channelx, uint32_t number); +/* get the number of remaining data to be transferred by the DMA */ +uint32_t dma_transfer_number_get(uint32_t dma_periph, dma_channel_enum channelx); + +/* configure priority level of DMA channel */ +void dma_priority_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t priority); + +/* configure transfer burst beats of memory */ +void dma_memory_burst_beats_config (uint32_t dma_periph, dma_channel_enum channelx, uint32_t mbeat); +/* configure transfer burst beats of peripheral */ +void dma_periph_burst_beats_config (uint32_t dma_periph, dma_channel_enum channelx, uint32_t pbeat); +/* configure transfer data size of memory */ +void dma_memory_width_config (uint32_t dma_periph, dma_channel_enum channelx, uint32_t msize); +/* configure transfer data size of peripheral */ +void dma_periph_width_config (uint32_t dma_periph, dma_channel_enum channelx, uint32_t psize); + +/* configure next address increasement algorithm of memory */ +void dma_memory_address_generation_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t generation_algorithm); +/* configure next address increasement algorithm of peripheral */ +void dma_peripheral_address_generation_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t generation_algorithm); + +/* enable DMA circulation mode */ +void dma_circulation_enable(uint32_t dma_periph, dma_channel_enum channelx); +/* disable DMA circulation mode */ +void dma_circulation_disable(uint32_t dma_periph, dma_channel_enum channelx); +/* enable DMA channel */ +void dma_channel_enable(uint32_t dma_periph, dma_channel_enum channelx); +/* disable DMA channel */ +void dma_channel_disable(uint32_t dma_periph, dma_channel_enum channelx); + +/* configure the direction of data transfer on the channel */ +void dma_transfer_direction_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t direction); + +/* DMA switch buffer mode config */ +void dma_switch_buffer_mode_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t memory1_addr, uint32_t memory_select); +/* DMA using memory get */ +uint32_t dma_using_memory_get(uint32_t dma_periph, dma_channel_enum channelx); + +/* DMA channel peripheral select */ +void dma_channel_subperipheral_select(uint32_t dma_periph, dma_channel_enum channelx, dma_subperipheral_enum sub_periph); +/* DMA flow controller configure */ +void dma_flow_controller_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t controller); +/* DMA switch buffer mode enable */ +void dma_switch_buffer_mode_enable(uint32_t dma_periph, dma_channel_enum channelx, ControlStatus newvalue); +/* DMA FIFO status get */ +uint32_t dma_fifo_status_get(uint32_t dma_periph, dma_channel_enum channelx); + +/* flag and interrupt functions */ +/* check DMA flag is set or not */ +FlagStatus dma_flag_get(uint32_t dma_periph, dma_channel_enum channelx, uint32_t flag); +/* clear DMA a channel flag */ +void dma_flag_clear(uint32_t dma_periph, dma_channel_enum channelx, uint32_t flag); +/* enable DMA interrupt */ +void dma_interrupt_enable(uint32_t dma_periph, dma_channel_enum channelx, uint32_t interrupt); +/* disable DMA interrupt */ +void dma_interrupt_disable(uint32_t dma_periph, dma_channel_enum channelx, uint32_t interrupt); +/* get DMA interrupt flag is set or not */ +FlagStatus dma_interrupt_flag_get(uint32_t dma_periph, dma_channel_enum channelx, uint32_t interrupt); +/* clear DMA a channel interrupt flag */ +void dma_interrupt_flag_clear(uint32_t dma_periph, dma_channel_enum channelx, uint32_t interrupt); + +#endif /* GD32F5XX_DMA_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_enet.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_enet.h new file mode 100644 index 0000000..d53cca0 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_enet.h @@ -0,0 +1,1697 @@ +/*! + \file gd32f5xx_enet.h + \brief definitions for the ENET + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_ENET_H +#define GD32F5XX_ENET_H + +#include "gd32f5xx.h" +#include + +#define IF_USE_EXTERNPHY_LIB 0 +#if (1 == IF_USE_EXTERNPHY_LIB) +#include "phy.h" +#endif + +#ifndef ENET_RXBUF_NUM +#define ENET_RXBUF_NUM 5U /*!< ethernet Rx DMA descriptor number */ +#endif + +#ifndef ENET_TXBUF_NUM +#define ENET_TXBUF_NUM 5U /*!< ethernet Tx DMA descriptor number */ +#endif + +#ifndef ENET_RXBUF_SIZE +#define ENET_RXBUF_SIZE ENET_MAX_FRAME_SIZE /*!< ethernet receive buffer size */ +#endif + +#ifndef ENET_TXBUF_SIZE +#define ENET_TXBUF_SIZE ENET_MAX_FRAME_SIZE /*!< ethernet transmit buffer size */ +#endif + +//#define SELECT_DESCRIPTORS_ENHANCED_MODE + +//#define USE_DELAY + +#ifndef _PHY_H_ +#define DP83848 0 +#define LAN8700 1 +#define PHY_TYPE DP83848 + +#define PHY_ADDRESS ((uint16_t)1U) /*!< phy address determined by the hardware */ + +/* PHY read write timeouts */ +#define PHY_READ_TO ((uint32_t)0x0004FFFFU) /*!< PHY read timeout */ +#define PHY_WRITE_TO ((uint32_t)0x0004FFFFU) /*!< PHY write timeout */ + +/* PHY delay */ +#define PHY_RESETDELAY ((uint32_t)0x008FFFFFU) /*!< PHY reset delay */ +#define PHY_CONFIGDELAY ((uint32_t)0x00FFFFFFU) /*!< PHY configure delay */ + +/* PHY register address */ +#define PHY_REG_BCR 0U /*!< tranceiver basic control register */ +#define PHY_REG_BSR 1U /*!< tranceiver basic status register */ + +/* PHY basic control register */ +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< enable phy loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< configure speed to 100 Mbit/s and the full-duplex mode */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< configure speed to 100 Mbit/s and the half-duplex mode */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< configure speed to 10 Mbit/s and the full-duplex mode */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< configure speed to 10 Mbit/s and the half-duplex mode */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< enable the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< isolate PHY from MII */ + +/* PHY basic status register */ +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< auto-negotioation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< jabber condition detected */ + +#if(PHY_TYPE == LAN8700) +#define PHY_SR 31U /*!< tranceiver status register */ +#define PHY_SPEED_STATUS ((uint16_t)0x0004) /*!< configured information of speed: 10Mbit/s */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0010) /*!< configured information of duplex: full-duplex */ +#elif(PHY_TYPE == DP83848) +#define PHY_SR 16U /*!< tranceiver status register */ +#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< configured information of speed: 10Mbit/s */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< configured information of duplex: full-duplex */ +#endif /* PHY_TYPE */ + +#endif /* _PHY_H_ */ + + +/* ENET definitions */ +#define ENET ENET_BASE + +/* registers definitions */ +#define ENET_MAC_CFG REG32((ENET) + 0x00U) /*!< ethernet MAC configuration register */ +#define ENET_MAC_FRMF REG32((ENET) + 0x04U) /*!< ethernet MAC frame filter register */ +#define ENET_MAC_HLH REG32((ENET) + 0x08U) /*!< ethernet MAC hash list high register */ +#define ENET_MAC_HLL REG32((ENET) + 0x0CU) /*!< ethernet MAC hash list low register */ +#define ENET_MAC_PHY_CTL REG32((ENET) + 0x10U) /*!< ethernet MAC PHY control register */ +#define ENET_MAC_PHY_DATA REG32((ENET) + 0x14U) /*!< ethernet MAC PHY data register */ +#define ENET_MAC_FCTL REG32((ENET) + 0x18U) /*!< ethernet MAC flow control register */ +#define ENET_MAC_VLT REG32((ENET) + 0x1CU) /*!< ethernet MAC VLAN tag register */ +#define ENET_MAC_RWFF REG32((ENET) + 0x28U) /*!< ethernet MAC remote wakeup frame filter register */ +#define ENET_MAC_WUM REG32((ENET) + 0x2CU) /*!< ethernet MAC wakeup management register */ +#define ENET_MAC_DBG REG32((ENET) + 0x34U) /*!< ethernet MAC debug register */ +#define ENET_MAC_INTF REG32((ENET) + 0x38U) /*!< ethernet MAC interrupt flag register */ +#define ENET_MAC_INTMSK REG32((ENET) + 0x3CU) /*!< ethernet MAC interrupt mask register */ +#define ENET_MAC_ADDR0H REG32((ENET) + 0x40U) /*!< ethernet MAC address 0 high register */ +#define ENET_MAC_ADDR0L REG32((ENET) + 0x44U) /*!< ethernet MAC address 0 low register */ +#define ENET_MAC_ADDR1H REG32((ENET) + 0x48U) /*!< ethernet MAC address 1 high register */ +#define ENET_MAC_ADDR1L REG32((ENET) + 0x4CU) /*!< ethernet MAC address 1 low register */ +#define ENET_MAC_ADDT2H REG32((ENET) + 0x50U) /*!< ethernet MAC address 2 high register */ +#define ENET_MAC_ADDR2L REG32((ENET) + 0x54U) /*!< ethernet MAC address 2 low register */ +#define ENET_MAC_ADDR3H REG32((ENET) + 0x58U) /*!< ethernet MAC address 3 high register */ +#define ENET_MAC_ADDR3L REG32((ENET) + 0x5CU) /*!< ethernet MAC address 3 low register */ +#define ENET_MAC_FCTH REG32((ENET) + 0x1080U) /*!< ethernet MAC flow control threshold register */ + +#define ENET_MSC_CTL REG32((ENET) + 0x100U) /*!< ethernet MSC control register */ +#define ENET_MSC_RINTF REG32((ENET) + 0x104U) /*!< ethernet MSC receive interrupt flag register */ +#define ENET_MSC_TINTF REG32((ENET) + 0x108U) /*!< ethernet MSC transmit interrupt flag register */ +#define ENET_MSC_RINTMSK REG32((ENET) + 0x10CU) /*!< ethernet MSC receive interrupt mask register */ +#define ENET_MSC_TINTMSK REG32((ENET) + 0x110U) /*!< ethernet MSC transmit interrupt mask register */ +#define ENET_MSC_SCCNT REG32((ENET) + 0x14CU) /*!< ethernet MSC transmitted good frames after a single collision counter register */ +#define ENET_MSC_MSCCNT REG32((ENET) + 0x150U) /*!< ethernet MSC transmitted good frames after more than a single collision counter register */ +#define ENET_MSC_TGFCNT REG32((ENET) + 0x168U) /*!< ethernet MSC transmitted good frames counter register */ +#define ENET_MSC_RFCECNT REG32((ENET) + 0x194U) /*!< ethernet MSC received frames with CRC error counter register */ +#define ENET_MSC_RFAECNT REG32((ENET) + 0x198U) /*!< ethernet MSC received frames with alignment error counter register */ +#define ENET_MSC_RGUFCNT REG32((ENET) + 0x1C4U) /*!< ethernet MSC received good unicast frames counter register */ + +#define ENET_PTP_TSCTL REG32((ENET) + 0x700U) /*!< ethernet PTP time stamp control register */ +#define ENET_PTP_SSINC REG32((ENET) + 0x704U) /*!< ethernet PTP subsecond increment register */ +#define ENET_PTP_TSH REG32((ENET) + 0x708U) /*!< ethernet PTP time stamp high register */ +#define ENET_PTP_TSL REG32((ENET) + 0x70CU) /*!< ethernet PTP time stamp low register */ +#define ENET_PTP_TSUH REG32((ENET) + 0x710U) /*!< ethernet PTP time stamp update high register */ +#define ENET_PTP_TSUL REG32((ENET) + 0x714U) /*!< ethernet PTP time stamp update low register */ +#define ENET_PTP_TSADDEND REG32((ENET) + 0x718U) /*!< ethernet PTP time stamp addend register */ +#define ENET_PTP_ETH REG32((ENET) + 0x71CU) /*!< ethernet PTP expected time high register */ +#define ENET_PTP_ETL REG32((ENET) + 0x720U) /*!< ethernet PTP expected time low register */ +#define ENET_PTP_TSF REG32((ENET) + 0x728U) /*!< ethernet PTP time stamp flag register */ +#define ENET_PTP_PPSCTL REG32((ENET) + 0x72CU) /*!< ethernet PTP PPS control register */ + +#define ENET_DMA_BCTL REG32((ENET) + 0x1000U) /*!< ethernet DMA bus control register */ +#define ENET_DMA_TPEN REG32((ENET) + 0x1004U) /*!< ethernet DMA transmit poll enable register */ +#define ENET_DMA_RPEN REG32((ENET) + 0x1008U) /*!< ethernet DMA receive poll enable register */ +#define ENET_DMA_RDTADDR REG32((ENET) + 0x100CU) /*!< ethernet DMA receive descriptor table address register */ +#define ENET_DMA_TDTADDR REG32((ENET) + 0x1010U) /*!< ethernet DMA transmit descriptor table address register */ +#define ENET_DMA_STAT REG32((ENET) + 0x1014U) /*!< ethernet DMA status register */ +#define ENET_DMA_CTL REG32((ENET) + 0x1018U) /*!< ethernet DMA control register */ +#define ENET_DMA_INTEN REG32((ENET) + 0x101CU) /*!< ethernet DMA interrupt enable register */ +#define ENET_DMA_MFBOCNT REG32((ENET) + 0x1020U) /*!< ethernet DMA missed frame and buffer overflow counter register */ +#define ENET_DMA_RSWDC REG32((ENET) + 0x1024U) /*!< ethernet DMA receive state watchdog counter register */ +#define ENET_DMA_CTDADDR REG32((ENET) + 0x1048U) /*!< ethernet DMA current transmit descriptor address register */ +#define ENET_DMA_CRDADDR REG32((ENET) + 0x104CU) /*!< ethernet DMA current receive descriptor address register */ +#define ENET_DMA_CTBADDR REG32((ENET) + 0x1050U) /*!< ethernet DMA current transmit buffer address register */ +#define ENET_DMA_CRBADDR REG32((ENET) + 0x1054U) /*!< ethernet DMA current receive buffer address register */ + +/* bits definitions */ +/* ENET_MAC_CFG */ +#define ENET_MAC_CFG_REN BIT(2) /*!< receiver enable */ +#define ENET_MAC_CFG_TEN BIT(3) /*!< transmitter enable */ +#define ENET_MAC_CFG_DFC BIT(4) /*!< defferal check */ +#define ENET_MAC_CFG_BOL BITS(5,6) /*!< back-off limit */ +#define ENET_MAC_CFG_APCD BIT(7) /*!< automatic pad/CRC drop */ +#define ENET_MAC_CFG_RTD BIT(9) /*!< retry disable */ +#define ENET_MAC_CFG_IPFCO BIT(10) /*!< IP frame checksum offload */ +#define ENET_MAC_CFG_DPM BIT(11) /*!< duplex mode */ +#define ENET_MAC_CFG_LBM BIT(12) /*!< loopback mode */ +#define ENET_MAC_CFG_ROD BIT(13) /*!< receive own disable */ +#define ENET_MAC_CFG_SPD BIT(14) /*!< fast eneternet speed */ +#define ENET_MAC_CFG_CSD BIT(16) /*!< carrier sense disable */ +#define ENET_MAC_CFG_IGBS BITS(17,19) /*!< inter-frame gap bit selection */ +#define ENET_MAC_CFG_JBD BIT(22) /*!< jabber disable */ +#define ENET_MAC_CFG_WDD BIT(23) /*!< watchdog disable */ +#define ENET_MAC_CFG_TFCD BIT(25) /*!< type frame CRC dropping */ + +/* ENET_MAC_FRMF */ +#define ENET_MAC_FRMF_PM BIT(0) /*!< promiscuous mode */ +#define ENET_MAC_FRMF_HUF BIT(1) /*!< hash unicast filter */ +#define ENET_MAC_FRMF_HMF BIT(2) /*!< hash multicast filter */ +#define ENET_MAC_FRMF_DAIFLT BIT(3) /*!< destination address inverse filtering enable */ +#define ENET_MAC_FRMF_MFD BIT(4) /*!< multicast filter disable */ +#define ENET_MAC_FRMF_BFRMD BIT(5) /*!< broadcast frame disable */ +#define ENET_MAC_FRMF_PCFRM BITS(6,7) /*!< pass control frames */ +#define ENET_MAC_FRMF_SAIFLT BIT(8) /*!< source address inverse filtering */ +#define ENET_MAC_FRMF_SAFLT BIT(9) /*!< source address filter */ +#define ENET_MAC_FRMF_HPFLT BIT(10) /*!< hash or perfect filter */ +#define ENET_MAC_FRMF_FAR BIT(31) /*!< frames all receive */ + +/* ENET_MAC_HLH */ +#define ENET_MAC_HLH_HLH BITS(0,31) /*!< hash list high */ + +/* ENET_MAC_HLL */ +#define ENET_MAC_HLL_HLL BITS(0,31) /*!< hash list low */ + +/* ENET_MAC_PHY_CTL */ +#define ENET_MAC_PHY_CTL_PB BIT(0) /*!< PHY busy */ +#define ENET_MAC_PHY_CTL_PW BIT(1) /*!< PHY write */ +#define ENET_MAC_PHY_CTL_CLR BITS(2,4) /*!< clock range */ +#define ENET_MAC_PHY_CTL_PR BITS(6,10) /*!< PHY register */ +#define ENET_MAC_PHY_CTL_PA BITS(11,15) /*!< PHY address */ + +/* ENET_MAC_PHY_DATA */ +#define ENET_MAC_PHY_DATA_PD BITS(0,15) /*!< PHY data */ + +/* ENET_MAC_FCTL */ +#define ENET_MAC_FCTL_FLCBBKPA BIT(0) /*!< flow control busy(in full duplex mode)/backpressure activate(in half duplex mode) */ +#define ENET_MAC_FCTL_TFCEN BIT(1) /*!< transmit flow control enable */ +#define ENET_MAC_FCTL_RFCEN BIT(2) /*!< receive flow control enable */ +#define ENET_MAC_FCTL_UPFDT BIT(3) /*!< unicast pause frame detect */ +#define ENET_MAC_FCTL_PLTS BITS(4,5) /*!< pause low threshold */ +#define ENET_MAC_FCTL_DZQP BIT(7) /*!< disable zero-quanta pause */ +#define ENET_MAC_FCTL_PTM BITS(16,31) /*!< pause time */ + +/* ENET_MAC_VLT */ +#define ENET_MAC_VLT_VLTI BITS(0,15) /*!< VLAN tag identifier(for receive frames) */ +#define ENET_MAC_VLT_VLTC BIT(16) /*!< 12-bit VLAN tag comparison */ + +/* ENET_MAC_RWFF */ +#define ENET_MAC_RWFF_DATA BITS(0,31) /*!< wakeup frame filter register data */ + +/* ENET_MAC_WUM */ +#define ENET_MAC_WUM_PWD BIT(0) /*!< power down */ +#define ENET_MAC_WUM_MPEN BIT(1) /*!< magic packet enable */ +#define ENET_MAC_WUM_WFEN BIT(2) /*!< wakeup frame enable */ +#define ENET_MAC_WUM_MPKR BIT(5) /*!< magic packet received */ +#define ENET_MAC_WUM_WUFR BIT(6) /*!< wakeup frame received */ +#define ENET_MAC_WUM_GU BIT(9) /*!< global unicast */ +#define ENET_MAC_WUM_WUFFRPR BIT(31) /*!< wakeup frame filter register pointer reset */ + +/* ENET_MAC_DBG */ +#define ENET_MAC_DBG_MRNI BIT(0) /*!< MAC receive state not idle */ +#define ENET_MAC_DBG_RXAFS BITS(1,2) /*!< Rx asynchronous FIFO status */ +#define ENET_MAC_DBG_RXFW BIT(4) /*!< RxFIFO is writing */ +#define ENET_MAC_DBG_RXFRS BITS(5,6) /*!< RxFIFO read operation status */ +#define ENET_MAC_DBG_RXFS BITS(8,9) /*!< RxFIFO state */ +#define ENET_MAC_DBG_MTNI BIT(16) /*!< MAC transmit state not idle */ +#define ENET_MAC_DBG_SOMT BITS(17,18) /*!< status of mac transmitter */ +#define ENET_MAC_DBG_PCS BIT(19) /*!< pause condition status */ +#define ENET_MAC_DBG_TXFRS BITS(20,21) /*!< TxFIFO read operation status */ +#define ENET_MAC_DBG_TXFW BIT(22) /*!< TxFIFO is writing */ +#define ENET_MAC_DBG_TXFNE BIT(24) /*!< TxFIFO not empty flag */ +#define ENET_MAC_DBG_TXFF BIT(25) /*!< TxFIFO full flag */ + +/* ENET_MAC_INTF */ +#define ENET_MAC_INTF_WUM BIT(3) /*!< WUM status */ +#define ENET_MAC_INTF_MSC BIT(4) /*!< MSC status */ +#define ENET_MAC_INTF_MSCR BIT(5) /*!< MSC receive status */ +#define ENET_MAC_INTF_MSCT BIT(6) /*!< MSC transmit status */ +#define ENET_MAC_INTF_TMST BIT(9) /*!< timestamp trigger status */ + +/* ENET_MAC_INTMSK */ +#define ENET_MAC_INTMSK_WUMIM BIT(3) /*!< WUM interrupt mask */ +#define ENET_MAC_INTMSK_TMSTIM BIT(9) /*!< timestamp trigger interrupt mask */ + +/* ENET_MAC_ADDR0H */ +#define ENET_MAC_ADDR0H_ADDR0H BITS(0,15) /*!< MAC address0 high */ +#define ENET_MAC_ADDR0H_MO BIT(31) /*!< always read 1 and must be kept */ + +/* ENET_MAC_ADDR0L */ +#define ENET_MAC_ADDR0L_ADDR0L BITS(0,31) /*!< MAC address0 low */ + +/* ENET_MAC_ADDR1H */ +#define ENET_MAC_ADDR1H_ADDR1H BITS(0,15) /*!< MAC address1 high */ +#define ENET_MAC_ADDR1H_MB BITS(24,29) /*!< mask byte */ +#define ENET_MAC_ADDR1H_SAF BIT(30) /*!< source address filter */ +#define ENET_MAC_ADDR1H_AFE BIT(31) /*!< address filter enable */ + +/* ENET_MAC_ADDR1L */ +#define ENET_MAC_ADDR1L_ADDR1L BITS(0,31) /*!< MAC address1 low */ + +/* ENET_MAC_ADDR2H */ +#define ENET_MAC_ADDR2H_ADDR2H BITS(0,15) /*!< MAC address2 high */ +#define ENET_MAC_ADDR2H_MB BITS(24,29) /*!< mask byte */ +#define ENET_MAC_ADDR2H_SAF BIT(30) /*!< source address filter */ +#define ENET_MAC_ADDR2H_AFE BIT(31) /*!< address filter enable */ + +/* ENET_MAC_ADDR2L */ +#define ENET_MAC_ADDR2L_ADDR2L BITS(0,31) /*!< MAC address2 low */ + +/* ENET_MAC_ADDR3H */ +#define ENET_MAC_ADDR3H_ADDR3H BITS(0,15) /*!< MAC address3 high */ +#define ENET_MAC_ADDR3H_MB BITS(24,29) /*!< mask byte */ +#define ENET_MAC_ADDR3H_SAF BIT(30) /*!< source address filter */ +#define ENET_MAC_ADDR3H_AFE BIT(31) /*!< address filter enable */ + +/* ENET_MAC_ADDR3L */ +#define ENET_MAC_ADDR3L_ADDR3L BITS(0,31) /*!< MAC address3 low */ + +/* ENET_MAC_FCTH */ +#define ENET_MAC_FCTH_RFA BITS(0,2) /*!< threshold of active flow control */ +#define ENET_MAC_FCTH_RFD BITS(4,6) /*!< threshold of deactive flow control */ + +/* ENET_MSC_CTL */ +#define ENET_MSC_CTL_CTR BIT(0) /*!< counter reset */ +#define ENET_MSC_CTL_CTSR BIT(1) /*!< counter stop rollover */ +#define ENET_MSC_CTL_RTOR BIT(2) /*!< reset on read */ +#define ENET_MSC_CTL_MCFZ BIT(3) /*!< MSC counter freeze */ +#define ENET_MSC_CTL_PMC BIT(4) /*!< preset MSC counter */ +#define ENET_MSC_CTL_AFHPM BIT(5) /*!< almost full or half preset mode */ + +/* ENET_MSC_RINTF */ +#define ENET_MSC_RINTF_RFCE BIT(5) /*!< received frames CRC error */ +#define ENET_MSC_RINTF_RFAE BIT(6) /*!< received frames alignment error */ +#define ENET_MSC_RINTF_RGUF BIT(17) /*!< receive good unicast frames */ + +/* ENET_MSC_TINTF */ +#define ENET_MSC_TINTF_TGFSC BIT(14) /*!< transmitted good frames single collision */ +#define ENET_MSC_TINTF_TGFMSC BIT(15) /*!< transmitted good frames more single collision */ +#define ENET_MSC_TINTF_TGF BIT(21) /*!< transmitted good frames */ + +/* ENET_MSC_RINTMSK */ +#define ENET_MSC_RINTMSK_RFCEIM BIT(5) /*!< received frame CRC error interrupt mask */ +#define ENET_MSC_RINTMSK_RFAEIM BIT(6) /*!< received frames alignment error interrupt mask */ +#define ENET_MSC_RINTMSK_RGUFIM BIT(17) /*!< received good unicast frames interrupt mask */ + +/* ENET_MSC_TINTMSK */ +#define ENET_MSC_TINTMSK_TGFSCIM BIT(14) /*!< transmitted good frames single collision interrupt mask */ +#define ENET_MSC_TINTMSK_TGFMSCIM BIT(15) /*!< transmitted good frames more single collision interrupt mask */ +#define ENET_MSC_TINTMSK_TGFIM BIT(21) /*!< transmitted good frames interrupt mask */ + +/* ENET_MSC_SCCNT */ +#define ENET_MSC_SCCNT_SCC BITS(0,31) /*!< transmitted good frames single collision counter */ + +/* ENET_MSC_MSCCNT */ +#define ENET_MSC_MSCCNT_MSCC BITS(0,31) /*!< transmitted good frames more one single collision counter */ + +/* ENET_MSC_TGFCNT */ +#define ENET_MSC_TGFCNT_TGF BITS(0,31) /*!< transmitted good frames counter */ + +/* ENET_MSC_RFCECNT */ +#define ENET_MSC_RFCECNT_RFCER BITS(0,31) /*!< received frames with CRC error counter */ + +/* ENET_MSC_RFAECNT */ +#define ENET_MSC_RFAECNT_RFAER BITS(0,31) /*!< received frames alignment error counter */ + +/* ENET_MSC_RGUFCNT */ +#define ENET_MSC_RGUFCNT_RGUF BITS(0,31) /*!< received good unicast frames counter */ + +/* ENET_PTP_TSCTL */ +#define PTP_TSCTL_CKNT(regval) (BITS(16,17) & ((uint32_t)(regval) << 16)) /*!< write value to ENET_PTP_TSCTL_CKNT bit field */ + +#define ENET_PTP_TSCTL_TMSEN BIT(0) /*!< timestamp enable */ +#define ENET_PTP_TSCTL_TMSFCU BIT(1) /*!< timestamp fine or coarse update */ +#define ENET_PTP_TSCTL_TMSSTI BIT(2) /*!< timestamp system time initialize */ +#define ENET_PTP_TSCTL_TMSSTU BIT(3) /*!< timestamp system time update */ +#define ENET_PTP_TSCTL_TMSITEN BIT(4) /*!< timestamp interrupt trigger enable */ +#define ENET_PTP_TSCTL_TMSARU BIT(5) /*!< timestamp addend register update */ +#define ENET_PTP_TSCTL_ARFSEN BIT(8) /*!< all received frames snapshot enable */ +#define ENET_PTP_TSCTL_SCROM BIT(9) /*!< subsecond counter rollover mode */ +#define ENET_PTP_TSCTL_PFSV BIT(10) /*!< PTP frame snooping version */ +#define ENET_PTP_TSCTL_ESEN BIT(11) /*!< received Ethernet snapshot enable */ +#define ENET_PTP_TSCTL_IP6SEN BIT(12) /*!< received IPv6 snapshot enable */ +#define ENET_PTP_TSCTL_IP4SEN BIT(13) /*!< received IPv4 snapshot enable */ +#define ENET_PTP_TSCTL_ETMSEN BIT(14) /*!< received event type message snapshot enable */ +#define ENET_PTP_TSCTL_MNMSEN BIT(15) /*!< received master node message snapshot enable */ +#define ENET_PTP_TSCTL_CKNT BITS(16,17) /*!< clock node type for time stamp */ +#define ENET_PTP_TSCTL_MAFEN BIT(18) /*!< MAC address filter enable for PTP frame */ + +/* ENET_PTP_SSINC */ +#define ENET_PTP_SSINC_STMSSI BITS(0,7) /*!< system time subsecond increment */ + +/* ENET_PTP_TSH */ +#define ENET_PTP_TSH_STMS BITS(0,31) /*!< system time second */ + +/* ENET_PTP_TSL */ +#define ENET_PTP_TSL_STMSS BITS(0,30) /*!< system time subseconds */ +#define ENET_PTP_TSL_STS BIT(31) /*!< system time sign */ + +/* ENET_PTP_TSUH */ +#define ENET_PTP_TSUH_TMSUS BITS(0,31) /*!< timestamp update seconds */ + +/* ENET_PTP_TSUL */ +#define ENET_PTP_TSUL_TMSUSS BITS(0,30) /*!< timestamp update subseconds */ +#define ENET_PTP_TSUL_TMSUPNS BIT(31) /*!< timestamp update positive or negative sign */ + +/* ENET_PTP_TSADDEND */ +#define ENET_PTP_TSADDEND_TMSA BITS(0,31) /*!< timestamp addend */ + +/* ENET_PTP_ETH */ +#define ENET_PTP_ETH_ETSH BITS(0,31) /*!< expected time high */ + +/* ENET_PTP_ETL */ +#define ENET_PTP_ETL_ETSL BITS(0,31) /*!< expected time low */ + +/* ENET_PTP_TSF */ +#define ENET_PTP_TSF_TSSCO BIT(0) /*!< timestamp second counter overflow */ +#define ENET_PTP_TSF_TTM BIT(1) /*!< target time match */ + +/* ENET_PTP_PPSCTL */ +#define ENET_PTP_PPSCTL_PPSOFC BITS(0,3) /*!< PPS output frequency configure */ + +/* ENET_DMA_BCTL */ +#define ENET_DMA_BCTL_SWR BIT(0) /*!< software reset */ +#define ENET_DMA_BCTL_DAB BIT(1) /*!< DMA arbitration */ +#define ENET_DMA_BCTL_DPSL BITS(2,6) /*!< descriptor skip length */ +#define ENET_DMA_BCTL_DFM BIT(7) /*!< descriptor format mode */ +#define ENET_DMA_BCTL_PGBL BITS(8,13) /*!< programmable burst length */ +#define ENET_DMA_BCTL_RTPR BITS(14,15) /*!< RxDMA and TxDMA transfer priority ratio */ +#define ENET_DMA_BCTL_FB BIT(16) /*!< fixed Burst */ +#define ENET_DMA_BCTL_RXDP BITS(17,22) /*!< RxDMA PGBL */ +#define ENET_DMA_BCTL_UIP BIT(23) /*!< use independent PGBL */ +#define ENET_DMA_BCTL_FPBL BIT(24) /*!< four times PGBL mode */ +#define ENET_DMA_BCTL_AA BIT(25) /*!< address-aligned */ +#define ENET_DMA_BCTL_MB BIT(26) /*!< mixed burst */ + +/* ENET_DMA_TPEN */ +#define ENET_DMA_TPEN_TPE BITS(0,31) /*!< transmit poll enable */ + +/* ENET_DMA_RPEN */ +#define ENET_DMA_RPEN_RPE BITS(0,31) /*!< receive poll enable */ + +/* ENET_DMA_RDTADDR */ +#define ENET_DMA_RDTADDR_SRT BITS(0,31) /*!< start address of receive table */ + +/* ENET_DMA_TDTADDR */ +#define ENET_DMA_TDTADDR_STT BITS(0,31) /*!< start address of transmit table */ + +/* ENET_DMA_STAT */ +#define ENET_DMA_STAT_TS BIT(0) /*!< transmit status */ +#define ENET_DMA_STAT_TPS BIT(1) /*!< transmit process stopped status */ +#define ENET_DMA_STAT_TBU BIT(2) /*!< transmit buffer unavailable status */ +#define ENET_DMA_STAT_TJT BIT(3) /*!< transmit jabber timeout status */ +#define ENET_DMA_STAT_RO BIT(4) /*!< receive overflow status */ +#define ENET_DMA_STAT_TU BIT(5) /*!< transmit underflow status */ +#define ENET_DMA_STAT_RS BIT(6) /*!< receive status */ +#define ENET_DMA_STAT_RBU BIT(7) /*!< receive buffer unavailable status */ +#define ENET_DMA_STAT_RPS BIT(8) /*!< receive process stopped status */ +#define ENET_DMA_STAT_RWT BIT(9) /*!< receive watchdog timeout status */ +#define ENET_DMA_STAT_ET BIT(10) /*!< early transmit status */ +#define ENET_DMA_STAT_FBE BIT(13) /*!< fatal bus error status */ +#define ENET_DMA_STAT_ER BIT(14) /*!< early receive status */ +#define ENET_DMA_STAT_AI BIT(15) /*!< abnormal interrupt summary */ +#define ENET_DMA_STAT_NI BIT(16) /*!< normal interrupt summary */ +#define ENET_DMA_STAT_RP BITS(17,19) /*!< receive process state */ +#define ENET_DMA_STAT_TP BITS(20,22) /*!< transmit process state */ +#define ENET_DMA_STAT_EB BITS(23,25) /*!< error bits status */ +#define ENET_DMA_STAT_MSC BIT(27) /*!< MSC status */ +#define ENET_DMA_STAT_WUM BIT(28) /*!< WUM status */ +#define ENET_DMA_STAT_TST BIT(29) /*!< timestamp trigger status */ + +/* ENET_DMA_CTL */ +#define ENET_DMA_CTL_SRE BIT(1) /*!< start/stop receive enable */ +#define ENET_DMA_CTL_OSF BIT(2) /*!< operate on second frame */ +#define ENET_DMA_CTL_RTHC BITS(3,4) /*!< receive threshold control */ +#define ENET_DMA_CTL_FUF BIT(6) /*!< forward undersized good frames */ +#define ENET_DMA_CTL_FERF BIT(7) /*!< forward error frames */ +#define ENET_DMA_CTL_STE BIT(13) /*!< start/stop transmission enable */ +#define ENET_DMA_CTL_TTHC BITS(14,16) /*!< transmit threshold control */ +#define ENET_DMA_CTL_FTF BIT(20) /*!< flush transmit FIFO */ +#define ENET_DMA_CTL_TSFD BIT(21) /*!< transmit store-and-forward */ +#define ENET_DMA_CTL_DAFRF BIT(24) /*!< disable flushing of received frames */ +#define ENET_DMA_CTL_RSFD BIT(25) /*!< receive store-and-forward */ +#define ENET_DMA_CTL_DTCERFD BIT(26) /*!< dropping of TCP/IP checksum error frames disable */ + +/* ENET_DMA_INTEN */ +#define ENET_DMA_INTEN_TIE BIT(0) /*!< transmit interrupt enable */ +#define ENET_DMA_INTEN_TPSIE BIT(1) /*!< transmit process stopped interrupt enable */ +#define ENET_DMA_INTEN_TBUIE BIT(2) /*!< transmit buffer unavailable interrupt enable */ +#define ENET_DMA_INTEN_TJTIE BIT(3) /*!< transmit jabber timeout interrupt enable */ +#define ENET_DMA_INTEN_ROIE BIT(4) /*!< receive overflow interrupt enable */ +#define ENET_DMA_INTEN_TUIE BIT(5) /*!< transmit underflow interrupt enable */ +#define ENET_DMA_INTEN_RIE BIT(6) /*!< receive interrupt enable */ +#define ENET_DMA_INTEN_RBUIE BIT(7) /*!< receive buffer unavailable interrupt enable */ +#define ENET_DMA_INTEN_RPSIE BIT(8) /*!< receive process stopped interrupt enable */ +#define ENET_DMA_INTEN_RWTIE BIT(9) /*!< receive watchdog timeout interrupt enable */ +#define ENET_DMA_INTEN_ETIE BIT(10) /*!< early transmit interrupt enable */ +#define ENET_DMA_INTEN_FBEIE BIT(13) /*!< fatal bus error interrupt enable */ +#define ENET_DMA_INTEN_ERIE BIT(14) /*!< early receive interrupt enable */ +#define ENET_DMA_INTEN_AIE BIT(15) /*!< abnormal interrupt summary enable */ +#define ENET_DMA_INTEN_NIE BIT(16) /*!< normal interrupt summary enable */ + +/* ENET_DMA_MFBOCNT */ +#define ENET_DMA_MFBOCNT_MSFC BITS(0,15) /*!< missed frames by the controller */ +#define ENET_DMA_MFBOCNT_MSFA BITS(17,27) /*!< missed frames by the application */ + +/* ENET_DMA_RSWDC */ +#define ENET_DMA_RSWDC_WDCFRS BITS(0,7) /*!< watchdog counter for receive status (RS) */ + +/* ENET_DMA_CTDADDR */ +#define ENET_DMA_CTDADDR_TDAP BITS(0,31) /*!< transmit descriptor address pointer */ + +/* ENET_DMA_CRDADDR */ +#define ENET_DMA_CRDADDR_RDAP BITS(0,31) /*!< receive descriptor address pointer */ + +/* ENET_DMA_CTBADDR */ +#define ENET_DMA_CTBADDR_TBAP BITS(0,31) /*!< transmit buffer address pointer */ + +/* ENET_DMA_CRBADDR */ +#define ENET_DMA_CRBADDR_RBAP BITS(0,31) /*!< receive buffer address pointer */ + +/* ENET DMA Tx descriptor TDES0 */ +#define ENET_TDES0_DB BIT(0) /*!< deferred */ +#define ENET_TDES0_UFE BIT(1) /*!< underflow error */ +#define ENET_TDES0_EXD BIT(2) /*!< excessive deferral */ +#define ENET_TDES0_COCNT BITS(3,6) /*!< collision count */ +#define ENET_TDES0_VFRM BIT(7) /*!< VLAN frame */ +#define ENET_TDES0_ECO BIT(8) /*!< excessive collision */ +#define ENET_TDES0_LCO BIT(9) /*!< late collision */ +#define ENET_TDES0_NCA BIT(10) /*!< no carrier */ +#define ENET_TDES0_LCA BIT(11) /*!< loss of carrier */ +#define ENET_TDES0_IPPE BIT(12) /*!< IP payload error */ +#define ENET_TDES0_FRMF BIT(13) /*!< frame flushed */ +#define ENET_TDES0_JT BIT(14) /*!< jabber timeout */ +#define ENET_TDES0_ES BIT(15) /*!< error summary */ +#define ENET_TDES0_IPHE BIT(16) /*!< IP header error */ +#define ENET_TDES0_TTMSS BIT(17) /*!< transmit timestamp status */ +#define ENET_TDES0_TCHM BIT(20) /*!< the second address chained mode */ +#define ENET_TDES0_TERM BIT(21) /*!< transmit end of ring mode*/ +#define ENET_TDES0_CM BITS(22,23) /*!< checksum mode */ +#define ENET_TDES0_TTSEN BIT(25) /*!< transmit timestamp function enable */ +#define ENET_TDES0_DPAD BIT(26) /*!< disable adding pad */ +#define ENET_TDES0_DCRC BIT(27) /*!< disable CRC */ +#define ENET_TDES0_FSG BIT(28) /*!< first segment */ +#define ENET_TDES0_LSG BIT(29) /*!< last segment */ +#define ENET_TDES0_INTC BIT(30) /*!< interrupt on completion */ +#define ENET_TDES0_DAV BIT(31) /*!< DAV bit */ + +/* ENET DMA Tx descriptor TDES1 */ +#define ENET_TDES1_TB1S BITS(0,12) /*!< transmit buffer 1 size */ +#define ENET_TDES1_TB2S BITS(16,28) /*!< transmit buffer 2 size */ + +/* ENET DMA Tx descriptor TDES2 */ +#define ENET_TDES2_TB1AP BITS(0,31) /*!< transmit buffer 1 address pointer/transmit frame timestamp low 32-bit value */ + +/* ENET DMA Tx descriptor TDES3 */ +#define ENET_TDES3_TB2AP BITS(0,31) /*!< transmit buffer 2 address pointer (or next descriptor address) / transmit frame timestamp high 32-bit value */ + +#ifdef SELECT_DESCRIPTORS_ENHANCED_MODE +/* ENET DMA Tx descriptor TDES6 */ +#define ENET_TDES6_TTSL BITS(0,31) /*!< transmit frame timestamp low 32-bit value */ + +/* ENET DMA Tx descriptor TDES7 */ +#define ENET_TDES7_TTSH BITS(0,31) /*!< transmit frame timestamp high 32-bit value */ +#endif /* SELECT_DESCRIPTORS_ENHANCED_MODE */ + +/* ENET DMA Rx descriptor RDES0 */ +#define ENET_RDES0_PCERR BIT(0) /*!< payload checksum error */ +#define ENET_RDES0_EXSV BIT(0) /*!< extended status valid */ +#define ENET_RDES0_CERR BIT(1) /*!< CRC error */ +#define ENET_RDES0_DBERR BIT(2) /*!< dribble bit error */ +#define ENET_RDES0_RERR BIT(3) /*!< receive error */ +#define ENET_RDES0_RWDT BIT(4) /*!< receive watchdog timeout */ +#define ENET_RDES0_FRMT BIT(5) /*!< frame type */ +#define ENET_RDES0_LCO BIT(6) /*!< late collision */ +#define ENET_RDES0_IPHERR BIT(7) /*!< IP frame header error */ +#define ENET_RDES0_TSV BIT(7) /*!< timestamp valid */ +#define ENET_RDES0_LDES BIT(8) /*!< last descriptor */ +#define ENET_RDES0_FDES BIT(9) /*!< first descriptor */ +#define ENET_RDES0_VTAG BIT(10) /*!< VLAN tag */ +#define ENET_RDES0_OERR BIT(11) /*!< overflow Error */ +#define ENET_RDES0_LERR BIT(12) /*!< length error */ +#define ENET_RDES0_SAFF BIT(13) /*!< SA filter fail */ +#define ENET_RDES0_DERR BIT(14) /*!< descriptor error */ +#define ENET_RDES0_ERRS BIT(15) /*!< error summary */ +#define ENET_RDES0_FRML BITS(16,29) /*!< frame length */ +#define ENET_RDES0_DAFF BIT(30) /*!< destination address filter fail */ +#define ENET_RDES0_DAV BIT(31) /*!< descriptor available */ + +/* ENET DMA Rx descriptor RDES1 */ +#define ENET_RDES1_RB1S BITS(0,12) /*!< receive buffer 1 size */ +#define ENET_RDES1_RCHM BIT(14) /*!< receive chained mode for second address */ +#define ENET_RDES1_RERM BIT(15) /*!< receive end of ring mode*/ +#define ENET_RDES1_RB2S BITS(16,28) /*!< receive buffer 2 size */ +#define ENET_RDES1_DINTC BIT(31) /*!< disable interrupt on completion */ + +/* ENET DMA Rx descriptor RDES2 */ +#define ENET_RDES2_RB1AP BITS(0,31) /*!< receive buffer 1 address pointer / receive frame timestamp low 32-bit */ + +/* ENET DMA Rx descriptor RDES3 */ +#define ENET_RDES3_RB2AP BITS(0,31) /*!< receive buffer 2 address pointer (next descriptor address)/receive frame timestamp high 32-bit value */ + +#ifdef SELECT_DESCRIPTORS_ENHANCED_MODE +/* ENET DMA Rx descriptor RDES4 */ +#define ENET_RDES4_IPPLDT BITS(0,2) /*!< IP frame payload type */ +#define ENET_RDES4_IPHERR BIT(3) /*!< IP frame header error */ +#define ENET_RDES4_IPPLDERR BIT(4) /*!< IP frame payload error */ +#define ENET_RDES4_IPCKSB BIT(5) /*!< IP frame checksum bypassed */ +#define ENET_RDES4_IPF4 BIT(6) /*!< IP frame in version 4 */ +#define ENET_RDES4_IPF6 BIT(7) /*!< IP frame in version 6 */ +#define ENET_RDES4_PTPMT BITS(8,11) /*!< PTP message type */ +#define ENET_RDES4_PTPOEF BIT(12) /*!< PTP on ethernet frame */ +#define ENET_RDES4_PTPVF BIT(13) /*!< PTP version format */ + +/* ENET DMA Rx descriptor RDES6 */ +#define ENET_RDES6_RTSL BITS(0,31) /*!< receive frame timestamp low 32-bit value */ + +/* ENET DMA Rx descriptor RDES7 */ +#define ENET_RDES7_RTSH BITS(0,31) /*!< receive frame timestamp high 32-bit value */ +#endif /* SELECT_DESCRIPTORS_ENHANCED_MODE */ + +/* constants definitions */ +/* define bit position and its register index offset */ +#define ENET_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)) +#define ENET_REG_VAL(periph) (REG32(ENET + ((uint32_t)(periph) >> 6))) +#define ENET_BIT_POS(val) ((uint32_t)(val) & 0x1FU) + +/* ENET clock range judgement */ +#define ENET_RANGE(hclk, n, m) (((hclk) >= (n))&&((hclk) < (m))) + +/* define MAC address configuration and reference address */ +#define ENET_SET_MACADDRH(p) (((uint32_t)(p)[5] << 8) | (uint32_t)(p)[4]) +#define ENET_SET_MACADDRL(p) (((uint32_t)(p)[3] << 24) | ((uint32_t)(p)[2] << 16) | ((uint32_t)(p)[1] << 8) | (uint32_t)(p)[0]) +#define ENET_ADDRH_BASE ((ENET) + 0x40U) +#define ENET_ADDRL_BASE ((ENET) + 0x44U) +#define ENET_GET_MACADDR(offset, n) ((uint8_t)((REG32((ENET_ADDRL_BASE + (offset)) - (((n) / 4U) * 4U)) >> (8U * ((n) % 4U))) & 0xFFU)) + +/* register offset */ +#define MAC_FCTL_REG_OFFSET ((uint16_t)0x0018U) /*!< MAC flow control register offset */ +#define MAC_WUM_REG_OFFSET ((uint16_t)0x002CU) /*!< MAC wakeup management register offset */ +#define MAC_INTF_REG_OFFSET ((uint16_t)0x0038U) /*!< MAC interrupt flag register offset */ +#define MAC_INTMSK_REG_OFFSET ((uint16_t)0x003CU) /*!< MAC interrupt mask register offset */ + +#define MSC_RINTF_REG_OFFSET ((uint16_t)0x0104U) /*!< MSC receive interrupt flag register offset */ +#define MSC_TINTF_REG_OFFSET ((uint16_t)0x0108U) /*!< MSC transmit interrupt flag register offset */ +#define MSC_RINTMSK_REG_OFFSET ((uint16_t)0x010CU) /*!< MSC receive interrupt mask register offset */ +#define MSC_TINTMSK_REG_OFFSET ((uint16_t)0x0110U) /*!< MSC transmit interrupt mask register offset */ +#define MSC_SCCNT_REG_OFFSET ((uint16_t)0x014CU) /*!< MSC transmitted good frames after a single collision counter register offset */ +#define MSC_MSCCNT_REG_OFFSET ((uint16_t)0x0150U) /*!< MSC transmitted good frames after more than a single collision counter register offset */ +#define MSC_TGFCNT_REG_OFFSET ((uint16_t)0x0168U) /*!< MSC transmitted good frames counter register offset */ +#define MSC_RFCECNT_REG_OFFSET ((uint16_t)0x0194U) /*!< MSC received frames with CRC error counter register offset */ +#define MSC_RFAECNT_REG_OFFSET ((uint16_t)0x0198U) /*!< MSC received frames with alignment error counter register offset */ +#define MSC_RGUFCNT_REG_OFFSET ((uint16_t)0x01C4U) /*!< MSC received good unicast frames counter register offset */ + +#define PTP_TSF_REG_OFFSET ((uint16_t)0x0728U) /*!< PTP time stamp flag register offset */ + +#define DMA_STAT_REG_OFFSET ((uint16_t)0x1014U) /*!< DMA status register offset */ +#define DMA_INTEN_REG_OFFSET ((uint16_t)0x101CU) /*!< DMA interrupt enable register offset */ +#define DMA_TDTADDR_REG_OFFSET ((uint16_t)0x1010U) /*!< DMA transmit descriptor table address register offset */ +#define DMA_CTDADDR_REG_OFFSET ((uint16_t)0x1048U) /*!< DMA current transmit descriptor address register */ +#define DMA_CTBADDR_REG_OFFSET ((uint16_t)0x1050U) /*!< DMA current transmit buffer address register */ +#define DMA_RDTADDR_REG_OFFSET ((uint16_t)0x100CU) /*!< DMA receive descriptor table address register */ +#define DMA_CRDADDR_REG_OFFSET ((uint16_t)0x104CU) /*!< DMA current receive descriptor address register */ +#define DMA_CRBADDR_REG_OFFSET ((uint16_t)0x1054U) /*!< DMA current receive buffer address register */ + +/* ENET status flag get */ +typedef enum +{ + /* ENET_MAC_WUM register */ + ENET_MAC_FLAG_MPKR = ENET_REGIDX_BIT(MAC_WUM_REG_OFFSET, 5U), /*!< magic packet received flag */ + ENET_MAC_FLAG_WUFR = ENET_REGIDX_BIT(MAC_WUM_REG_OFFSET, 6U), /*!< wakeup frame received flag */ + /* ENET_MAC_FCTL register */ + ENET_MAC_FLAG_FLOWCONTROL = ENET_REGIDX_BIT(MAC_FCTL_REG_OFFSET, 0U), /*!< flow control status flag */ + /* ENET_MAC_INTF register */ + ENET_MAC_FLAG_WUM = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 3U), /*!< WUM status flag */ + ENET_MAC_FLAG_MSC = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 4U), /*!< MSC status flag */ + ENET_MAC_FLAG_MSCR = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 5U), /*!< MSC receive status flag */ + ENET_MAC_FLAG_MSCT = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 6U), /*!< MSC transmit status flag */ + ENET_MAC_FLAG_TMST = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 9U), /*!< timestamp trigger status flag */ + /* ENET_PTP_TSF register */ + ENET_PTP_FLAG_TSSCO = ENET_REGIDX_BIT(PTP_TSF_REG_OFFSET, 0U), /*!< timestamp second counter overflow flag */ + ENET_PTP_FLAG_TTM = ENET_REGIDX_BIT(PTP_TSF_REG_OFFSET, 1U), /*!< target time match flag */ + /* ENET_MSC_RINTF register */ + ENET_MSC_FLAG_RFCE = ENET_REGIDX_BIT(MSC_RINTF_REG_OFFSET, 5U), /*!< received frames CRC error flag */ + ENET_MSC_FLAG_RFAE = ENET_REGIDX_BIT(MSC_RINTF_REG_OFFSET, 6U), /*!< received frames alignment error flag */ + ENET_MSC_FLAG_RGUF = ENET_REGIDX_BIT(MSC_RINTF_REG_OFFSET, 17U), /*!< received good unicast frames flag */ + /* ENET_MSC_TINTF register */ + ENET_MSC_FLAG_TGFSC = ENET_REGIDX_BIT(MSC_TINTF_REG_OFFSET, 14U), /*!< transmitted good frames single collision flag */ + ENET_MSC_FLAG_TGFMSC = ENET_REGIDX_BIT(MSC_TINTF_REG_OFFSET, 15U), /*!< transmitted good frames more single collision flag */ + ENET_MSC_FLAG_TGF = ENET_REGIDX_BIT(MSC_TINTF_REG_OFFSET, 21U), /*!< transmitted good frames flag */ + /* ENET_DMA_STAT register */ + ENET_DMA_FLAG_TS = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 0U), /*!< transmit status flag */ + ENET_DMA_FLAG_TPS = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 1U), /*!< transmit process stopped status flag */ + ENET_DMA_FLAG_TBU = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 2U), /*!< transmit buffer unavailable status flag */ + ENET_DMA_FLAG_TJT = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 3U), /*!< transmit jabber timeout status flag */ + ENET_DMA_FLAG_RO = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 4U), /*!< receive overflow status flag */ + ENET_DMA_FLAG_TU = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 5U), /*!< transmit underflow status flag */ + ENET_DMA_FLAG_RS = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 6U), /*!< receive status flag */ + ENET_DMA_FLAG_RBU = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 7U), /*!< receive buffer unavailable status flag */ + ENET_DMA_FLAG_RPS = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 8U), /*!< receive process stopped status flag */ + ENET_DMA_FLAG_RWT = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 9U), /*!< receive watchdog timeout status flag */ + ENET_DMA_FLAG_ET = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 10U), /*!< early transmit status flag */ + ENET_DMA_FLAG_FBE = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 13U), /*!< fatal bus error status flag */ + ENET_DMA_FLAG_ER = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 14U), /*!< early receive status flag */ + ENET_DMA_FLAG_AI = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 15U), /*!< abnormal interrupt summary flag */ + ENET_DMA_FLAG_NI = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 16U), /*!< normal interrupt summary flag */ + ENET_DMA_FLAG_EB_DMA_ERROR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 23U), /*!< error during data transfer by RxDMA/TxDMA flag */ + ENET_DMA_FLAG_EB_TRANSFER_ERROR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 24U), /*!< error during write/read transfer flag */ + ENET_DMA_FLAG_EB_ACCESS_ERROR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 25U), /*!< error during data buffer/descriptor access flag */ + ENET_DMA_FLAG_MSC = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 27U), /*!< MSC status flag */ + ENET_DMA_FLAG_WUM = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 28U), /*!< WUM status flag */ + ENET_DMA_FLAG_TST = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 29U) /*!< timestamp trigger status flag */ +}enet_flag_enum; + +/* ENET stutus flag clear */ +typedef enum +{ + /* ENET_DMA_STAT register */ + ENET_DMA_FLAG_TS_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 0U), /*!< transmit status flag */ + ENET_DMA_FLAG_TPS_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 1U), /*!< transmit process stopped status flag */ + ENET_DMA_FLAG_TBU_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 2U), /*!< transmit buffer unavailable status flag */ + ENET_DMA_FLAG_TJT_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 3U), /*!< transmit jabber timeout status flag */ + ENET_DMA_FLAG_RO_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 4U), /*!< receive overflow status flag */ + ENET_DMA_FLAG_TU_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 5U), /*!< transmit underflow status flag */ + ENET_DMA_FLAG_RS_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 6U), /*!< receive status flag */ + ENET_DMA_FLAG_RBU_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 7U), /*!< receive buffer unavailable status flag */ + ENET_DMA_FLAG_RPS_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 8U), /*!< receive process stopped status flag */ + ENET_DMA_FLAG_RWT_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 9U), /*!< receive watchdog timeout status flag */ + ENET_DMA_FLAG_ET_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 10U), /*!< early transmit status flag */ + ENET_DMA_FLAG_FBE_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 13U), /*!< fatal bus error status flag */ + ENET_DMA_FLAG_ER_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 14U), /*!< early receive status flag */ + ENET_DMA_FLAG_AI_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 15U), /*!< abnormal interrupt summary flag */ + ENET_DMA_FLAG_NI_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 16U) /*!< normal interrupt summary flag */ +}enet_flag_clear_enum; + +/* ENET interrupt enable/disable */ +typedef enum +{ + /* ENET_MAC_INTMSK register */ + ENET_MAC_INT_WUMIM = ENET_REGIDX_BIT(MAC_INTMSK_REG_OFFSET, 3U), /*!< WUM interrupt mask */ + ENET_MAC_INT_TMSTIM = ENET_REGIDX_BIT(MAC_INTMSK_REG_OFFSET, 9U), /*!< timestamp trigger interrupt mask */ + /* ENET_MSC_RINTMSK register */ + ENET_MSC_INT_RFCEIM = ENET_REGIDX_BIT(MSC_RINTMSK_REG_OFFSET, 5U), /*!< received frame CRC error interrupt mask */ + ENET_MSC_INT_RFAEIM = ENET_REGIDX_BIT(MSC_RINTMSK_REG_OFFSET, 6U), /*!< received frames alignment error interrupt mask */ + ENET_MSC_INT_RGUFIM = ENET_REGIDX_BIT(MSC_RINTMSK_REG_OFFSET, 17U), /*!< received good unicast frames interrupt mask */ + /* ENET_MSC_TINTMSK register */ + ENET_MSC_INT_TGFSCIM = ENET_REGIDX_BIT(MSC_TINTMSK_REG_OFFSET, 14U), /*!< transmitted good frames single collision interrupt mask */ + ENET_MSC_INT_TGFMSCIM = ENET_REGIDX_BIT(MSC_TINTMSK_REG_OFFSET, 15U), /*!< transmitted good frames more single collision interrupt mask */ + ENET_MSC_INT_TGFIM = ENET_REGIDX_BIT(MSC_TINTMSK_REG_OFFSET, 21U), /*!< transmitted good frames interrupt mask */ + /* ENET_DMA_INTEN register */ + ENET_DMA_INT_TIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 0U), /*!< transmit interrupt enable */ + ENET_DMA_INT_TPSIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 1U), /*!< transmit process stopped interrupt enable */ + ENET_DMA_INT_TBUIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 2U), /*!< transmit buffer unavailable interrupt enable */ + ENET_DMA_INT_TJTIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 3U), /*!< transmit jabber timeout interrupt enable */ + ENET_DMA_INT_ROIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 4U), /*!< receive overflow interrupt enable */ + ENET_DMA_INT_TUIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 5U), /*!< transmit underflow interrupt enable */ + ENET_DMA_INT_RIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 6U), /*!< receive interrupt enable */ + ENET_DMA_INT_RBUIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 7U), /*!< receive buffer unavailable interrupt enable */ + ENET_DMA_INT_RPSIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 8U), /*!< receive process stopped interrupt enable */ + ENET_DMA_INT_RWTIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 9U), /*!< receive watchdog timeout interrupt enable */ + ENET_DMA_INT_ETIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 10U), /*!< early transmit interrupt enable */ + ENET_DMA_INT_FBEIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 13U), /*!< fatal bus error interrupt enable */ + ENET_DMA_INT_ERIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 14U), /*!< early receive interrupt enable */ + ENET_DMA_INT_AIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 15U), /*!< abnormal interrupt summary enable */ + ENET_DMA_INT_NIE = ENET_REGIDX_BIT(DMA_INTEN_REG_OFFSET, 16U) /*!< normal interrupt summary enable */ +}enet_int_enum; + +/* ENET interrupt flag get */ +typedef enum +{ + /* ENET_MAC_INTF register */ + ENET_MAC_INT_FLAG_WUM = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 3U), /*!< WUM status flag */ + ENET_MAC_INT_FLAG_MSC = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 4U), /*!< MSC status flag */ + ENET_MAC_INT_FLAG_MSCR = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 5U), /*!< MSC receive status flag */ + ENET_MAC_INT_FLAG_MSCT = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 6U), /*!< MSC transmit status flag */ + ENET_MAC_INT_FLAG_TMST = ENET_REGIDX_BIT(MAC_INTF_REG_OFFSET, 9U), /*!< timestamp trigger status flag */ + /* ENET_MSC_RINTF register */ + ENET_MSC_INT_FLAG_RFCE = ENET_REGIDX_BIT(MSC_RINTF_REG_OFFSET, 5U), /*!< received frames CRC error flag */ + ENET_MSC_INT_FLAG_RFAE = ENET_REGIDX_BIT(MSC_RINTF_REG_OFFSET, 6U), /*!< received frames alignment error flag */ + ENET_MSC_INT_FLAG_RGUF = ENET_REGIDX_BIT(MSC_RINTF_REG_OFFSET, 17U), /*!< received good unicast frames flag */ + /* ENET_MSC_TINTF register */ + ENET_MSC_INT_FLAG_TGFSC = ENET_REGIDX_BIT(MSC_TINTF_REG_OFFSET, 14U), /*!< transmitted good frames single collision flag */ + ENET_MSC_INT_FLAG_TGFMSC = ENET_REGIDX_BIT(MSC_TINTF_REG_OFFSET, 15U), /*!< transmitted good frames more single collision flag */ + ENET_MSC_INT_FLAG_TGF = ENET_REGIDX_BIT(MSC_TINTF_REG_OFFSET, 21U), /*!< transmitted good frames flag */ + /* ENET_DMA_STAT register */ + ENET_DMA_INT_FLAG_TS = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 0U), /*!< transmit status flag */ + ENET_DMA_INT_FLAG_TPS = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 1U), /*!< transmit process stopped status flag */ + ENET_DMA_INT_FLAG_TBU = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 2U), /*!< transmit buffer unavailable status flag */ + ENET_DMA_INT_FLAG_TJT = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 3U), /*!< transmit jabber timeout status flag */ + ENET_DMA_INT_FLAG_RO = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 4U), /*!< receive overflow status flag */ + ENET_DMA_INT_FLAG_TU = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 5U), /*!< transmit underflow status flag */ + ENET_DMA_INT_FLAG_RS = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 6U), /*!< receive status flag */ + ENET_DMA_INT_FLAG_RBU = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 7U), /*!< receive buffer unavailable status flag */ + ENET_DMA_INT_FLAG_RPS = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 8U), /*!< receive process stopped status flag */ + ENET_DMA_INT_FLAG_RWT = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 9U), /*!< receive watchdog timeout status flag */ + ENET_DMA_INT_FLAG_ET = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 10U), /*!< early transmit status flag */ + ENET_DMA_INT_FLAG_FBE = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 13U), /*!< fatal bus error status flag */ + ENET_DMA_INT_FLAG_ER = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 14U), /*!< early receive status flag */ + ENET_DMA_INT_FLAG_AI = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 15U), /*!< abnormal interrupt summary flag */ + ENET_DMA_INT_FLAG_NI = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 16U), /*!< normal interrupt summary flag */ + ENET_DMA_INT_FLAG_MSC = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 27U), /*!< MSC status flag */ + ENET_DMA_INT_FLAG_WUM = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 28U), /*!< WUM status flag */ + ENET_DMA_INT_FLAG_TST = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 29U) /*!< timestamp trigger status flag */ +}enet_int_flag_enum; + +/* ENET interrupt flag clear */ +typedef enum +{ + /* ENET_DMA_STAT register */ + ENET_DMA_INT_FLAG_TS_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 0U), /*!< transmit status flag */ + ENET_DMA_INT_FLAG_TPS_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 1U), /*!< transmit process stopped status flag */ + ENET_DMA_INT_FLAG_TBU_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 2U), /*!< transmit buffer unavailable status flag */ + ENET_DMA_INT_FLAG_TJT_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 3U), /*!< transmit jabber timeout status flag */ + ENET_DMA_INT_FLAG_RO_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 4U), /*!< receive overflow status flag */ + ENET_DMA_INT_FLAG_TU_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 5U), /*!< transmit underflow status flag */ + ENET_DMA_INT_FLAG_RS_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 6U), /*!< receive status flag */ + ENET_DMA_INT_FLAG_RBU_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 7U), /*!< receive buffer unavailable status flag */ + ENET_DMA_INT_FLAG_RPS_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 8U), /*!< receive process stopped status flag */ + ENET_DMA_INT_FLAG_RWT_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 9U), /*!< receive watchdog timeout status flag */ + ENET_DMA_INT_FLAG_ET_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 10U), /*!< early transmit status flag */ + ENET_DMA_INT_FLAG_FBE_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 13U), /*!< fatal bus error status flag */ + ENET_DMA_INT_FLAG_ER_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 14U), /*!< early receive status flag */ + ENET_DMA_INT_FLAG_AI_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 15U), /*!< abnormal interrupt summary flag */ + ENET_DMA_INT_FLAG_NI_CLR = ENET_REGIDX_BIT(DMA_STAT_REG_OFFSET, 16U) /*!< normal interrupt summary flag */ +}enet_int_flag_clear_enum; + +/* current RX/TX descriptor/buffer/descriptor table address get */ +typedef enum +{ + ENET_RX_DESC_TABLE = DMA_RDTADDR_REG_OFFSET, /*!< RX descriptor table */ + ENET_RX_CURRENT_DESC = DMA_CRDADDR_REG_OFFSET, /*!< current RX descriptor */ + ENET_RX_CURRENT_BUFFER = DMA_CRBADDR_REG_OFFSET, /*!< current RX buffer */ + ENET_TX_DESC_TABLE = DMA_TDTADDR_REG_OFFSET, /*!< TX descriptor table */ + ENET_TX_CURRENT_DESC = DMA_CTDADDR_REG_OFFSET, /*!< current TX descriptor */ + ENET_TX_CURRENT_BUFFER = DMA_CTBADDR_REG_OFFSET /*!< current TX buffer */ +}enet_desc_reg_enum; + +/* MAC statistics counter get */ +typedef enum +{ + ENET_MSC_TX_SCCNT = MSC_SCCNT_REG_OFFSET, /*!< MSC transmitted good frames after a single collision counter */ + ENET_MSC_TX_MSCCNT = MSC_MSCCNT_REG_OFFSET, /*!< MSC transmitted good frames after more than a single collision counter */ + ENET_MSC_TX_TGFCNT = MSC_TGFCNT_REG_OFFSET, /*!< MSC transmitted good frames counter */ + ENET_MSC_RX_RFCECNT = MSC_RFCECNT_REG_OFFSET, /*!< MSC received frames with CRC error counter */ + ENET_MSC_RX_RFAECNT = MSC_RFAECNT_REG_OFFSET, /*!< MSC received frames with alignment error counter */ + ENET_MSC_RX_RGUFCNT = MSC_RGUFCNT_REG_OFFSET /*!< MSC received good unicast frames counter */ +}enet_msc_counter_enum; + +/* function option, used for ENET initialization */ +typedef enum +{ + FORWARD_OPTION = BIT(0), /*!< configure the frame forward related parameters */ + DMABUS_OPTION = BIT(1), /*!< configure the DMA bus mode related parameters */ + DMA_MAXBURST_OPTION = BIT(2), /*!< configure the DMA max burst related parameters */ + DMA_ARBITRATION_OPTION = BIT(3), /*!< configure the DMA arbitration related parameters */ + STORE_OPTION = BIT(4), /*!< configure the store forward mode related parameters */ + DMA_OPTION = BIT(5), /*!< configure the DMA control related parameters */ + VLAN_OPTION = BIT(6), /*!< configure the VLAN tag related parameters */ + FLOWCTL_OPTION = BIT(7), /*!< configure the flow control related parameters */ + HASHH_OPTION = BIT(8), /*!< configure the hash list high 32-bit related parameters */ + HASHL_OPTION = BIT(9), /*!< configure the hash list low 32-bit related parameters */ + FILTER_OPTION = BIT(10), /*!< configure the frame filter control related parameters */ + HALFDUPLEX_OPTION = BIT(11), /*!< configure the halfduplex related parameters */ + TIMER_OPTION = BIT(12), /*!< configure the frame timer related parameters */ + INTERFRAMEGAP_OPTION = BIT(13) /*!< configure the inter frame gap related parameters */ +}enet_option_enum; + +/* phy mode and mac loopback configurations */ +typedef enum +{ + ENET_AUTO_NEGOTIATION = 0x01U, /*!< PHY auto negotiation */ + ENET_100M_FULLDUPLEX = (ENET_MAC_CFG_SPD | ENET_MAC_CFG_DPM), /*!< 100Mbit/s, full-duplex */ + ENET_100M_HALFDUPLEX = ENET_MAC_CFG_SPD , /*!< 100Mbit/s, half-duplex */ + ENET_10M_FULLDUPLEX = ENET_MAC_CFG_DPM, /*!< 10Mbit/s, full-duplex */ + ENET_10M_HALFDUPLEX = (uint32_t)0x00000000U, /*!< 10Mbit/s, half-duplex */ + ENET_LOOPBACKMODE = (ENET_MAC_CFG_LBM | ENET_MAC_CFG_DPM) /*!< MAC in loopback mode at the MII */ +}enet_mediamode_enum; + +/* IP frame checksum function */ +typedef enum +{ + ENET_NO_AUTOCHECKSUM = (uint32_t)0x00000000U, /*!< disable IP frame checksum function */ + ENET_AUTOCHECKSUM_DROP_FAILFRAMES = ENET_MAC_CFG_IPFCO, /*!< enable IP frame checksum function */ + ENET_AUTOCHECKSUM_ACCEPT_FAILFRAMES = (ENET_MAC_CFG_IPFCO|ENET_DMA_CTL_DTCERFD) /*!< enable IP frame checksum function, and the received frame + with only payload error but no other errors will not be dropped */ +}enet_chksumconf_enum; + +/* received frame filter function */ +typedef enum +{ + ENET_PROMISCUOUS_MODE = ENET_MAC_FRMF_PM, /*!< promiscuous mode enabled */ + ENET_RECEIVEALL = (int32_t)ENET_MAC_FRMF_FAR, /*!< all received frame are forwarded to application */ + ENET_BROADCAST_FRAMES_PASS = (uint32_t)0x00000000U, /*!< the address filters pass all received broadcast frames */ + ENET_BROADCAST_FRAMES_DROP = ENET_MAC_FRMF_BFRMD /*!< the address filters filter all incoming broadcast frames */ +}enet_frmrecept_enum; + +/* register group value get */ +typedef enum +{ + ALL_MAC_REG = 0U, /*!< MAC register group */ + ALL_MSC_REG = 22U, /*!< MSC register group */ + ALL_PTP_REG = 33U, /*!< PTP register group */ + ALL_DMA_REG = 44U /*!< DMA register group */ +}enet_registers_type_enum; + +/* dma direction select */ +typedef enum +{ + ENET_DMA_TX = ENET_DMA_STAT_TP, /*!< DMA transmit direction */ + ENET_DMA_RX = ENET_DMA_STAT_RP /*!< DMA receive direction */ +}enet_dmadirection_enum; + +/* PHY operation direction select */ +typedef enum +{ + ENET_PHY_READ = (uint32_t)0x00000000, /*!< read PHY */ + ENET_PHY_WRITE = ENET_MAC_PHY_CTL_PW /*!< write PHY */ +}enet_phydirection_enum; + +/* register operation direction select */ +typedef enum +{ + ENET_REG_READ, /*!< read register */ + ENET_REG_WRITE /*!< write register */ +}enet_regdirection_enum; + +/* ENET MAC addresses */ +typedef enum +{ + ENET_MAC_ADDRESS0 = ((uint32_t)0x00000000), /*!< MAC address0 */ + ENET_MAC_ADDRESS1 = ((uint32_t)0x00000008), /*!< MAC address1 */ + ENET_MAC_ADDRESS2 = ((uint32_t)0x00000010), /*!< MAC address2 */ + ENET_MAC_ADDRESS3 = ((uint32_t)0x00000018) /*!< MAC address3 */ +}enet_macaddress_enum; + +/* descriptor information */ +typedef enum +{ + TXDESC_COLLISION_COUNT, /*!< the number of collisions occurred before the frame was transmitted */ + TXDESC_BUFFER_1_ADDR, /*!< transmit frame buffer 1 address */ + RXDESC_FRAME_LENGTH, /*!< the byte length of the received frame that was transferred to the buffer */ + RXDESC_BUFFER_1_SIZE, /*!< receive buffer 1 size */ + RXDESC_BUFFER_2_SIZE, /*!< receive buffer 2 size */ + RXDESC_BUFFER_1_ADDR /*!< receive frame buffer 1 address */ +}enet_descstate_enum; + +/* MSC counters preset mode */ +typedef enum +{ + ENET_MSC_PRESET_NONE = 0U, /*!< do not preset MSC counter */ + ENET_MSC_PRESET_HALF = ENET_MSC_CTL_PMC, /*!< preset all MSC counters to almost-half(0x7FFF FFF0) value */ + ENET_MSC_PRESET_FULL = ENET_MSC_CTL_PMC | ENET_MSC_CTL_AFHPM /*!< preset all MSC counters to almost-full(0xFFFF FFF0) value */ +}enet_msc_preset_enum; + +typedef enum{ + ENET_CKNT_ORDINARY = PTP_TSCTL_CKNT(0), /*!< type of ordinary clock node type for timestamp */ + ENET_CKNT_BOUNDARY = PTP_TSCTL_CKNT(1), /*!< type of boundary clock node type for timestamp */ + ENET_CKNT_END_TO_END = PTP_TSCTL_CKNT(2), /*!< type of end-to-end transparent clock node type for timestamp */ + ENET_CKNT_PEER_TO_PEER = PTP_TSCTL_CKNT(3), /*!< type of peer-to-peer transparent clock node type for timestamp */ + ENET_PTP_SYSTIME_INIT = ENET_PTP_TSCTL_TMSSTI, /*!< timestamp initialize */ + ENET_PTP_SYSTIME_UPDATE = ENET_PTP_TSCTL_TMSSTU, /*!< timestamp update */ + ENET_PTP_ADDEND_UPDATE = ENET_PTP_TSCTL_TMSARU, /*!< addend register update */ + ENET_PTP_FINEMODE = (int32_t)(ENET_PTP_TSCTL_TMSFCU| BIT(31)), /*!< the system timestamp uses the fine method for updating */ + ENET_PTP_COARSEMODE = ENET_PTP_TSCTL_TMSFCU, /*!< the system timestamp uses the coarse method for updating */ + ENET_SUBSECOND_DIGITAL_ROLLOVER = (int32_t)(ENET_PTP_TSCTL_SCROM | BIT(31)), /*!< digital rollover mode */ + ENET_SUBSECOND_BINARY_ROLLOVER = ENET_PTP_TSCTL_SCROM, /*!< binary rollover mode */ + ENET_SNOOPING_PTP_VERSION_2 = (int32_t)(ENET_PTP_TSCTL_PFSV| BIT(31)), /*!< version 2 */ + ENET_SNOOPING_PTP_VERSION_1 = ENET_PTP_TSCTL_PFSV, /*!< version 1 */ + ENET_EVENT_TYPE_MESSAGES_SNAPSHOT = (int32_t)(ENET_PTP_TSCTL_ETMSEN| BIT(31)), /*!< only event type messages are taken snapshot */ + ENET_ALL_TYPE_MESSAGES_SNAPSHOT = ENET_PTP_TSCTL_ETMSEN, /*!< all type messages are taken snapshot except announce, management and signaling message */ + ENET_MASTER_NODE_MESSAGE_SNAPSHOT = (int32_t)(ENET_PTP_TSCTL_MNMSEN| BIT(31)), /*!< snapshot is only take for master node message */ + ENET_SLAVE_NODE_MESSAGE_SNAPSHOT = ENET_PTP_TSCTL_MNMSEN /*!< snapshot is only taken for slave node message */ +}enet_ptp_function_enum; + +/* structure for initialization of the ENET */ +typedef struct +{ + uint32_t option_enable; /*!< select which function to configure */ + uint32_t forward_frame; /*!< frame forward related parameters */ + uint32_t dmabus_mode; /*!< DMA bus mode related parameters */ + uint32_t dma_maxburst; /*!< DMA max burst related parameters */ + uint32_t dma_arbitration; /*!< DMA Tx and Rx arbitration related parameters */ + uint32_t store_forward_mode; /*!< store forward mode related parameters */ + uint32_t dma_function; /*!< DMA control related parameters */ + uint32_t vlan_config; /*!< VLAN tag related parameters */ + uint32_t flow_control; /*!< flow control related parameters */ + uint32_t hashtable_high; /*!< hash list high 32-bit related parameters */ + uint32_t hashtable_low; /*!< hash list low 32-bit related parameters */ + uint32_t framesfilter_mode; /*!< frame filter control related parameters */ + uint32_t halfduplex_param; /*!< halfduplex related parameters */ + uint32_t timer_config; /*!< frame timer related parameters */ + uint32_t interframegap; /*!< inter frame gap related parameters */ +}enet_initpara_struct; + +/* structure for ENET DMA desciptors */ +typedef struct +{ + uint32_t status; /*!< status */ + uint32_t control_buffer_size; /*!< control and buffer1, buffer2 lengths */ + uint32_t buffer1_addr; /*!< buffer1 address pointer/timestamp low */ + uint32_t buffer2_next_desc_addr; /*!< buffer2 or next descriptor address pointer/timestamp high */ + +#ifdef SELECT_DESCRIPTORS_ENHANCED_MODE + uint32_t extended_status; /*!< extended status */ + uint32_t reserved; /*!< reserved */ + uint32_t timestamp_low; /*!< timestamp low */ + uint32_t timestamp_high; /*!< timestamp high */ +#endif /* SELECT_DESCRIPTORS_ENHANCED_MODE */ + +} enet_descriptors_struct; + +/* structure of PTP system time */ +typedef struct +{ + uint32_t second; /*!< second of system time */ + uint32_t nanosecond; /*!< nanosecond of system time */ + uint32_t sign; /*!< sign of system time */ +}enet_ptp_systime_struct; + +/* mac_cfg register value */ +#define MAC_CFG_BOL(regval) (BITS(5,6) & ((uint32_t)(regval) << 5)) /*!< write value to ENET_MAC_CFG_BOL bit field */ +#define ENET_BACKOFFLIMIT_10 MAC_CFG_BOL(0) /*!< min (n, 10) */ +#define ENET_BACKOFFLIMIT_8 MAC_CFG_BOL(1) /*!< min (n, 8) */ +#define ENET_BACKOFFLIMIT_4 MAC_CFG_BOL(2) /*!< min (n, 4) */ +#define ENET_BACKOFFLIMIT_1 MAC_CFG_BOL(3) /*!< min (n, 1) */ + +#define MAC_CFG_IGBS(regval) (BITS(17,19) & ((uint32_t)(regval) << 17)) /*!< write value to ENET_MAC_CFG_IGBS bit field */ +#define ENET_INTERFRAMEGAP_96BIT MAC_CFG_IGBS(0) /*!< minimum 96 bit times */ +#define ENET_INTERFRAMEGAP_88BIT MAC_CFG_IGBS(1) /*!< minimum 88 bit times */ +#define ENET_INTERFRAMEGAP_80BIT MAC_CFG_IGBS(2) /*!< minimum 80 bit times */ +#define ENET_INTERFRAMEGAP_72BIT MAC_CFG_IGBS(3) /*!< minimum 72 bit times */ +#define ENET_INTERFRAMEGAP_64BIT MAC_CFG_IGBS(4) /*!< minimum 64 bit times */ +#define ENET_INTERFRAMEGAP_56BIT MAC_CFG_IGBS(5) /*!< minimum 56 bit times */ +#define ENET_INTERFRAMEGAP_48BIT MAC_CFG_IGBS(6) /*!< minimum 48 bit times */ +#define ENET_INTERFRAMEGAP_40BIT MAC_CFG_IGBS(7) /*!< minimum 40 bit times */ + +#define ENET_TYPEFRAME_CRC_DROP_ENABLE ENET_MAC_CFG_TFCD /*!< FCS field(last 4 bytes) of frame will be dropped before forwarding */ +#define ENET_TYPEFRAME_CRC_DROP_DISABLE ((uint32_t)0x00000000U) /*!< FCS field(last 4 bytes) of frame will not be dropped before forwarding */ +#define ENET_TYPEFRAME_CRC_DROP ENET_MAC_CFG_TFCD /*!< the function that FCS field(last 4 bytes) of frame will be dropped before forwarding */ + +#define ENET_WATCHDOG_ENABLE ((uint32_t)0x00000000U) /*!< the MAC allows no more than 2048 bytes of the frame being received */ +#define ENET_WATCHDOG_DISABLE ENET_MAC_CFG_WDD /*!< the MAC disables the watchdog timer on the receiver, and can receive frames of up to 16384 bytes */ + +#define ENET_JABBER_ENABLE ((uint32_t)0x00000000U) /*!< the maximum transmission byte is 2048 */ +#define ENET_JABBER_DISABLE ENET_MAC_CFG_JBD /*!< the maximum transmission byte can be 16384 */ + +#define ENET_CARRIERSENSE_ENABLE ((uint32_t)0x00000000U) /*!< the MAC transmitter generates carrier sense error and aborts the transmission */ +#define ENET_CARRIERSENSE_DISABLE ENET_MAC_CFG_CSD /*!< the MAC transmitter ignores the MII CRS signal during frame transmission in half-duplex mode */ + +#define ENET_SPEEDMODE_10M ((uint32_t)0x00000000U) /*!< 10 Mbit/s */ +#define ENET_SPEEDMODE_100M ENET_MAC_CFG_SPD /*!< 100 Mbit/s */ + +#define ENET_RECEIVEOWN_ENABLE ((uint32_t)0x00000000U) /*!< the MAC receives all packets that are given by the PHY while transmitting */ +#define ENET_RECEIVEOWN_DISABLE ENET_MAC_CFG_ROD /*!< the MAC disables the reception of frames in half-duplex mode */ + +#define ENET_LOOPBACKMODE_ENABLE ENET_MAC_CFG_LBM /*!< the MAC operates in loopback mode at the MII */ +#define ENET_LOOPBACKMODE_DISABLE ((uint32_t)0x00000000U) /*!< the MAC operates in normal mode */ + +#define ENET_MODE_FULLDUPLEX ENET_MAC_CFG_DPM /*!< full-duplex mode enable */ +#define ENET_MODE_HALFDUPLEX ((uint32_t)0x00000000U) /*!< half-duplex mode enable */ + +#define ENET_CHECKSUMOFFLOAD_ENABLE ENET_MAC_CFG_IPFCO /*!< IP frame checksum offload function enabled for received IP frame */ +#define ENET_CHECKSUMOFFLOAD_DISABLE ((uint32_t)0x00000000U) /*!< the checksum offload function in the receiver is disabled */ + +#define ENET_RETRYTRANSMISSION_ENABLE ((uint32_t)0x00000000U) /*!< the MAC attempts retries up to 16 times based on the settings of BOL*/ +#define ENET_RETRYTRANSMISSION_DISABLE ENET_MAC_CFG_RTD /*!< the MAC attempts only 1 transmission */ + +#define ENET_AUTO_PADCRC_DROP_ENABLE ENET_MAC_CFG_APCD /*!< the MAC strips the Pad/FCS field on received frames */ +#define ENET_AUTO_PADCRC_DROP_DISABLE ((uint32_t)0x00000000U) /*!< the MAC forwards all received frames without modify it */ +#define ENET_AUTO_PADCRC_DROP ENET_MAC_CFG_APCD /*!< the function of the MAC strips the Pad/FCS field on received frames */ + +#define ENET_DEFERRALCHECK_ENABLE ENET_MAC_CFG_DFC /*!< the deferral check function is enabled in the MAC */ +#define ENET_DEFERRALCHECK_DISABLE ((uint32_t)0x00000000U) /*!< the deferral check function is disabled */ + +/* mac_frmf register value */ +#define MAC_FRMF_PCFRM(regval) (BITS(6,7) & ((uint32_t)(regval) << 6)) /*!< write value to ENET_MAC_FRMF_PCFRM bit field */ +#define ENET_PCFRM_PREVENT_ALL MAC_FRMF_PCFRM(0) /*!< MAC prevents all control frames from reaching the application */ +#define ENET_PCFRM_PREVENT_PAUSEFRAME MAC_FRMF_PCFRM(1) /*!< MAC only forwards all other control frames except pause control frame */ +#define ENET_PCFRM_FORWARD_ALL MAC_FRMF_PCFRM(2) /*!< MAC forwards all control frames to application even if they fail the address filter */ +#define ENET_PCFRM_FORWARD_FILTERED MAC_FRMF_PCFRM(3) /*!< MAC forwards control frames that only pass the address filter */ + +#define ENET_RX_FILTER_DISABLE ENET_MAC_FRMF_FAR /*!< all received frame are forwarded to application */ +#define ENET_RX_FILTER_ENABLE ((uint32_t)0x00000000U) /*!< only the frame passed the filter can be forwarded to application */ + +#define ENET_SRC_FILTER_NORMAL_ENABLE ENET_MAC_FRMF_SAFLT /*!< filter source address */ +#define ENET_SRC_FILTER_INVERSE_ENABLE (ENET_MAC_FRMF_SAFLT | ENET_MAC_FRMF_SAIFLT) /*!< inverse source address filtering result */ +#define ENET_SRC_FILTER_DISABLE ((uint32_t)0x00000000U) /*!< source address function in filter disable */ +#define ENET_SRC_FILTER ENET_MAC_FRMF_SAFLT /*!< filter source address function */ +#define ENET_SRC_FILTER_INVERSE ENET_MAC_FRMF_SAIFLT /*!< inverse source address filtering result function */ + +#define ENET_BROADCASTFRAMES_ENABLE ((uint32_t)0x00000000U) /*!< the address filters pass all received broadcast frames */ +#define ENET_BROADCASTFRAMES_DISABLE ENET_MAC_FRMF_BFRMD /*!< the address filters filter all incoming broadcast frames */ + +#define ENET_DEST_FILTER_INVERSE_ENABLE ENET_MAC_FRMF_DAIFLT /*!< inverse DA filtering result */ +#define ENET_DEST_FILTER_INVERSE_DISABLE ((uint32_t)0x00000000U) /*!< not inverse DA filtering result */ +#define ENET_DEST_FILTER_INVERSE ENET_MAC_FRMF_DAIFLT /*!< inverse DA filtering result function */ + +#define ENET_PROMISCUOUS_ENABLE ENET_MAC_FRMF_PM /*!< promiscuous mode enabled */ +#define ENET_PROMISCUOUS_DISABLE ((uint32_t)0x00000000U) /*!< promiscuous mode disabled */ + +#define ENET_MULTICAST_FILTER_HASH_OR_PERFECT (ENET_MAC_FRMF_HMF | ENET_MAC_FRMF_HPFLT) /*!< pass multicast frames that match either the perfect or the hash filtering */ +#define ENET_MULTICAST_FILTER_HASH ENET_MAC_FRMF_HMF /*!< pass multicast frames that match the hash filtering */ +#define ENET_MULTICAST_FILTER_PERFECT ((uint32_t)0x00000000U) /*!< pass multicast frames that match the perfect filtering */ +#define ENET_MULTICAST_FILTER_NONE ENET_MAC_FRMF_MFD /*!< all multicast frames are passed */ +#define ENET_MULTICAST_FILTER_PASS ENET_MAC_FRMF_MFD /*!< pass all multicast frames function */ +#define ENET_MULTICAST_FILTER_HASH_MODE ENET_MAC_FRMF_HMF /*!< HASH multicast filter function */ +#define ENET_FILTER_MODE_EITHER ENET_MAC_FRMF_HPFLT /*!< HASH or perfect filter function */ + +#define ENET_UNICAST_FILTER_EITHER (ENET_MAC_FRMF_HUF | ENET_MAC_FRMF_HPFLT) /*!< pass unicast frames that match either the perfect or the hash filtering */ +#define ENET_UNICAST_FILTER_HASH ENET_MAC_FRMF_HUF /*!< pass unicast frames that match the hash filtering */ +#define ENET_UNICAST_FILTER_PERFECT ((uint32_t)0x00000000U) /*!< pass unicast frames that match the perfect filtering */ +#define ENET_UNICAST_FILTER_HASH_MODE ENET_MAC_FRMF_HUF /*!< HASH unicast filter function */ + +/* mac_phy_ctl register value */ +#define MAC_PHY_CTL_CLR(regval) (BITS(2,4) & ((uint32_t)(regval) << 2)) /*!< write value to ENET_MAC_PHY_CTL_CLR bit field */ +#define ENET_MDC_HCLK_DIV42 MAC_PHY_CTL_CLR(0) /*!< HCLK:60-100 MHz; MDC clock= HCLK/42 */ +#define ENET_MDC_HCLK_DIV62 MAC_PHY_CTL_CLR(1) /*!< HCLK:100-150 MHz; MDC clock= HCLK/62 */ +#define ENET_MDC_HCLK_DIV16 MAC_PHY_CTL_CLR(2) /*!< HCLK:20-35 MHz; MDC clock= HCLK/16 */ +#define ENET_MDC_HCLK_DIV26 MAC_PHY_CTL_CLR(3) /*!< HCLK:35-60 MHz; MDC clock= HCLK/26 */ +#define ENET_MDC_HCLK_DIV102 MAC_PHY_CTL_CLR(4) /*!< HCLK:150-240 MHz; MDC clock= HCLK/102 */ + +#define MAC_PHY_CTL_PR(regval) (BITS(6,10) & ((uint32_t)(regval) << 6)) /*!< write value to ENET_MAC_PHY_CTL_PR bit field */ + +#define MAC_PHY_CTL_PA(regval) (BITS(11,15) & ((uint32_t)(regval) << 11)) /*!< write value to ENET_MAC_PHY_CTL_PA bit field */ + +/* mac_phy_data register value */ +#define MAC_PHY_DATA_PD(regval) (BITS(0,15) & ((uint32_t)(regval) << 0)) /*!< write value to ENET_MAC_PHY_DATA_PD bit field */ + +/* mac_fctl register value */ +#define MAC_FCTL_PLTS(regval) (BITS(4,5) & ((uint32_t)(regval) << 4)) /*!< write value to ENET_MAC_FCTL_PLTS bit field */ +#define ENET_PAUSETIME_MINUS4 MAC_FCTL_PLTS(0) /*!< pause time minus 4 slot times */ +#define ENET_PAUSETIME_MINUS28 MAC_FCTL_PLTS(1) /*!< pause time minus 28 slot times */ +#define ENET_PAUSETIME_MINUS144 MAC_FCTL_PLTS(2) /*!< pause time minus 144 slot times */ +#define ENET_PAUSETIME_MINUS256 MAC_FCTL_PLTS(3) /*!< pause time minus 256 slot times */ + +#define ENET_ZERO_QUANTA_PAUSE_ENABLE ((uint32_t)0x00000000U) /*!< enable the automatic zero-quanta generation function */ +#define ENET_ZERO_QUANTA_PAUSE_DISABLE ENET_MAC_FCTL_DZQP /*!< disable the automatic zero-quanta generation function */ +#define ENET_ZERO_QUANTA_PAUSE ENET_MAC_FCTL_DZQP /*!< the automatic zero-quanta generation function */ + +#define ENET_MAC0_AND_UNIQUE_ADDRESS_PAUSEDETECT ENET_MAC_FCTL_UPFDT /*!< besides the unique multicast address, MAC also use the MAC0 address to detect pause frame */ +#define ENET_UNIQUE_PAUSEDETECT ((uint32_t)0x00000000U) /*!< only the unique multicast address for pause frame which is specified in IEEE802.3 can be detected */ + +#define ENET_RX_FLOWCONTROL_ENABLE ENET_MAC_FCTL_RFCEN /*!< enable decoding function for the received pause frame and process it */ +#define ENET_RX_FLOWCONTROL_DISABLE ((uint32_t)0x00000000U) /*!< decode function for pause frame is disabled */ +#define ENET_RX_FLOWCONTROL ENET_MAC_FCTL_RFCEN /*!< decoding function for the received pause frame and process it */ + +#define ENET_TX_FLOWCONTROL_ENABLE ENET_MAC_FCTL_TFCEN /*!< enable the flow control operation in the MAC */ +#define ENET_TX_FLOWCONTROL_DISABLE ((uint32_t)0x00000000U) /*!< disable the flow control operation in the MAC */ +#define ENET_TX_FLOWCONTROL ENET_MAC_FCTL_TFCEN /*!< the flow control operation in the MAC */ + +#define ENET_BACK_PRESSURE_ENABLE ENET_MAC_FCTL_FLCBBKPA /*!< enable the back pressure operation in the MAC */ +#define ENET_BACK_PRESSURE_DISABLE ((uint32_t)0x00000000U) /*!< disable the back pressure operation in the MAC */ +#define ENET_BACK_PRESSURE ENET_MAC_FCTL_FLCBBKPA /*!< the back pressure operation in the MAC */ + +#define MAC_FCTL_PTM(regval) (BITS(16,31) & ((uint32_t)(regval) << 16)) /*!< write value to ENET_MAC_FCTL_PTM bit field */ +/* mac_vlt register value */ +#define MAC_VLT_VLTI(regval) (BITS(0,15) & ((uint32_t)(regval) << 0)) /*!< write value to ENET_MAC_VLT_VLTI bit field */ + +#define ENET_VLANTAGCOMPARISON_12BIT ENET_MAC_VLT_VLTC /*!< only low 12 bits of the VLAN tag are used for comparison */ +#define ENET_VLANTAGCOMPARISON_16BIT ((uint32_t)0x00000000U) /*!< all 16 bits of the VLAN tag are used for comparison */ + +/* mac_wum register value */ +#define ENET_WUM_FLAG_WUFFRPR ENET_MAC_WUM_WUFFRPR /*!< wakeup frame filter register poniter reset */ +#define ENET_WUM_FLAG_WUFR ENET_MAC_WUM_WUFR /*!< wakeup frame received */ +#define ENET_WUM_FLAG_MPKR ENET_MAC_WUM_MPKR /*!< magic packet received */ +#define ENET_WUM_POWER_DOWN ENET_MAC_WUM_PWD /*!< power down mode */ +#define ENET_WUM_MAGIC_PACKET_FRAME ENET_MAC_WUM_MPEN /*!< enable a wakeup event due to magic packet reception */ +#define ENET_WUM_WAKE_UP_FRAME ENET_MAC_WUM_WFEN /*!< enable a wakeup event due to wakeup frame reception */ +#define ENET_WUM_GLOBAL_UNICAST ENET_MAC_WUM_GU /*!< any received unicast frame passed filter is considered to be a wakeup frame */ + +/* mac_dbg register value */ +#define ENET_MAC_RECEIVER_NOT_IDLE ENET_MAC_DBG_MRNI /*!< MAC receiver is not in idle state */ +#define ENET_RX_ASYNCHRONOUS_FIFO_STATE ENET_MAC_DBG_RXAFS /*!< Rx asynchronous FIFO status */ +#define ENET_RXFIFO_WRITING ENET_MAC_DBG_RXFW /*!< RxFIFO is doing write operation */ +#define ENET_RXFIFO_READ_STATUS ENET_MAC_DBG_RXFRS /*!< RxFIFO read operation status */ +#define ENET_RXFIFO_STATE ENET_MAC_DBG_RXFS /*!< RxFIFO state */ +#define ENET_MAC_TRANSMITTER_NOT_IDLE ENET_MAC_DBG_MTNI /*!< MAC transmitter is not in idle state */ +#define ENET_MAC_TRANSMITTER_STATUS ENET_MAC_DBG_SOMT /*!< status of MAC transmitter */ +#define ENET_PAUSE_CONDITION_STATUS ENET_MAC_DBG_PCS /*!< pause condition status */ +#define ENET_TXFIFO_READ_STATUS ENET_MAC_DBG_TXFRS /*!< TxFIFO read operation status */ +#define ENET_TXFIFO_WRITING ENET_MAC_DBG_TXFW /*!< TxFIFO is doing write operation */ +#define ENET_TXFIFO_NOT_EMPTY ENET_MAC_DBG_TXFNE /*!< TxFIFO is not empty */ +#define ENET_TXFIFO_FULL ENET_MAC_DBG_TXFF /*!< TxFIFO is full */ + +#define GET_MAC_DBG_RXAFS(regval) GET_BITS((regval),1,2) /*!< get value of ENET_MAC_DBG_RXAFS bit field */ + +#define GET_MAC_DBG_RXFRS(regval) GET_BITS((regval),5,6) /*!< get value of ENET_MAC_DBG_RXFRS bit field */ + +#define GET_MAC_DBG_RXFS(regval) GET_BITS((regval),8,9) /*!< get value of ENET_MAC_DBG_RXFS bit field */ + +#define GET_MAC_DBG_SOMT(regval) GET_BITS((regval),17,18) /*!< get value of ENET_MAC_DBG_SOMT bit field */ + +#define GET_MAC_DBG_TXFRS(regval) GET_BITS((regval),20,21) /*!< get value of ENET_MAC_DBG_TXFRS bit field */ + +/* mac_addr0h register value */ +#define MAC_ADDR0H_ADDR0H(regval) (BITS(0,15) & ((uint32_t)(regval) << 0)) /*!< write value to ENET_MAC_ADDR0H_ADDR0H bit field */ + +/* mac_addrxh register value, x = 1,2,3 */ +#define MAC_ADDR123H_ADDR123H(regval) (BITS(0,15) & ((uint32_t)(regval) << 0)) /*!< write value to ENET_MAC_ADDRxH_ADDRxH(x=1,2,3) bit field */ + +#define ENET_ADDRESS_MASK_BYTE0 BIT(24) /*!< low register bits [7:0] */ +#define ENET_ADDRESS_MASK_BYTE1 BIT(25) /*!< low register bits [15:8] */ +#define ENET_ADDRESS_MASK_BYTE2 BIT(26) /*!< low register bits [23:16] */ +#define ENET_ADDRESS_MASK_BYTE3 BIT(27) /*!< low register bits [31:24] */ +#define ENET_ADDRESS_MASK_BYTE4 BIT(28) /*!< high register bits [7:0] */ +#define ENET_ADDRESS_MASK_BYTE5 BIT(29) /*!< high register bits [15:8] */ + +#define ENET_ADDRESS_FILTER_SA BIT(30) /*!< use MAC address[47:0] is to compare with the SA fields of the received frame */ +#define ENET_ADDRESS_FILTER_DA ((uint32_t)0x00000000) /*!< use MAC address[47:0] is to compare with the DA fields of the received frame */ + +/* mac_fcth register value */ +#define MAC_FCTH_RFA(regval) ((BITS(0,2) & ((uint32_t)(regval) << 0)) << 8) /*!< write value to ENET_MAC_FCTH_RFA bit field */ +#define ENET_ACTIVE_THRESHOLD_256BYTES MAC_FCTH_RFA(0) /*!< threshold level is 256 bytes */ +#define ENET_ACTIVE_THRESHOLD_512BYTES MAC_FCTH_RFA(1) /*!< threshold level is 512 bytes */ +#define ENET_ACTIVE_THRESHOLD_768BYTES MAC_FCTH_RFA(2) /*!< threshold level is 768 bytes */ +#define ENET_ACTIVE_THRESHOLD_1024BYTES MAC_FCTH_RFA(3) /*!< threshold level is 1024 bytes */ +#define ENET_ACTIVE_THRESHOLD_1280BYTES MAC_FCTH_RFA(4) /*!< threshold level is 1280 bytes */ +#define ENET_ACTIVE_THRESHOLD_1536BYTES MAC_FCTH_RFA(5) /*!< threshold level is 1536 bytes */ +#define ENET_ACTIVE_THRESHOLD_1792BYTES MAC_FCTH_RFA(6) /*!< threshold level is 1792 bytes */ + +#define MAC_FCTH_RFD(regval) ((BITS(4,6) & ((uint32_t)(regval) << 4)) << 8) /*!< write value to ENET_MAC_FCTH_RFD bit field */ +#define ENET_DEACTIVE_THRESHOLD_256BYTES MAC_FCTH_RFD(0) /*!< threshold level is 256 bytes */ +#define ENET_DEACTIVE_THRESHOLD_512BYTES MAC_FCTH_RFD(1) /*!< threshold level is 512 bytes */ +#define ENET_DEACTIVE_THRESHOLD_768BYTES MAC_FCTH_RFD(2) /*!< threshold level is 768 bytes */ +#define ENET_DEACTIVE_THRESHOLD_1024BYTES MAC_FCTH_RFD(3) /*!< threshold level is 1024 bytes */ +#define ENET_DEACTIVE_THRESHOLD_1280BYTES MAC_FCTH_RFD(4) /*!< threshold level is 1280 bytes */ +#define ENET_DEACTIVE_THRESHOLD_1536BYTES MAC_FCTH_RFD(5) /*!< threshold level is 1536 bytes */ +#define ENET_DEACTIVE_THRESHOLD_1792BYTES MAC_FCTH_RFD(6) /*!< threshold level is 1792 bytes */ + +/* msc_ctl register value */ +#define ENET_MSC_COUNTER_STOP_ROLLOVER ENET_MSC_CTL_CTSR /*!< counter stop rollover */ +#define ENET_MSC_RESET_ON_READ ENET_MSC_CTL_RTOR /*!< reset on read */ +#define ENET_MSC_COUNTERS_FREEZE ENET_MSC_CTL_MCFZ /*!< MSC counter freeze */ + +/* ptp_tsctl register value */ +#define ENET_RXTX_TIMESTAMP ENET_PTP_TSCTL_TMSEN /*!< enable timestamp function for transmit and receive frames */ +#define ENET_PTP_TIMESTAMP_INT ENET_PTP_TSCTL_TMSITEN /*!< timestamp interrupt trigger enable */ +#define ENET_ALL_RX_TIMESTAMP ENET_PTP_TSCTL_ARFSEN /*!< all received frames are taken snapshot */ +#define ENET_NONTYPE_FRAME_SNAPSHOT ENET_PTP_TSCTL_ESEN /*!< take snapshot when received non type frame */ +#define ENET_IPV6_FRAME_SNAPSHOT ENET_PTP_TSCTL_IP6SEN /*!< take snapshot for IPv6 frame */ +#define ENET_IPV4_FRAME_SNAPSHOT ENET_PTP_TSCTL_IP4SEN /*!< take snapshot for IPv4 frame */ +#define ENET_PTP_FRAME_USE_MACADDRESS_FILTER ENET_PTP_TSCTL_MAFEN /*!< enable MAC address1-3 to filter the PTP frame */ + +/* ptp_ssinc register value */ +#define PTP_SSINC_STMSSI(regval) (BITS(0,7) & ((uint32_t)(regval) << 0)) /*!< write value to ENET_PTP_SSINC_STMSSI bit field */ + +/* ptp_tsl register value */ +#define GET_PTP_TSL_STMSS(regval) GET_BITS((uint32_t)(regval),0,30) /*!< get value of ENET_PTP_TSL_STMSS bit field */ + +#define ENET_PTP_TIME_POSITIVE ((uint32_t)0x00000000) /*!< time value is positive */ +#define ENET_PTP_TIME_NEGATIVE ENET_PTP_TSL_STS /*!< time value is negative */ + +#define GET_PTP_TSL_STS(regval) (((regval) & BIT(31)) >> (31U)) /*!< get value of ENET_PTP_TSL_STS bit field */ + +/* ptp_tsul register value */ +#define PTP_TSUL_TMSUSS(regval) (BITS(0,30) & ((uint32_t)(regval) << 0)) /*!< write value to ENET_PTP_TSUL_TMSUSS bit field */ + +#define ENET_PTP_ADD_TO_TIME ((uint32_t)0x00000000) /*!< timestamp update value is added to system time */ +#define ENET_PTP_SUBSTRACT_FROM_TIME ENET_PTP_TSUL_TMSUPNS /*!< timestamp update value is subtracted from system time */ + +/* ptp_ppsctl register value */ +#define PTP_PPSCTL_PPSOFC(regval) (BITS(0,3) & ((uint32_t)(regval) << 0)) /*!< write value to ENET_PTP_PPSCTL_PPSOFC bit field */ +#define ENET_PPSOFC_1HZ PTP_PPSCTL_PPSOFC(0) /*!< PPS output 1Hz frequency */ +#define ENET_PPSOFC_2HZ PTP_PPSCTL_PPSOFC(1) /*!< PPS output 2Hz frequency */ +#define ENET_PPSOFC_4HZ PTP_PPSCTL_PPSOFC(2) /*!< PPS output 4Hz frequency */ +#define ENET_PPSOFC_8HZ PTP_PPSCTL_PPSOFC(3) /*!< PPS output 8Hz frequency */ +#define ENET_PPSOFC_16HZ PTP_PPSCTL_PPSOFC(4) /*!< PPS output 16Hz frequency */ +#define ENET_PPSOFC_32HZ PTP_PPSCTL_PPSOFC(5) /*!< PPS output 32Hz frequency */ +#define ENET_PPSOFC_64HZ PTP_PPSCTL_PPSOFC(6) /*!< PPS output 64Hz frequency */ +#define ENET_PPSOFC_128HZ PTP_PPSCTL_PPSOFC(7) /*!< PPS output 128Hz frequency */ +#define ENET_PPSOFC_256HZ PTP_PPSCTL_PPSOFC(8) /*!< PPS output 256Hz frequency */ +#define ENET_PPSOFC_512HZ PTP_PPSCTL_PPSOFC(9) /*!< PPS output 512Hz frequency */ +#define ENET_PPSOFC_1024HZ PTP_PPSCTL_PPSOFC(10) /*!< PPS output 1024Hz frequency */ +#define ENET_PPSOFC_2048HZ PTP_PPSCTL_PPSOFC(11) /*!< PPS output 2048Hz frequency */ +#define ENET_PPSOFC_4096HZ PTP_PPSCTL_PPSOFC(12) /*!< PPS output 4096Hz frequency */ +#define ENET_PPSOFC_8192HZ PTP_PPSCTL_PPSOFC(13) /*!< PPS output 8192Hz frequency */ +#define ENET_PPSOFC_16384HZ PTP_PPSCTL_PPSOFC(14) /*!< PPS output 16384Hz frequency */ +#define ENET_PPSOFC_32768HZ PTP_PPSCTL_PPSOFC(15) /*!< PPS output 32768Hz frequency */ + +/* dma_bctl register value */ +#define DMA_BCTL_DPSL(regval) (BITS(2,6) & ((uint32_t)(regval) << 2)) /*!< write value to ENET_DMA_BCTL_DPSL bit field */ +#define GET_DMA_BCTL_DPSL(regval) GET_BITS((regval),2,6) /*!< get value of ENET_DMA_BCTL_DPSL bit field */ + +#define ENET_ENHANCED_DESCRIPTOR ENET_DMA_BCTL_DFM /*!< enhanced mode descriptor */ +#define ENET_NORMAL_DESCRIPTOR ((uint32_t)0x00000000) /*!< normal mode descriptor */ + +#define DMA_BCTL_PGBL(regval) (BITS(8,13) & ((uint32_t)(regval) << 8)) /*!< write value to ENET_DMA_BCTL_PGBL bit field */ +#define ENET_PGBL_1BEAT DMA_BCTL_PGBL(1) /*!< maximum number of beats is 1 */ +#define ENET_PGBL_2BEAT DMA_BCTL_PGBL(2) /*!< maximum number of beats is 2 */ +#define ENET_PGBL_4BEAT DMA_BCTL_PGBL(4) /*!< maximum number of beats is 4 */ +#define ENET_PGBL_8BEAT DMA_BCTL_PGBL(8) /*!< maximum number of beats is 8 */ +#define ENET_PGBL_16BEAT DMA_BCTL_PGBL(16) /*!< maximum number of beats is 16 */ +#define ENET_PGBL_32BEAT DMA_BCTL_PGBL(32) /*!< maximum number of beats is 32 */ +#define ENET_PGBL_4xPGBL_4BEAT (DMA_BCTL_PGBL(1)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats is 4 */ +#define ENET_PGBL_4xPGBL_8BEAT (DMA_BCTL_PGBL(2)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats is 8 */ +#define ENET_PGBL_4xPGBL_16BEAT (DMA_BCTL_PGBL(4)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats is 16 */ +#define ENET_PGBL_4xPGBL_32BEAT (DMA_BCTL_PGBL(8)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats is 32 */ +#define ENET_PGBL_4xPGBL_64BEAT (DMA_BCTL_PGBL(16)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats is 64 */ +#define ENET_PGBL_4xPGBL_128BEAT (DMA_BCTL_PGBL(32)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats is 128 */ + +#define DMA_BCTL_RTPR(regval) (BITS(14,15) & ((uint32_t)(regval) << 14)) /*!< write value to ENET_DMA_BCTL_RTPR bit field */ +#define ENET_ARBITRATION_RXTX_1_1 DMA_BCTL_RTPR(0) /*!< receive and transmit priority ratio is 1:1*/ +#define ENET_ARBITRATION_RXTX_2_1 DMA_BCTL_RTPR(1) /*!< receive and transmit priority ratio is 2:1*/ +#define ENET_ARBITRATION_RXTX_3_1 DMA_BCTL_RTPR(2) /*!< receive and transmit priority ratio is 3:1 */ +#define ENET_ARBITRATION_RXTX_4_1 DMA_BCTL_RTPR(3) /*!< receive and transmit priority ratio is 4:1 */ +#define ENET_ARBITRATION_RXPRIORTX ENET_DMA_BCTL_DAB /*!< RxDMA has higher priority than TxDMA */ + +#define ENET_FIXED_BURST_ENABLE ENET_DMA_BCTL_FB /*!< AHB can only use SINGLE/INCR4/INCR8/INCR16 during start of normal burst transfers */ +#define ENET_FIXED_BURST_DISABLE ((uint32_t)0x00000000) /*!< AHB can use SINGLE/INCR burst transfer operations */ + +#define DMA_BCTL_RXDP(regval) (BITS(17,22) & ((uint32_t)(regval) << 17)) /*!< write value to ENET_DMA_BCTL_RXDP bit field */ +#define ENET_RXDP_1BEAT DMA_BCTL_RXDP(1) /*!< maximum number of beats 1 */ +#define ENET_RXDP_2BEAT DMA_BCTL_RXDP(2) /*!< maximum number of beats 2 */ +#define ENET_RXDP_4BEAT DMA_BCTL_RXDP(4) /*!< maximum number of beats 4 */ +#define ENET_RXDP_8BEAT DMA_BCTL_RXDP(8) /*!< maximum number of beats 8 */ +#define ENET_RXDP_16BEAT DMA_BCTL_RXDP(16) /*!< maximum number of beats 16 */ +#define ENET_RXDP_32BEAT DMA_BCTL_RXDP(32) /*!< maximum number of beats 32 */ +#define ENET_RXDP_4xPGBL_4BEAT (DMA_BCTL_RXDP(1)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats 4 */ +#define ENET_RXDP_4xPGBL_8BEAT (DMA_BCTL_RXDP(2)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats 8 */ +#define ENET_RXDP_4xPGBL_16BEAT (DMA_BCTL_RXDP(4)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats 16 */ +#define ENET_RXDP_4xPGBL_32BEAT (DMA_BCTL_RXDP(8)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats 32 */ +#define ENET_RXDP_4xPGBL_64BEAT (DMA_BCTL_RXDP(16)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats 64 */ +#define ENET_RXDP_4xPGBL_128BEAT (DMA_BCTL_RXDP(32)|ENET_DMA_BCTL_FPBL) /*!< maximum number of beats 128 */ + +#define ENET_RXTX_DIFFERENT_PGBL ENET_DMA_BCTL_UIP /*!< RxDMA uses the RXDP[5:0], while TxDMA uses the PGBL[5:0] */ +#define ENET_RXTX_SAME_PGBL ((uint32_t)0x00000000) /*!< RxDMA/TxDMA uses PGBL[5:0] */ + +#define ENET_ADDRESS_ALIGN_ENABLE ENET_DMA_BCTL_AA /*!< enabled address-aligned */ +#define ENET_ADDRESS_ALIGN_DISABLE ((uint32_t)0x00000000) /*!< disable address-aligned */ + +#define ENET_MIXED_BURST_ENABLE ENET_DMA_BCTL_MB /*!< AHB master interface transfer burst length greater than 16 with INCR */ +#define ENET_MIXED_BURST_DISABLE ((uint32_t)0x00000000) /*!< AHB master interface only transfer fixed burst length with 16 and below */ + +/* dma_stat register value */ +#define GET_DMA_STAT_RP(regval) GET_BITS((uint32_t)(regval),17,19) /*!< get value of ENET_DMA_STAT_RP bit field */ +#define ENET_RX_STATE_STOPPED ((uint32_t)0x00000000) /*!< reset or stop rx command issued */ +#define ENET_RX_STATE_FETCHING BIT(17) /*!< fetching the Rx descriptor */ +#define ENET_RX_STATE_WAITING (BIT(17)|BIT(18)) /*!< waiting for receive packet */ +#define ENET_RX_STATE_SUSPENDED BIT(19) /*!< Rx descriptor unavailable */ +#define ENET_RX_STATE_CLOSING (BIT(17)|BIT(19)) /*!< closing receive descriptor */ +#define ENET_RX_STATE_QUEUING ENET_DMA_STAT_RP /*!< transferring the receive packet data from recevie buffer to host memory */ + +#define GET_DMA_STAT_TP(regval) GET_BITS((uint32_t)(regval),20,22) /*!< get value of ENET_DMA_STAT_TP bit field */ +#define ENET_TX_STATE_STOPPED ((uint32_t)0x00000000) /*!< reset or stop Tx Command issued */ +#define ENET_TX_STATE_FETCHING BIT(20) /*!< fetching the Tx descriptor */ +#define ENET_TX_STATE_WAITING BIT(21) /*!< waiting for status */ +#define ENET_TX_STATE_READING (BIT(20)|BIT(21)) /*!< reading the data from host memory buffer and queuing it to transmit buffer */ +#define ENET_TX_STATE_SUSPENDED (BIT(21)|BIT(22)) /*!< Tx descriptor unavailabe or transmit buffer underflow */ +#define ENET_TX_STATE_CLOSING ENET_DMA_STAT_TP /*!< closing Tx descriptor */ + +#define GET_DMA_STAT_EB(regval) GET_BITS((uint32_t)(regval),23,25) /*!< get value of ENET_DMA_STAT_EB bit field */ +#define ENET_ERROR_TXDATA_TRANSFER BIT(23) /*!< error during data transfer by TxDMA or RxDMA */ +#define ENET_ERROR_READ_TRANSFER BIT(24) /*!< error during write transfer or read transfer */ +#define ENET_ERROR_DESC_ACCESS BIT(25) /*!< error during descriptor or buffer access */ + +/* dma_ctl register value */ +#define DMA_CTL_RTHC(regval) (BITS(3,4) & ((uint32_t)(regval) << 3)) /*!< write value to ENET_DMA_CTL_RTHC bit field */ +#define ENET_RX_THRESHOLD_64BYTES DMA_CTL_RTHC(0) /*!< threshold level is 64 Bytes */ +#define ENET_RX_THRESHOLD_32BYTES DMA_CTL_RTHC(1) /*!< threshold level is 32 Bytes */ +#define ENET_RX_THRESHOLD_96BYTES DMA_CTL_RTHC(2) /*!< threshold level is 96 Bytes */ +#define ENET_RX_THRESHOLD_128BYTES DMA_CTL_RTHC(3) /*!< threshold level is 128 Bytes */ + +#define DMA_CTL_TTHC(regval) (BITS(14,16) & ((uint32_t)(regval) << 14)) /*!< write value to ENET_DMA_CTL_TTHC bit field */ +#define ENET_TX_THRESHOLD_64BYTES DMA_CTL_TTHC(0) /*!< threshold level is 64 Bytes */ +#define ENET_TX_THRESHOLD_128BYTES DMA_CTL_TTHC(1) /*!< threshold level is 128 Bytes */ +#define ENET_TX_THRESHOLD_192BYTES DMA_CTL_TTHC(2) /*!< threshold level is 192 Bytes */ +#define ENET_TX_THRESHOLD_256BYTES DMA_CTL_TTHC(3) /*!< threshold level is 256 Bytes */ +#define ENET_TX_THRESHOLD_40BYTES DMA_CTL_TTHC(4) /*!< threshold level is 40 Bytes */ +#define ENET_TX_THRESHOLD_32BYTES DMA_CTL_TTHC(5) /*!< threshold level is 32 Bytes */ +#define ENET_TX_THRESHOLD_24BYTES DMA_CTL_TTHC(6) /*!< threshold level is 24 Bytes */ +#define ENET_TX_THRESHOLD_16BYTES DMA_CTL_TTHC(7) /*!< threshold level is 16 Bytes */ + +#define ENET_TCPIP_CKSUMERROR_ACCEPT ENET_DMA_CTL_DTCERFD /*!< Rx frame with only payload error but no other errors will not be dropped */ +#define ENET_TCPIP_CKSUMERROR_DROP ((uint32_t)0x00000000) /*!< all error frames will be dropped when FERF = 0 */ + +#define ENET_RX_MODE_STOREFORWARD ENET_DMA_CTL_RSFD /*!< RxFIFO operates in store-and-forward mode */ +#define ENET_RX_MODE_CUTTHROUGH ((uint32_t)0x00000000) /*!< RxFIFO operates in cut-through mode */ + +#define ENET_FLUSH_RXFRAME_ENABLE ((uint32_t)0x00000000) /*!< RxDMA flushes all frames */ +#define ENET_FLUSH_RXFRAME_DISABLE ENET_DMA_CTL_DAFRF /*!< RxDMA does not flush any frames */ +#define ENET_NO_FLUSH_RXFRAME ENET_DMA_CTL_DAFRF /*!< RxDMA flushes frames function */ + +#define ENET_TX_MODE_STOREFORWARD ENET_DMA_CTL_TSFD /*!< TxFIFO operates in store-and-forward mode */ +#define ENET_TX_MODE_CUTTHROUGH ((uint32_t)0x00000000) /*!< TxFIFO operates in cut-through mode */ + +#define ENET_FORWARD_ERRFRAMES_ENABLE (ENET_DMA_CTL_FERF << 2) /*!< all frame received with error except runt error are forwarded to memory */ +#define ENET_FORWARD_ERRFRAMES_DISABLE ((uint32_t)0x00000000) /*!< RxFIFO drop error frame */ +#define ENET_FORWARD_ERRFRAMES (ENET_DMA_CTL_FERF << 2) /*!< the function that all frame received with error except runt error are forwarded to memory */ + +#define ENET_FORWARD_UNDERSZ_GOODFRAMES_ENABLE (ENET_DMA_CTL_FUF << 2) /*!< forward undersized good frames */ +#define ENET_FORWARD_UNDERSZ_GOODFRAMES_DISABLE ((uint32_t)0x00000000) /*!< RxFIFO drops all frames whose length is less than 64 bytes */ +#define ENET_FORWARD_UNDERSZ_GOODFRAMES (ENET_DMA_CTL_FUF << 2) /*!< the function that forwarding undersized good frames */ + +#define ENET_SECONDFRAME_OPT_ENABLE ENET_DMA_CTL_OSF /*!< TxDMA controller operate on second frame mode enable*/ +#define ENET_SECONDFRAME_OPT_DISABLE ((uint32_t)0x00000000) /*!< TxDMA controller operate on second frame mode disable */ +#define ENET_SECONDFRAME_OPT ENET_DMA_CTL_OSF /*!< TxDMA controller operate on second frame function */ +/* dma_mfbocnt register value */ +#define GET_DMA_MFBOCNT_MSFC(regval) GET_BITS((regval),0,15) /*!< get value of ENET_DMA_MFBOCNT_MSFC bit field */ + +#define GET_DMA_MFBOCNT_MSFA(regval) GET_BITS((regval),17,27) /*!< get value of ENET_DMA_MFBOCNT_MSFA bit field */ + +/* dma_rswdc register value */ +#define DMA_RSWDC_WDCFRS(regval) (BITS(0,7) & ((uint32_t)(regval) << 0)) /*!< write value to ENET_DMA_RSWDC_WDCFRS bit field */ + +/* dma tx descriptor tdes0 register value */ +#define TDES0_CONT(regval) (BITS(3,6) & ((uint32_t)(regval) << 3)) /*!< write value to ENET DMA TDES0 CONT bit field */ +#define GET_TDES0_COCNT(regval) GET_BITS((regval),3,6) /*!< get value of ENET DMA TDES0 CONT bit field */ + +#define TDES0_CM(regval) (BITS(22,23) & ((uint32_t)(regval) << 22)) /*!< write value to ENET DMA TDES0 CM bit field */ +#define ENET_CHECKSUM_DISABLE TDES0_CM(0) /*!< checksum insertion disabled */ +#define ENET_CHECKSUM_IPV4HEADER TDES0_CM(1) /*!< only IP header checksum calculation and insertion are enabled */ +#define ENET_CHECKSUM_TCPUDPICMP_SEGMENT TDES0_CM(2) /*!< TCP/UDP/ICMP checksum insertion calculated but pseudo-header */ +#define ENET_CHECKSUM_TCPUDPICMP_FULL TDES0_CM(3) /*!< TCP/UDP/ICMP checksum insertion fully calculated */ + +/* dma tx descriptor tdes1 register value */ +#define TDES1_TB1S(regval) (BITS(0,12) & ((uint32_t)(regval) << 0)) /*!< write value to ENET DMA TDES1 TB1S bit field */ + +#define TDES1_TB2S(regval) (BITS(16,28) & ((uint32_t)(regval) << 16)) /*!< write value to ENET DMA TDES1 TB2S bit field */ + +/* dma rx descriptor rdes0 register value */ +#define RDES0_FRML(regval) (BITS(16,29) & ((uint32_t)(regval) << 16)) /*!< write value to ENET DMA RDES0 FRML bit field */ +#define GET_RDES0_FRML(regval) GET_BITS((regval),16,29) /*!< get value of ENET DMA RDES0 FRML bit field */ + +/* dma rx descriptor rdes1 register value */ +#define ENET_RECEIVE_COMPLETE_INT_ENABLE ((uint32_t)0x00000000U) /*!< RS bit immediately set after Rx completed */ +#define ENET_RECEIVE_COMPLETE_INT_DISABLE ENET_RDES1_DINTC /*!< RS bit not immediately set after Rx completed */ + +#define GET_RDES1_RB1S(regval) GET_BITS((regval),0,12) /*!< get value of ENET DMA RDES1 RB1S bit field */ + +#define GET_RDES1_RB2S(regval) GET_BITS((regval),16,28) /*!< get value of ENET DMA RDES1 RB2S bit field */ + +/* dma rx descriptor rdes4 register value */ +#define RDES4_IPPLDT(regval) (BITS(0,2) & ((uint32_t)(regval) << 0)) /*!< write value to ENET DMA RDES4 IPPLDT bit field */ +#define GET_RDES4_IPPLDT(regval) GET_BITS((regval),0,2) /*!< get value of ENET DMA RDES4 IPPLDT bit field */ + +#define RDES4_PTPMT(regval) (BITS(8,11) & ((uint32_t)(regval) << 8)) /*!< write value to ENET DMA RDES4 PTPMT bit field */ +#define GET_RDES4_PTPMT(regval) GET_BITS((regval),8,11) /*!< get value of ENET DMA RDES4 PTPMT bit field */ + +/* ENET register mask value */ +#define MAC_CFG_MASK ((uint32_t)0xFD30810FU) /*!< ENET_MAC_CFG register mask */ +#define MAC_FCTL_MASK ((uint32_t)0x0000FF41U) /*!< ENET_MAC_FCTL register mask */ +#define DMA_CTL_MASK ((uint32_t)0xF8DE3F23U) /*!< ENET_DMA_CTL register mask */ +#define DMA_BCTL_MASK ((uint32_t)0xF800007DU) /*!< ENET_DMA_BCTL register mask */ +#define ENET_MSC_PRESET_MASK (~(ENET_MSC_CTL_PMC | ENET_MSC_CTL_AFHPM)) /*!< ENET_MSC_CTL preset mask */ + +#ifdef SELECT_DESCRIPTORS_ENHANCED_MODE +#define ETH_DMATXDESC_SIZE ((uint32_t)0x00000020U) /*!< TxDMA enhanced descriptor size */ +#define ETH_DMARXDESC_SIZE ((uint32_t)0x00000020U) /*!< RxDMA enhanced descriptor size */ +#else +#define ETH_DMATXDESC_SIZE ((uint32_t)0x00000010U) /*!< TxDMA descriptor size */ +#define ETH_DMARXDESC_SIZE ((uint32_t)0x00000010U) /*!< RxDMA descriptor size */ +#endif /* SELECT_DESCRIPTORS_ENHANCED_MODE */ + +/* ENET remote wake-up frame register length */ +#define ETH_WAKEUP_REGISTER_LENGTH 8U /*!< remote wake-up frame register length */ + +/* ENET frame size */ +#define ENET_MAX_FRAME_SIZE 1524U /*!< header + frame_extra + payload + CRC */ + +/* ENET delay timeout */ +#define ENET_DELAY_TO ((uint32_t)0x0004FFFFU) /*!< ENET delay timeout */ +#define ENET_RESET_TO ((uint32_t)0x000004FFU) /*!< ENET reset timeout */ + + + +/* function declarations */ +/* main function */ +/* deinitialize the ENET, and reset structure parameters for ENET initialization */ +void enet_deinit(void); +/* configure the parameters which are usually less cared for initialization */ +void enet_initpara_config(enet_option_enum option, uint32_t para); +/* initialize ENET peripheral with generally concerned parameters and the less cared parameters */ +ErrStatus enet_init(enet_mediamode_enum mediamode, enet_chksumconf_enum checksum, enet_frmrecept_enum recept); +/* reset all core internal registers located in CLK_TX and CLK_RX */ +ErrStatus enet_software_reset(void); +/* check receive frame valid and return frame size */ +uint32_t enet_rxframe_size_get(void); +/* initialize the dma tx/rx descriptors's parameters in chain mode */ +void enet_descriptors_chain_init(enet_dmadirection_enum direction); +/* initialize the dma tx/rx descriptors's parameters in ring mode */ +void enet_descriptors_ring_init(enet_dmadirection_enum direction); +/* handle current received frame data to application buffer */ +ErrStatus enet_frame_receive(uint8_t *buffer, uint32_t bufsize); +/* handle current received frame but without data copy to application buffer */ +#define ENET_NOCOPY_FRAME_RECEIVE() enet_frame_receive(NULL, 0U) +/* handle application buffer data to transmit it */ +ErrStatus enet_frame_transmit(uint8_t *buffer, uint32_t length); +/* handle current transmit frame but without data copy from application buffer */ +#define ENET_NOCOPY_FRAME_TRANSMIT(len) enet_frame_transmit(NULL, (len)) +/* configure the transmit IP frame checksum offload calculation and insertion */ +ErrStatus enet_transmit_checksum_config(enet_descriptors_struct *desc, uint32_t checksum); +/* ENET Tx and Rx function enable (include MAC and DMA module) */ +void enet_enable(void); +/* ENET Tx and Rx function disable (include MAC and DMA module) */ +void enet_disable(void); +/* configure MAC address */ +void enet_mac_address_set(enet_macaddress_enum mac_addr, uint8_t paddr[]); +/* get MAC address */ +ErrStatus enet_mac_address_get(enet_macaddress_enum mac_addr, uint8_t paddr[], uint8_t bufsize); + +/* get the ENET MAC/MSC/PTP/DMA status flag */ +FlagStatus enet_flag_get(enet_flag_enum enet_flag); +/* clear the ENET DMA status flag */ +void enet_flag_clear(enet_flag_clear_enum enet_flag); +/* enable ENET MAC/MSC/DMA interrupt */ +void enet_interrupt_enable(enet_int_enum enet_int); +/* disable ENET MAC/MSC/DMA interrupt */ +void enet_interrupt_disable(enet_int_enum enet_int); +/* get ENET MAC/MSC/DMA interrupt flag */ +FlagStatus enet_interrupt_flag_get(enet_int_flag_enum int_flag); +/* clear ENET DMA interrupt flag */ +void enet_interrupt_flag_clear(enet_int_flag_clear_enum int_flag_clear); + +/* MAC function */ +/* ENET Tx function enable (include MAC and DMA module) */ +void enet_tx_enable(void); +/* ENET Tx function disable (include MAC and DMA module) */ +void enet_tx_disable(void); +/* ENET Rx function enable (include MAC and DMA module) */ +void enet_rx_enable(void); +/* ENET Rx function disable (include MAC and DMA module) */ +void enet_rx_disable(void); +/* put registers value into the application buffer */ +void enet_registers_get(enet_registers_type_enum type, uint32_t *preg, uint32_t num); +/* get the enet debug status from the debug register */ +uint32_t enet_debug_status_get(uint32_t mac_debug); +/* enable the MAC address filter */ +void enet_address_filter_enable(enet_macaddress_enum mac_addr); +/* disable the MAC address filter */ +void enet_address_filter_disable(enet_macaddress_enum mac_addr); +/* configure the MAC address filter */ +void enet_address_filter_config(enet_macaddress_enum mac_addr, uint32_t addr_mask, uint32_t filter_type); +/* PHY interface configuration (configure SMI clock and reset PHY chip) */ +ErrStatus enet_phy_config(void); +/* write to/read from a PHY register */ +ErrStatus enet_phy_write_read(enet_phydirection_enum direction, uint16_t phy_address, uint16_t phy_reg, uint16_t *pvalue); +/* enable the loopback function of phy chip */ +ErrStatus enet_phyloopback_enable(void); +/* disable the loopback function of phy chip */ +ErrStatus enet_phyloopback_disable(void); +/* enable ENET forward feature */ +void enet_forward_feature_enable(uint32_t feature); +/* disable ENET forward feature */ +void enet_forward_feature_disable(uint32_t feature); +/* enable ENET fliter feature */ +void enet_fliter_feature_enable(uint32_t feature); +/* disable ENET fliter feature */ +void enet_fliter_feature_disable(uint32_t feature); + +/* flow control function */ +/* generate the pause frame, ENET will send pause frame after enable transmit flow control */ +ErrStatus enet_pauseframe_generate(void); +/* configure the pause frame detect type */ +void enet_pauseframe_detect_config(uint32_t detect); +/* configure the pause frame parameters */ +void enet_pauseframe_config(uint32_t pausetime, uint32_t pause_threshold); +/* configure the threshold of the flow control(deactive and active threshold) */ +void enet_flowcontrol_threshold_config(uint32_t deactive, uint32_t active); +/* enable ENET flow control feature */ +void enet_flowcontrol_feature_enable(uint32_t feature); +/* disable ENET flow control feature */ +void enet_flowcontrol_feature_disable(uint32_t feature); + +/* DMA function */ +/* get the dma transmit/receive process state */ +uint32_t enet_dmaprocess_state_get(enet_dmadirection_enum direction); +/* poll the dma transmission/reception enable */ +void enet_dmaprocess_resume(enet_dmadirection_enum direction); +/* check and recover the Rx process */ +void enet_rxprocess_check_recovery(void); +/* flush the ENET transmit fifo, and wait until the flush operation completes */ +ErrStatus enet_txfifo_flush(void); +/* get the transmit/receive address of current descriptor, or current buffer, or descriptor table */ +uint32_t enet_current_desc_address_get(enet_desc_reg_enum addr_get); +/* get the Tx or Rx descriptor information */ +uint32_t enet_desc_information_get(enet_descriptors_struct *desc, enet_descstate_enum info_get); +/* get the number of missed frames during receiving */ +void enet_missed_frame_counter_get(uint32_t *rxfifo_drop, uint32_t *rxdma_drop); + +/* descriptor function */ +/* get the bit flag of ENET dma descriptor */ +FlagStatus enet_desc_flag_get(enet_descriptors_struct *desc, uint32_t desc_flag); +/* set the bit flag of ENET dma tx descriptor */ +void enet_desc_flag_set(enet_descriptors_struct *desc, uint32_t desc_flag); +/* clear the bit flag of ENET dma tx descriptor */ +void enet_desc_flag_clear(enet_descriptors_struct *desc, uint32_t desc_flag); +/* when receiving the completed, set RS bit in ENET_DMA_STAT register will immediately set */ +void enet_rx_desc_immediate_receive_complete_interrupt(enet_descriptors_struct *desc); +/* when receiving the completed, set RS bit in ENET_DMA_STAT register will is set after a configurable delay time */ +void enet_rx_desc_delay_receive_complete_interrupt(enet_descriptors_struct *desc, uint32_t delay_time); +/* drop current receive frame */ +void enet_rxframe_drop(void); +/* enable DMA feature */ +void enet_dma_feature_enable(uint32_t feature); +/* disable DMA feature */ +void enet_dma_feature_disable(uint32_t feature); + + +/* special enhanced mode function */ +#ifdef SELECT_DESCRIPTORS_ENHANCED_MODE +/* get the bit of extended status flag in ENET DMA descriptor */ +uint32_t enet_rx_desc_enhanced_status_get(enet_descriptors_struct *desc, uint32_t desc_status); +/* configure descriptor to work in enhanced mode */ +void enet_desc_select_enhanced_mode(void); +/* initialize the dma Tx/Rx descriptors's parameters in enhanced chain mode with ptp function */ +void enet_ptp_enhanced_descriptors_chain_init(enet_dmadirection_enum direction); +/* initialize the dma Tx/Rx descriptors's parameters in enhanced ring mode with ptp function */ +void enet_ptp_enhanced_descriptors_ring_init(enet_dmadirection_enum direction); +/* receive a packet data with timestamp values to application buffer, when the DMA is in enhanced mode */ +ErrStatus enet_ptpframe_receive_enhanced_mode(uint8_t *buffer, uint32_t bufsize, uint32_t timestamp[]); +/* handle current received frame but without data copy to application buffer in PTP enhanced mode */ +#define ENET_NOCOPY_PTPFRAME_RECEIVE_ENHANCED_MODE(ptr) enet_ptpframe_receive_enhanced_mode(NULL, 0U, (ptr)) +/* send data with timestamp values in application buffer as a transmit packet, when the DMA is in enhanced mode */ +ErrStatus enet_ptpframe_transmit_enhanced_mode(uint8_t *buffer, uint32_t length, uint32_t timestamp[]); +/* handle current transmit frame but without data copy from application buffer in PTP enhanced mode */ +#define ENET_NOCOPY_PTPFRAME_TRANSMIT_ENHANCED_MODE(len, ptr) enet_ptpframe_transmit_enhanced_mode(NULL, (len), (ptr)) + +#else + +/* configure descriptor to work in normal mode */ +void enet_desc_select_normal_mode(void); +/* initialize the dma Tx/Rx descriptors's parameters in normal chain mode with ptp function */ +void enet_ptp_normal_descriptors_chain_init(enet_dmadirection_enum direction, enet_descriptors_struct *desc_ptptab); +/* initialize the dma Tx/Rx descriptors's parameters in normal ring mode with ptp function */ +void enet_ptp_normal_descriptors_ring_init(enet_dmadirection_enum direction, enet_descriptors_struct *desc_ptptab); +/* receive a packet data with timestamp values to application buffer, when the DMA is in normal mode */ +ErrStatus enet_ptpframe_receive_normal_mode(uint8_t *buffer, uint32_t bufsize, uint32_t timestamp[]); +/* handle current received frame but without data copy to application buffer in PTP normal mode */ +#define ENET_NOCOPY_PTPFRAME_RECEIVE_NORMAL_MODE(ptr) enet_ptpframe_receive_normal_mode(NULL, 0U, (ptr)) +/* send data with timestamp values in application buffer as a transmit packet, when the DMA is in normal mode */ +ErrStatus enet_ptpframe_transmit_normal_mode(uint8_t *buffer, uint32_t length, uint32_t timestamp[]); +/* handle current transmit frame but without data copy from application buffer in PTP normal mode */ +#define ENET_NOCOPY_PTPFRAME_TRANSMIT_NORMAL_MODE(len, ptr) enet_ptpframe_transmit_normal_mode(NULL, (len), (ptr)) + +#endif /* SELECT_DESCRIPTORS_ENHANCED_MODE */ + +/* WUM function */ +/* wakeup frame filter register pointer reset */ +void enet_wum_filter_register_pointer_reset(void); +/* set the remote wakeup frame registers */ +void enet_wum_filter_config(uint32_t pdata[]); +/* enable wakeup management features */ +void enet_wum_feature_enable(uint32_t feature); +/* disable wakeup management features */ +void enet_wum_feature_disable(uint32_t feature); + +/* MSC function */ +/* reset the MAC statistics counters */ +void enet_msc_counters_reset(void); +/* enable the MAC statistics counter features */ +void enet_msc_feature_enable(uint32_t feature); +/* disable the MAC statistics counter features */ +void enet_msc_feature_disable(uint32_t feature); +/* configure MAC statistics counters preset mode */ +void enet_msc_counters_preset_config(enet_msc_preset_enum mode); +/* get MAC statistics counter */ +uint32_t enet_msc_counters_get(enet_msc_counter_enum counter); + +/* PTP function */ +/* change subsecond to nanosecond */ +uint32_t enet_ptp_subsecond_2_nanosecond(uint32_t subsecond); +/* change nanosecond to subsecond */ +uint32_t enet_ptp_nanosecond_2_subsecond(uint32_t nanosecond); +/* enable the PTP features */ +void enet_ptp_feature_enable(uint32_t feature); +/* disable the PTP features */ +void enet_ptp_feature_disable(uint32_t feature); +/* configure the PTP timestamp function */ +ErrStatus enet_ptp_timestamp_function_config(enet_ptp_function_enum func); +/* configure the PTP system time subsecond increment value */ +void enet_ptp_subsecond_increment_config(uint32_t subsecond); +/* adjusting the PTP clock frequency only in fine update mode */ +void enet_ptp_timestamp_addend_config(uint32_t add); +/* initializing or adding/subtracting to second of the PTP system time */ +void enet_ptp_timestamp_update_config(uint32_t sign, uint32_t second, uint32_t subsecond); +/* configure the PTP expected target time */ +void enet_ptp_expected_time_config(uint32_t second, uint32_t nanosecond); +/* get the PTP current system time */ +void enet_ptp_system_time_get(enet_ptp_systime_struct *systime_struct); +/* configure the PPS output frequency */ +void enet_ptp_pps_output_frequency_config(uint32_t freq); +/* configure and start PTP timestamp counter */ +void enet_ptp_start(int32_t updatemethod, uint32_t init_sec, uint32_t init_subsec, uint32_t carry_cfg, uint32_t accuracy_cfg); +/* adjust frequency in fine method by configure addend register */ +void enet_ptp_finecorrection_adjfreq(int32_t carry_cfg); +/* update system time in coarse method */ +void enet_ptp_coarsecorrection_systime_update(enet_ptp_systime_struct *systime_struct); +/* set system time in fine method */ +void enet_ptp_finecorrection_settime(enet_ptp_systime_struct * systime_struct); +/* get the ptp flag status */ +FlagStatus enet_ptp_flag_get(uint32_t flag); + +/* internal function */ +/* reset the ENET initpara struct, call it before using enet_initpara_config() */ +void enet_initpara_reset(void); +#ifdef USE_DELAY +/* user can provide more timing precise _ENET_DELAY_ function */ +#define _ENET_DELAY_ delay_ms +#else +/* default _ENET_DELAY_ function with less precise timing */ +#define _ENET_DELAY_ enet_delay +#endif + +#endif /* GD32F5XX_ENET_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_exmc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_exmc.h new file mode 100644 index 0000000..41d7208 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_exmc.h @@ -0,0 +1,812 @@ +/*! + \file gd32f5xx_exmc.h + \brief definitions for the EXMC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_EXMC_H +#define GD32F5XX_EXMC_H + +#include "gd32f5xx.h" + +/* EXMC definitions */ +#define EXMC (EXMC_BASE) /*!< EXMC register base address */ +#define EXMC_NOR_PSRAM (EXMC_BASE - 0x40000000U) /*!< EXMC NOR/PSRAM base address */ +#define EXMC_NAND (EXMC_BASE - 0x30000000U) /*!< EXMC NAND base address */ +#define EXMC_PCCARD (EXMC_BASE - 0x10000000U) /*!< EXMC PC card base address */ +#define EXMC_SDRAM (EXMC_BASE + 0x20000000U) /*!< EXMC SDRAM base address */ + +/* registers definitions */ +/* NOR/PSRAM */ +#define EXMC_SNCTL0 REG32(EXMC + 0x00000000U) /*!< EXMC SRAM/NOR flash control register for region0 */ +#define EXMC_SNTCFG0 REG32(EXMC + 0x00000004U) /*!< EXMC SRAM/NOR flash timing configuration register for region0 */ +#define EXMC_SNWTCFG0 REG32(EXMC + 0x00000104U) /*!< EXMC SRAM/NOR flash write timing configuration register for region0 */ + +#define EXMC_SNCTL1 REG32(EXMC + 0x00000008U) /*!< EXMC SRAM/NOR flash control register for region1 */ +#define EXMC_SNTCFG1 REG32(EXMC + 0x0000000CU) /*!< EXMC SRAM/NOR flash timing configuration register for region1 */ +#define EXMC_SNWTCFG1 REG32(EXMC + 0x0000010CU) /*!< EXMC SRAM/NOR flash write timing configuration register for region1 */ + +#define EXMC_SNCTL2 REG32(EXMC + 0x00000010U) /*!< EXMC SRAM/NOR flash control register for region2 */ +#define EXMC_SNTCFG2 REG32(EXMC + 0x00000014U) /*!< EXMC SRAM/NOR flash timing configuration register for region2 */ +#define EXMC_SNWTCFG2 REG32(EXMC + 0x00000114U) /*!< EXMC SRAM/NOR flash write timing configuration register for region2 */ + +#define EXMC_SNCTL3 REG32(EXMC + 0x00000018U) /*!< EXMC SRAM/NOR flash control register for region3 */ +#define EXMC_SNTCFG3 REG32(EXMC + 0x0000001CU) /*!< EXMC SRAM/NOR flash timing configuration register for region3 */ +#define EXMC_SNWTCFG3 REG32(EXMC + 0x0000011CU) /*!< EXMC SRAM/NOR flash write timing configuration register for region3 */ + +#define EXMC_SNLATDEC0 REG32(EXMC + 0x00000300U) /*!< EXMC SRAM/NOR flash data latency decrease register0 */ +#define EXMC_SNLATDEC1 REG32(EXMC + 0x00000304U) /*!< EXMC SRAM/NOR flash data latency decrease register1 */ +#define EXMC_SNLATDEC2 REG32(EXMC + 0x00000308U) /*!< EXMC SRAM/NOR flash data latency decrease register2 */ +#define EXMC_SNLATDEC3 REG32(EXMC + 0x0000030CU) /*!< EXMC SRAM/NOR flash data latency decrease register3 */ + +/* NAND/PC card */ +#define EXMC_NPCTL1 REG32(EXMC + 0x00000060U) /*!< EXMC NAND/PC card control register for bank1 */ +#define EXMC_NPINTEN1 REG32(EXMC + 0x00000064U) /*!< EXMC NAND/PC card interrupt enable register for bank1 */ +#define EXMC_NPCTCFG1 REG32(EXMC + 0x00000068U) /*!< EXMC NAND/PC card common space timing configuration register for bank1 */ +#define EXMC_NPATCFG1 REG32(EXMC + 0x0000006CU) /*!< EXMC NAND/PC card attribute space timing configuration register for bank1 */ +#define EXMC_NECC1 REG32(EXMC + 0x00000074U) /*!< EXMC NAND ECC register */ + +#define EXMC_NPCTL2 REG32(EXMC + 0x00000080U) /*!< EXMC NAND/PC card control register for bank2 */ +#define EXMC_NPINTEN2 REG32(EXMC + 0x00000084U) /*!< EXMC NAND/PC card interrupt enable register for bank2 */ +#define EXMC_NPCTCFG2 REG32(EXMC + 0x00000088U) /*!< EXMC NAND/PC card common space timing configuration register for bank2 */ +#define EXMC_NPATCFG2 REG32(EXMC + 0x0000008CU) /*!< EXMC NAND/PC card attribute space timing configuration register for bank2 */ +#define EXMC_NECC2 REG32(EXMC + 0x00000094U) /*!< EXMC NAND ECC register */ + +#define EXMC_NPCTL3 REG32(EXMC + 0x000000A0U) /*!< EXMC NAND/PC card control register for bank3 */ +#define EXMC_NPINTEN3 REG32(EXMC + 0x000000A4U) /*!< EXMC NAND/PC card interrupt enable register for bank3 */ +#define EXMC_NPCTCFG3 REG32(EXMC + 0x000000A8U) /*!< EXMC NAND/PC card common space timing configuration register for bank3 */ +#define EXMC_NPATCFG3 REG32(EXMC + 0x000000ACU) /*!< EXMC NAND/PC card attribute space timing configuration register for bank3 */ +#define EXMC_PIOTCFG3 REG32(EXMC + 0x000000B0U) /*!< EXMC PC card I/O space timing configuration register for bank3 */ + +/* SDRAM */ +#define EXMC_SDCTL0 REG32(EXMC + 0x00000140U) /*!< EXMC SDRAM control register for device0 */ +#define EXMC_SDTCFG0 REG32(EXMC + 0x00000148U) /*!< EXMC SDRAM timing configuration register register for device0 */ + +#define EXMC_SDCTL1 REG32(EXMC + 0x00000144U) /*!< EXMC SDRAM control register for device1 */ +#define EXMC_SDTCFG1 REG32(EXMC + 0x0000014CU) /*!< EXMC SDRAM timing configuration register register for device1 */ + +#define EXMC_SDCMD REG32(EXMC + 0x00000150U) /*!< EXMC SDRAM command register */ +#define EXMC_SDARI REG32(EXMC + 0x00000154U) /*!< EXMC SDRAM auto-refresh interval register */ +#define EXMC_SDSTAT REG32(EXMC + 0x00000158U) /*!< EXMC SDRAM status register */ +#define EXMC_SDRSCTL REG32(EXMC + 0x00000180U) /*!< EXMC SDRAM read sample control register */ + +/* SQPI PSRAM */ +#define EXMC_SINIT REG32(EXMC + 0x00000310U) /*!< EXMC SPI initialization register */ +#define EXMC_SRCMD REG32(EXMC + 0x00000320U) /*!< EXMC SPI read command register */ +#define EXMC_SWCMD REG32(EXMC + 0x00000330U) /*!< EXMC SPI write command register */ +#define EXMC_SIDL REG32(EXMC + 0x00000340U) /*!< EXMC SPI ID low register */ +#define EXMC_SIDH REG32(EXMC + 0x00000350U) /*!< EXMC SPI ID high register */ + +/* bits definitions */ +/* EXMC_SNCTLx,x=0..3 */ +#define EXMC_SNCTL_NRBKEN BIT(0) /*!< NOR bank enable */ +#define EXMC_SNCTL_NRMUX BIT(1) /*!< NOR bank memory address/data multiplexing enable */ +#define EXMC_SNCTL_NRTP BITS(2,3) /*!< NOR bank memory type */ +#define EXMC_SNCTL_NRW BITS(4,5) /*!< NOR bank memory data bus width */ +#define EXMC_SNCTL_NREN BIT(6) /*!< NOR flash access enable */ +#define EXMC_SNCTL_SBRSTEN BIT(8) /*!< synchronous burst enable */ +#define EXMC_SNCTL_NRWTPOL BIT(9) /*!< NWAIT signal polarity */ +#define EXMC_SNCTL_WRAPEN BIT(10) /*!< wrapped burst mode enable */ +#define EXMC_SNCTL_NRWTCFG BIT(11) /*!< NWAIT signal configuration, only work in synchronous mode */ +#define EXMC_SNCTL_WEN BIT(12) /*!< write enable */ +#define EXMC_SNCTL_NRWTEN BIT(13) /*!< NWAIT signal enable */ +#define EXMC_SNCTL_EXMODEN BIT(14) /*!< extended mode enable */ +#define EXMC_SNCTL_ASYNCWTEN BIT(15) /*!< asynchronous wait enable */ +#define EXMC_SNCTL_CPS BITS(16,18) /*!< CRAM page size */ +#define EXMC_SNCTL_SYNCWR BIT(19) /*!< synchronous write configuration */ +#define EXMC_SNCTL_CCK BIT(20) /*!< consecutive clock configuration */ + +/* EXMC_SNTCFGx,x=0..3 */ +#define EXMC_SNTCFG_ASET BITS(0,3) /*!< asynchronous address setup time */ +#define EXMC_SNTCFG_AHLD BITS(4,7) /*!< asynchronous address hold time */ +#define EXMC_SNTCFG_DSET BITS(8,15) /*!< asynchronous data setup time */ +#define EXMC_SNTCFG_BUSLAT BITS(16,19) /*!< bus latency */ +#define EXMC_SNTCFG_CKDIV BITS(20,23) /*!< synchronous clock divide ratio */ +#define EXMC_SNTCFG_DLAT BITS(24,27) /*!< synchronous data latency for NOR flash */ +#define EXMC_SNTCFG_ASYNCMOD BITS(28,29) /*!< asynchronous access mode */ + +/* EXMC_SNWTCFGx,x=0..3 */ +#define EXMC_SNWTCFG_WASET BITS(0,3) /*!< asynchronous address setup time */ +#define EXMC_SNWTCFG_WAHLD BITS(4,7) /*!< asynchronous address hold time */ +#define EXMC_SNWTCFG_WDSET BITS(8,15) /*!< asynchronous data setup time */ +#define EXMC_SNWTCFG_WBUSLAT BITS(16,19) /*!< bus latency */ +#define EXMC_SNWTCFG_WASYNCMOD BITS(28,29) /*!< asynchronous access mode */ + +/* EXMC_SNLATDECx,x=0..3 */ +#define EXMC_SNLATDEC_LATDEC BITS(0,2) /*!< data latency decrease for NOR Flash and only valid in synchronous read access */ + +/* EXMC_NPCTLx,x=1..3 */ +#define EXMC_NPCTL_NDWTEN BIT(1) /*!< wait feature enable */ +#define EXMC_NPCTL_NDBKEN BIT(2) /*!< NAND bank enable */ +#define EXMC_NPCTL_NDTP BIT(3) /*!< NAND bank memory type */ +#define EXMC_NPCTL_NDW BITS(4,5) /*!< NAND bank memory data bus width */ +#define EXMC_NPCTL_ECCEN BIT(6) /*!< ECC enable */ +#define EXMC_NPCTL_CTR BITS(9,12) /*!< CLE to RE delay */ +#define EXMC_NPCTL_ATR BITS(13,16) /*!< ALE to RE delay */ +#define EXMC_NPCTL_ECCSZ BITS(17,19) /*!< ECC size */ + +/* EXMC_NPINTENx,x=1..3 */ +#define EXMC_NPINTEN_INTRS BIT(0) /*!< interrupt rising edge status */ +#define EXMC_NPINTEN_INTHS BIT(1) /*!< interrupt high-level status */ +#define EXMC_NPINTEN_INTFS BIT(2) /*!< interrupt falling edge status */ +#define EXMC_NPINTEN_INTREN BIT(3) /*!< interrupt rising edge detection enable */ +#define EXMC_NPINTEN_INTHEN BIT(4) /*!< interrupt high-level detection enable */ +#define EXMC_NPINTEN_INTFEN BIT(5) /*!< interrupt falling edge detection enable */ +#define EXMC_NPINTEN_FFEPT BIT(6) /*!< FIFO empty flag */ + +/* EXMC_NPCTCFGx,x=1..3 */ +#define EXMC_NPCTCFG_COMSET BITS(0,7) /*!< common memory setup time */ +#define EXMC_NPCTCFG_COMWAIT BITS(8,15) /*!< common memory wait time */ +#define EXMC_NPCTCFG_COMHLD BITS(16,23) /*!< common memory hold time */ +#define EXMC_NPCTCFG_COMHIZ BITS(24,31) /*!< common memory data bus HiZ time */ + +/* EXMC_NPATCFGx,x=1..3 */ +#define EXMC_NPATCFG_ATTSET BITS(0,7) /*!< attribute memory setup time */ +#define EXMC_NPATCFG_ATTWAIT BITS(8,15) /*!< attribute memory wait time */ +#define EXMC_NPATCFG_ATTHLD BITS(16,23) /*!< attribute memory hold time */ +#define EXMC_NPATCFG_ATTHIZ BITS(24,31) /*!< attribute memory data bus HiZ time */ + +/* EXMC_PIOTCFG3 */ +#define EXMC_PIOTCFG3_IOSET BITS(0,7) /*!< IO space setup time */ +#define EXMC_PIOTCFG3_IOWAIT BITS(8,15) /*!< IO space wait time */ +#define EXMC_PIOTCFG3_IOHLD BITS(16,23) /*!< IO space hold time */ +#define EXMC_PIOTCFG3_IOHIZ BITS(24,31) /*!< IO space data bus HiZ time */ + +/* EXMC_NECCx,x=1..2 */ +#define EXMC_NECC_ECC BITS(0,31) /*!< ECC result */ + +/* EXMC_SDCTLx,x=0..1 */ +#define EXMC_SDCTL_CAW BITS(0,1) /*!< column address bit width */ +#define EXMC_SDCTL_RAW BITS(2,3) /*!< row address bit width */ +#define EXMC_SDCTL_SDW BITS(4,5) /*!< SDRAM data bus width */ +#define EXMC_SDCTL_NBK BIT(6) /*!< number of banks */ +#define EXMC_SDCTL_CL BIT(7,8) /*!< CAS Latency */ +#define EXMC_SDCTL_WPEN BIT(9) /*!< write protection enable */ +#define EXMC_SDCTL_SDCLK BITS(10,11) /*!< SDRAM clock configuration */ +#define EXMC_SDCTL_BRSTRD BIT(12) /*!< burst read enable */ +#define EXMC_SDCTL_PIPED BITS(13,14) /*!< pipeline delay */ + +/* EXMC_SDTCFGx,x=0..1 */ +#define EXMC_SDTCFG_LMRD BITS(0,3) /*!< load mode register delay */ +#define EXMC_SDTCFG_XSRD BITS(4,7) /*!< exit self-refresh delay */ +#define EXMC_SDTCFG_RASD BITS(8,11) /*!< row address select delay */ +#define EXMC_SDTCFG_ARFD BITS(12,15) /*!< auto refresh delay */ +#define EXMC_SDTCFG_WRD BITS(16,19) /*!< write recovery delay */ +#define EXMC_SDTCFG_RPD BITS(20,23) /*!< row precharge delay */ +#define EXMC_SDTCFG_RCD BITS(24,27) /*!< row to column delay */ + +/* EXMC_SDCMD */ +#define EXMC_SDCMD_CMD BITS(0,2) /*!< command */ +#define EXMC_SDCMD_DS1 BIT(3) /*!< select device1 */ +#define EXMC_SDCMD_DS0 BIT(4) /*!< select device0 */ +#define EXMC_SDCMD_NARF BITS(5,8) /*!< number of successive auto-refresh */ +#define EXMC_SDCMD_MRC BITS(9,21) /*!< mode register content */ + +/* EXMC_SDARI */ +#define EXMC_SDARI_REC BIT(0) /*!< refresh error flag clear */ +#define EXMC_SDARI_ARINTV BITS(1,13) /*!< auto-refresh interval */ +#define EXMC_SDARI_REIE BIT(14) /*!< refresh error interrupt enable */ + +/* EXMC_SDSTAT */ +#define EXMC_SDSDAT_REIF BIT(0) /*!< refresh error interrupt flag */ +#define EXMC_SDSDAT_STA0 BITS(1,2) /*!< device0 status */ +#define EXMC_SDSDAT_STA1 BITS(3,4) /*!< device1 status */ +#define EXMC_SDSDAT_NRDY BIT(5) /*!< not ready status */ + +/* EXMC_SDRSCTL */ +#define EXMC_SDRSCTL_RSEN BIT(0) /*!< read sample enable */ +#define EXMC_SDRSCTL_SSCR BIT(1) /*!< select sample cycle of read data */ +#define EXMC_SDRSCTL_SDSC BITS(4,7) /*!< select the delayed sample clock of read data */ + +/* EXMC_SINIT */ +#define EXMC_SINIT_CMDBIT BITS(16,17) /*!< bit number of SPI PSRAM command phase */ +#define EXMC_SINIT_ARDBIT BITS(24,28) /*!< bit number of SPI PSRAM address phase */ +#define EXMC_SINIT_IDL BITS(29,30) /*!< SPI PSRAM ID length */ +#define EXMC_SINIT_POL BIT(31) /*!< read data sample polarity */ + +/* EXMC_SRCMD */ +#define EXMC_SRCMD_RCMD BITS(0,15) /*!< SPI read command for AHB read transfer */ +#define EXMC_SRCMD_RWAITCYCLE BITS(16,19) /*!< SPI read wait cycle number after address phase */ +#define EXMC_SRCMD_RMODE BITS(20,21) /*!< SPI PSRAM read command mode */ +#define EXMC_SRCMD_RDID BIT(31) /*!< send SPI read ID command */ + +/* EXMC_SWCMD */ +#define EXMC_SWCMD_WCMD BITS(0,15) /*!< SPI write command for AHB write transfer */ +#define EXMC_SWCMD_WWAITCYCLE BITS(16,19) /*!< SPI write wait cycle number after address phase */ +#define EXMC_SWCMD_WMODE BITS(20,21) /*!< SPI PSRAM write command mode */ +#define EXMC_SWCMD_SC BIT(31) /*!< send SPI special command */ + +/* EXMC_SIDL */ +#define EXMC_SIDL_SIDL BITS(0,31) /*!< ID low data saved for SPI read ID command */ + +/* EXMC_SIDH */ +#define EXMC_SIDL_SIDH BITS(0,31) /*!< ID high Data saved for SPI read ID command */ + +/* constants definitions */ +/* EXMC NOR/SRAM timing initialize structure */ +typedef struct { + uint32_t asyn_access_mode; /*!< asynchronous access mode */ + uint32_t syn_data_latency; /*!< configure the data latency */ + uint32_t syn_data_latency_dec; /*!< configure the data latency decreasing value */ + uint32_t syn_clk_division; /*!< configure the clock divide ratio */ + uint32_t bus_latency; /*!< configure the bus latency */ + uint32_t asyn_data_setuptime; /*!< configure the data setup time, asynchronous access mode valid */ + uint32_t asyn_address_holdtime; /*!< configure the address hold time, asynchronous access mode valid */ + uint32_t asyn_address_setuptime; /*!< configure the address setup time, asynchronous access mode valid */ +} exmc_norsram_timing_parameter_struct; + +/* EXMC NOR/SRAM initialize structure */ +typedef struct { + uint32_t norsram_region; /*!< select the region of EXMC NOR/SRAM bank */ + uint32_t write_mode; /*!< the write mode, synchronous mode or asynchronous mode */ + uint32_t extended_mode; /*!< enable or disable the extended mode */ + uint32_t asyn_wait; /*!< enable or disable the asynchronous wait function */ + uint32_t nwait_signal; /*!< enable or disable the NWAIT signal while in synchronous bust mode */ + uint32_t memory_write; /*!< enable or disable the write operation */ + uint32_t nwait_config; /*!< NWAIT signal configuration */ + uint32_t wrap_burst_mode; /*!< enable or disable the wrap burst mode */ + uint32_t nwait_polarity; /*!< specifies the polarity of NWAIT signal from memory */ + uint32_t burst_mode; /*!< enable or disable the burst mode */ + uint32_t databus_width; /*!< specifies the databus width of external memory */ + uint32_t memory_type; /*!< specifies the type of external memory */ + uint32_t address_data_mux; /*!< specifies whether the data bus and address bus are multiplexed */ + exmc_norsram_timing_parameter_struct *read_write_timing; /*!< timing parameters for read and write if the extendedmode is not used or the timing + parameters for read if the extendedmode is used. */ + exmc_norsram_timing_parameter_struct *write_timing; /*!< timing parameters for write when the extendedmode is used. */ +} exmc_norsram_parameter_struct; + +/* EXMC NAND/PC card timing initialize structure */ +typedef struct { + uint32_t databus_hiztime; /*!< configure the dadtabus HiZ time for write operation */ + uint32_t holdtime; /*!< configure the address hold time(or the data hold time for write operation) */ + uint32_t waittime; /*!< configure the minimum wait time */ + uint32_t setuptime; /*!< configure the address setup time */ +} exmc_nand_pccard_timing_parameter_struct; + +/* EXMC NAND initialize structure */ +typedef struct { + uint32_t nand_bank; /*!< select the bank of NAND */ + uint32_t ecc_size; /*!< the page size for the ECC calculation */ + uint32_t atr_latency; /*!< configure the latency of ALE low to RB low */ + uint32_t ctr_latency; /*!< configure the latency of CLE low to RB low */ + uint32_t ecc_logic; /*!< enable or disable the ECC calculation logic */ + uint32_t databus_width; /*!< the NAND flash databus width */ + uint32_t wait_feature; /*!< enable or disable the wait feature */ + exmc_nand_pccard_timing_parameter_struct *common_space_timing; /*!< the timing parameters for NAND flash common space */ + exmc_nand_pccard_timing_parameter_struct *attribute_space_timing; /*!< the timing parameters for NAND flash attribute space */ +} exmc_nand_parameter_struct; + +/* EXMC PC card initialize structure */ +typedef struct { + uint32_t atr_latency; /*!< configure the latency of ALE low to RB low */ + uint32_t ctr_latency; /*!< configure the latency of CLE low to RB low */ + uint32_t wait_feature; /*!< enable or disable the wait feature */ + exmc_nand_pccard_timing_parameter_struct *common_space_timing; /*!< the timing parameters for PC card common space */ + exmc_nand_pccard_timing_parameter_struct *attribute_space_timing; /*!< the timing parameters for PC card attribute space */ + exmc_nand_pccard_timing_parameter_struct *io_space_timing; /*!< the timing parameters for PC card IO space */ +} exmc_pccard_parameter_struct; + +/* EXMC SDRAM timing initialize structure */ +typedef struct { + uint32_t row_to_column_delay; /*!< configure the row to column delay */ + uint32_t row_precharge_delay; /*!< configure the row precharge delay */ + uint32_t write_recovery_delay; /*!< configure the write recovery delay */ + uint32_t auto_refresh_delay; /*!< configure the auto refresh delay */ + uint32_t row_address_select_delay; /*!< configure the row address select delay */ + uint32_t exit_selfrefresh_delay; /*!< configure the exit self-refresh delay */ + uint32_t load_mode_register_delay; /*!< configure the load mode register delay */ +} exmc_sdram_timing_parameter_struct; + +/* EXMC SDRAM initialize structure */ +typedef struct { + uint32_t sdram_device; /*!< device of SDRAM */ + uint32_t pipeline_read_delay; /*!< the delay for reading data after CAS latency in HCLK clock cycles */ + uint32_t burst_read_switch; /*!< enable or disable the burst read */ + uint32_t sdclock_config; /*!< the SDCLK memory clock for both SDRAM banks */ + uint32_t write_protection; /*!< enable or disable SDRAM bank write protection function */ + uint32_t cas_latency; /*!< configure the SDRAM CAS latency */ + uint32_t internal_bank_number; /*!< the number of internal bank */ + uint32_t data_width; /*!< the databus width of SDRAM memory */ + uint32_t row_address_width; /*!< the bit width of a row address */ + uint32_t column_address_width; /*!< the bit width of a column address */ + exmc_sdram_timing_parameter_struct *timing; /*!< the timing parameters for write and read SDRAM */ +} exmc_sdram_parameter_struct; + +/* EXMC SDRAM command initialize structure */ +typedef struct { + uint32_t mode_register_content; /*!< the SDRAM mode register content */ + uint32_t auto_refresh_number; /*!< the number of successive auto-refresh cycles will be send when CMD = 011 */ + uint32_t bank_select; /*!< the bank which command will be sent to */ + uint32_t command; /*!< the commands that will be sent to SDRAM */ +} exmc_sdram_command_parameter_struct; + +/* EXMC SQPISRAM initialize structure */ +typedef struct { + uint32_t sample_polarity; /*!< read data sample polarity */ + uint32_t id_length; /*!< SPI PSRAM ID length */ + uint32_t address_bits; /*!< bit number of SPI PSRAM address phase */ + uint32_t command_bits; /*!< bit number of SPI PSRAM command phase */ +} exmc_sqpipsram_parameter_struct; + +/* EXMC register address */ +#define EXMC_SNCTL(region) REG32(EXMC + 0x08U*((uint32_t)(region))) /*!< EXMC SRAM/NOR flash control registers, region = 0,1,2,3 */ +#define EXMC_SNTCFG(region) REG32(EXMC + 0x04U + 0x08U*((uint32_t)(region))) /*!< EXMC SRAM/NOR flash timing configuration registers, region = 0,1,2,3 */ +#define EXMC_SNWTCFG(region) REG32(EXMC + 0x104U + 0x08U*((uint32_t)(region))) /*!< EXMC SRAM/NOR flash write timing configuration registers, region = 0,1,2,3 */ +#define EXMC_SNLATDEC(region) REG32(EXMC + 0x300U + 0x04U*((uint32_t)(region))) /*!< EXMC SRAM/NOR flash data latency decrease registers, region = 0,1,2,3 */ + +#define EXMC_NPCTL(bank) REG32(EXMC + 0x40U + 0x20U*((uint32_t)(bank))) /*!< EXMC NAND/PC card control registers, bank = 1,2,3 */ +#define EXMC_NPINTEN(bank) REG32(EXMC + 0x44U + 0x20U*((uint32_t)(bank))) /*!< EXMC NAND/PC card interrupt enable registers, bank = 1,2,3 */ +#define EXMC_NPCTCFG(bank) REG32(EXMC + 0x48U + 0x20U*((uint32_t)(bank))) /*!< EXMC NAND/PC card common space timing configuration registers, bank = 1,2,3 */ +#define EXMC_NPATCFG(bank) REG32(EXMC + 0x4CU + 0x20U*((uint32_t)(bank))) /*!< EXMC NAND/PC card attribute space timing configuration registers, bank = 1,2,3 */ +#define EXMC_NECC(bank) REG32(EXMC + 0x54U + 0x20U*((uint32_t)(bank))) /*!< EXMC NAND ECC registers, bank = 1,2 */ + +#define EXMC_SDCTL(device) REG32(EXMC + 0x140U + 0x4U*(((uint32_t)(device)) - 0x4U)) /*!< EXMC SDRAM control registers,device = 0,1 */ +#define EXMC_SDTCFG(device) REG32(EXMC + 0x148U + 0x4U*(((uint32_t)(device)) - 0x4U)) /*!< EXMC SDRAM timing configuration registers,device = 0,1 */ + +/* CRAM page size */ +#define SNCTL_CPS(regval) (BITS(16,18) & ((uint32_t)(regval) << 16)) +#define EXMC_CRAM_AUTO_SPLIT SNCTL_CPS(0) /*!< automatic burst split on page boundary crossing */ +#define EXMC_CRAM_PAGE_SIZE_128_BYTES SNCTL_CPS(1) /*!< page size is 128 bytes */ +#define EXMC_CRAM_PAGE_SIZE_256_BYTES SNCTL_CPS(2) /*!< page size is 256 bytes */ +#define EXMC_CRAM_PAGE_SIZE_512_BYTES SNCTL_CPS(3) /*!< page size is 512 bytes */ +#define EXMC_CRAM_PAGE_SIZE_1024_BYTES SNCTL_CPS(4) /*!< page size is 1024 bytes */ + +/* NOR bank memory data bus width */ +#define SNCTL_NRW(regval) (BITS(4,5) & ((uint32_t)(regval) << 4)) +#define EXMC_NOR_DATABUS_WIDTH_8B SNCTL_NRW(0) /*!< NOR data width is 8 bits */ +#define EXMC_NOR_DATABUS_WIDTH_16B SNCTL_NRW(1) /*!< NOR data width is 16 bits */ + +/* NOR bank memory type */ +#define SNCTL_NRTP(regval) (BITS(2,3) & ((uint32_t)(regval) << 2)) +#define EXMC_MEMORY_TYPE_SRAM SNCTL_NRTP(0) /*!< SRAM,ROM */ +#define EXMC_MEMORY_TYPE_PSRAM SNCTL_NRTP(1) /*!< PSRAM, CRAM */ +#define EXMC_MEMORY_TYPE_NOR SNCTL_NRTP(2) /*!< NOR flash */ + +/* asynchronous access mode */ +#define SNTCFG_ASYNCMOD(regval) (BITS(28,29) & ((uint32_t)(regval) << 28)) +#define EXMC_ACCESS_MODE_A SNTCFG_ASYNCMOD(0) /*!< mode A access */ +#define EXMC_ACCESS_MODE_B SNTCFG_ASYNCMOD(1) /*!< mode B access */ +#define EXMC_ACCESS_MODE_C SNTCFG_ASYNCMOD(2) /*!< mode C access */ +#define EXMC_ACCESS_MODE_D SNTCFG_ASYNCMOD(3) /*!< mode D access */ + +/* data latency for NOR flash */ +#define SNTCFG_DLAT(regval) (BITS(24,27) & ((uint32_t)(regval) << 24)) +#define EXMC_DATALAT_2_CLK SNTCFG_DLAT(0) /*!< data latency of first burst access is 2 EXMC_CLK */ +#define EXMC_DATALAT_3_CLK SNTCFG_DLAT(1) /*!< data latency of first burst access is 3 EXMC_CLK */ +#define EXMC_DATALAT_4_CLK SNTCFG_DLAT(2) /*!< data latency of first burst access is 4 EXMC_CLK */ +#define EXMC_DATALAT_5_CLK SNTCFG_DLAT(3) /*!< data latency of first burst access is 5 EXMC_CLK */ +#define EXMC_DATALAT_6_CLK SNTCFG_DLAT(4) /*!< data latency of first burst access is 6 EXMC_CLK */ +#define EXMC_DATALAT_7_CLK SNTCFG_DLAT(5) /*!< data latency of first burst access is 7 EXMC_CLK */ +#define EXMC_DATALAT_8_CLK SNTCFG_DLAT(6) /*!< data latency of first burst access is 8 EXMC_CLK */ +#define EXMC_DATALAT_9_CLK SNTCFG_DLAT(7) /*!< data latency of first burst access is 9 EXMC_CLK */ +#define EXMC_DATALAT_10_CLK SNTCFG_DLAT(8) /*!< data latency of first burst access is 10 EXMC_CLK */ +#define EXMC_DATALAT_11_CLK SNTCFG_DLAT(9) /*!< data latency of first burst access is 11 EXMC_CLK */ +#define EXMC_DATALAT_12_CLK SNTCFG_DLAT(10) /*!< data latency of first burst access is 12 EXMC_CLK */ +#define EXMC_DATALAT_13_CLK SNTCFG_DLAT(11) /*!< data latency of first burst access is 13 EXMC_CLK */ +#define EXMC_DATALAT_14_CLK SNTCFG_DLAT(12) /*!< data latency of first burst access is 14 EXMC_CLK */ +#define EXMC_DATALAT_15_CLK SNTCFG_DLAT(13) /*!< data latency of first burst access is 15 EXMC_CLK */ +#define EXMC_DATALAT_16_CLK SNTCFG_DLAT(14) /*!< data latency of first burst access is 16 EXMC_CLK */ +#define EXMC_DATALAT_17_CLK SNTCFG_DLAT(15) /*!< data latency of first burst access is 17 EXMC_CLK */ + +/* synchronous clock divide ratio */ +#define SNTCFG_CKDIV(regval) (BITS(20,23) & ((uint32_t)(regval) << 20)) +#define EXMC_SYN_CLOCK_RATIO_DISABLE SNTCFG_CKDIV(0) /*!< EXMC_CLK disable */ +#define EXMC_SYN_CLOCK_RATIO_2_CLK SNTCFG_CKDIV(1) /*!< EXMC_CLK = 2*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_3_CLK SNTCFG_CKDIV(2) /*!< EXMC_CLK = 3*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_4_CLK SNTCFG_CKDIV(3) /*!< EXMC_CLK = 4*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_5_CLK SNTCFG_CKDIV(4) /*!< EXMC_CLK = 5*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_6_CLK SNTCFG_CKDIV(5) /*!< EXMC_CLK = 6*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_7_CLK SNTCFG_CKDIV(6) /*!< EXMC_CLK = 7*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_8_CLK SNTCFG_CKDIV(7) /*!< EXMC_CLK = 8*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_9_CLK SNTCFG_CKDIV(8) /*!< EXMC_CLK = 9*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_10_CLK SNTCFG_CKDIV(9) /*!< EXMC_CLK = 10*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_11_CLK SNTCFG_CKDIV(10) /*!< EXMC_CLK = 11*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_12_CLK SNTCFG_CKDIV(11) /*!< EXMC_CLK = 12*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_13_CLK SNTCFG_CKDIV(12) /*!< EXMC_CLK = 13*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_14_CLK SNTCFG_CKDIV(13) /*!< EXMC_CLK = 14*HCLK*/ +#define EXMC_SYN_CLOCK_RATIO_15_CLK SNTCFG_CKDIV(14) /*!< EXMC_CLK = 15*HCLK */ +#define EXMC_SYN_CLOCK_RATIO_16_CLK SNTCFG_CKDIV(15) /*!< EXMC_CLK = 16*HCLK */ + +/* ECC size */ +#define NPCTL_ECCSZ(regval) (BITS(17,19) & ((uint32_t)(regval) << 17)) +#define EXMC_ECC_SIZE_256BYTES NPCTL_ECCSZ(0) /*!< ECC size is 256 bytes */ +#define EXMC_ECC_SIZE_512BYTES NPCTL_ECCSZ(1) /*!< ECC size is 512 bytes */ +#define EXMC_ECC_SIZE_1024BYTES NPCTL_ECCSZ(2) /*!< ECC size is 1024 bytes */ +#define EXMC_ECC_SIZE_2048BYTES NPCTL_ECCSZ(3) /*!< ECC size is 2048 bytes */ +#define EXMC_ECC_SIZE_4096BYTES NPCTL_ECCSZ(4) /*!< ECC size is 4096 bytes */ +#define EXMC_ECC_SIZE_8192BYTES NPCTL_ECCSZ(5) /*!< ECC size is 8192 bytes */ + +/* ALE to RE delay */ +#define NPCTL_ATR(regval) (BITS(13,16) & ((uint32_t)(regval) << 13)) +#define EXMC_ALE_RE_DELAY_1_HCLK NPCTL_ATR(0) /*!< ALE to RE delay = 1*HCLK */ +#define EXMC_ALE_RE_DELAY_2_HCLK NPCTL_ATR(1) /*!< ALE to RE delay = 2*HCLK */ +#define EXMC_ALE_RE_DELAY_3_HCLK NPCTL_ATR(2) /*!< ALE to RE delay = 3*HCLK */ +#define EXMC_ALE_RE_DELAY_4_HCLK NPCTL_ATR(3) /*!< ALE to RE delay = 4*HCLK */ +#define EXMC_ALE_RE_DELAY_5_HCLK NPCTL_ATR(4) /*!< ALE to RE delay = 5*HCLK */ +#define EXMC_ALE_RE_DELAY_6_HCLK NPCTL_ATR(5) /*!< ALE to RE delay = 6*HCLK */ +#define EXMC_ALE_RE_DELAY_7_HCLK NPCTL_ATR(6) /*!< ALE to RE delay = 7*HCLK */ +#define EXMC_ALE_RE_DELAY_8_HCLK NPCTL_ATR(7) /*!< ALE to RE delay = 8*HCLK */ +#define EXMC_ALE_RE_DELAY_9_HCLK NPCTL_ATR(8) /*!< ALE to RE delay = 9*HCLK */ +#define EXMC_ALE_RE_DELAY_10_HCLK NPCTL_ATR(9) /*!< ALE to RE delay = 10*HCLK */ +#define EXMC_ALE_RE_DELAY_11_HCLK NPCTL_ATR(10) /*!< ALE to RE delay = 11*HCLK */ +#define EXMC_ALE_RE_DELAY_12_HCLK NPCTL_ATR(11) /*!< ALE to RE delay = 12*HCLK */ +#define EXMC_ALE_RE_DELAY_13_HCLK NPCTL_ATR(12) /*!< ALE to RE delay = 13*HCLK */ +#define EXMC_ALE_RE_DELAY_14_HCLK NPCTL_ATR(13) /*!< ALE to RE delay = 14*HCLK */ +#define EXMC_ALE_RE_DELAY_15_HCLK NPCTL_ATR(14) /*!< ALE to RE delay = 15*HCLK */ +#define EXMC_ALE_RE_DELAY_16_HCLK NPCTL_ATR(15) /*!< ALE to RE delay = 16*HCLK */ + +/* CLE to RE delay */ +#define NPCTL_CTR(regval) (BITS(9,12) & ((uint32_t)(regval) << 9)) +#define EXMC_CLE_RE_DELAY_1_HCLK NPCTL_CTR(0) /*!< CLE to RE delay = 1*HCLK */ +#define EXMC_CLE_RE_DELAY_2_HCLK NPCTL_CTR(1) /*!< CLE to RE delay = 2*HCLK */ +#define EXMC_CLE_RE_DELAY_3_HCLK NPCTL_CTR(2) /*!< CLE to RE delay = 3*HCLK */ +#define EXMC_CLE_RE_DELAY_4_HCLK NPCTL_CTR(3) /*!< CLE to RE delay = 4*HCLK */ +#define EXMC_CLE_RE_DELAY_5_HCLK NPCTL_CTR(4) /*!< CLE to RE delay = 5*HCLK */ +#define EXMC_CLE_RE_DELAY_6_HCLK NPCTL_CTR(5) /*!< CLE to RE delay = 6*HCLK */ +#define EXMC_CLE_RE_DELAY_7_HCLK NPCTL_CTR(6) /*!< CLE to RE delay = 7*HCLK */ +#define EXMC_CLE_RE_DELAY_8_HCLK NPCTL_CTR(7) /*!< CLE to RE delay = 8*HCLK */ +#define EXMC_CLE_RE_DELAY_9_HCLK NPCTL_CTR(8) /*!< CLE to RE delay = 9*HCLK */ +#define EXMC_CLE_RE_DELAY_10_HCLK NPCTL_CTR(9) /*!< CLE to RE delay = 10*HCLK */ +#define EXMC_CLE_RE_DELAY_11_HCLK NPCTL_CTR(10) /*!< CLE to RE delay = 11*HCLK */ +#define EXMC_CLE_RE_DELAY_12_HCLK NPCTL_CTR(11) /*!< CLE to RE delay = 12*HCLK */ +#define EXMC_CLE_RE_DELAY_13_HCLK NPCTL_CTR(12) /*!< CLE to RE delay = 13*HCLK */ +#define EXMC_CLE_RE_DELAY_14_HCLK NPCTL_CTR(13) /*!< CLE to RE delay = 14*HCLK */ +#define EXMC_CLE_RE_DELAY_15_HCLK NPCTL_CTR(14) /*!< CLE to RE delay = 15*HCLK */ +#define EXMC_CLE_RE_DELAY_16_HCLK NPCTL_CTR(15) /*!< CLE to RE delay = 16*HCLK */ + +/* NAND bank memory data bus width */ +#define NPCTL_NDW(regval) (BITS(4,5) & ((uint32_t)(regval) << 4)) +#define EXMC_NAND_DATABUS_WIDTH_8B NPCTL_NDW(0) /*!< NAND data width is 8 bits */ +#define EXMC_NAND_DATABUS_WIDTH_16B NPCTL_NDW(1) /*!< NAND data width is 16 bits */ + +/* SDRAM pipeline delay */ +#define SDCTL_PIPED(regval) (BITS(13,14) & ((uint32_t)(regval) << 13)) +#define EXMC_PIPELINE_DELAY_0_HCLK SDCTL_PIPED(0) /*!< 0 HCLK clock cycle delay */ +#define EXMC_PIPELINE_DELAY_1_HCLK SDCTL_PIPED(1) /*!< 1 HCLK clock cycle delay */ +#define EXMC_PIPELINE_DELAY_2_HCLK SDCTL_PIPED(2) /*!< 2 HCLK clock cycle delay */ + +/* SDRAM clock configuration */ +#define SDCTL_SDCLK(regval) (BITS(10,11) & ((uint32_t)(regval) << 10)) +#define EXMC_SDCLK_DISABLE SDCTL_SDCLK(0) /*!< SDCLK memory clock disabled */ +#define EXMC_SDCLK_PERIODS_2_HCLK SDCTL_SDCLK(2) /*!< SDCLK memory period = 2*HCLK */ +#define EXMC_SDCLK_PERIODS_3_HCLK SDCTL_SDCLK(3) /*!< SDCLK memory period = 3*HCLK */ + +/* CAS latency */ +#define SDCTL_CL(regval) (BITS(7,8) & ((uint32_t)(regval) << 7)) +#define EXMC_CAS_LATENCY_1_SDCLK SDCTL_CL(1) /*!< CAS latency is 1 memory clock cycle */ +#define EXMC_CAS_LATENCY_2_SDCLK SDCTL_CL(2) /*!< CAS latency is 2 memory clock cycle */ +#define EXMC_CAS_LATENCY_3_SDCLK SDCTL_CL(3) /*!< CAS latency is 3 memory clock cycle */ + +/* SDRAM data bus width */ +#define SDCTL_SDW(regval) (BITS(4,5) & ((uint32_t)(regval) << 4)) +#define EXMC_SDRAM_DATABUS_WIDTH_8B SDCTL_SDW(0) /*!< SDRAM data width 8 bits */ +#define EXMC_SDRAM_DATABUS_WIDTH_16B SDCTL_SDW(1) /*!< SDRAM data width 16 bits */ +#define EXMC_SDRAM_DATABUS_WIDTH_32B SDCTL_SDW(2) /*!< SDRAM data width 32 bits */ + +/* SDRAM row address bit width */ +#define SDCTL_RAW(regval) (BITS(2,3) & ((uint32_t)(regval) << 2)) +#define EXMC_SDRAM_ROW_ADDRESS_11 SDCTL_RAW(0) /*!< row address bit width is 11 bits */ +#define EXMC_SDRAM_ROW_ADDRESS_12 SDCTL_RAW(1) /*!< row address bit width is 12 bits */ +#define EXMC_SDRAM_ROW_ADDRESS_13 SDCTL_RAW(2) /*!< row address bit width is 13 bits */ + +/* SDRAM column address bit width */ +#define SDCTL_CAW(regval) (BITS(0,1) & ((uint32_t)(regval) << 0)) +#define EXMC_SDRAM_COW_ADDRESS_8 SDCTL_CAW(0) /*!< column address bit width is 8 bits */ +#define EXMC_SDRAM_COW_ADDRESS_9 SDCTL_CAW(1) /*!< column address bit width is 9 bits */ +#define EXMC_SDRAM_COW_ADDRESS_10 SDCTL_CAW(2) /*!< column address bit width is 10 bits */ +#define EXMC_SDRAM_COW_ADDRESS_11 SDCTL_CAW(3) /*!< column address bit width is 11 bits */ + +/* SDRAM number of successive auto-refresh */ +#define SDCMD_NARF(regval) (BITS(5,8) & ((uint32_t)(regval) << 5)) +#define EXMC_SDRAM_AUTO_REFLESH_1_SDCLK SDCMD_NARF(0) /*!< 1 auto-refresh cycle */ +#define EXMC_SDRAM_AUTO_REFLESH_2_SDCLK SDCMD_NARF(1) /*!< 2 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_3_SDCLK SDCMD_NARF(2) /*!< 3 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_4_SDCLK SDCMD_NARF(3) /*!< 4 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_5_SDCLK SDCMD_NARF(4) /*!< 5 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_6_SDCLK SDCMD_NARF(5) /*!< 6 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_7_SDCLK SDCMD_NARF(6) /*!< 7 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_8_SDCLK SDCMD_NARF(7) /*!< 8 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_9_SDCLK SDCMD_NARF(8) /*!< 9 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_10_SDCLK SDCMD_NARF(9) /*!< 10 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_11_SDCLK SDCMD_NARF(10) /*!< 11 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_12_SDCLK SDCMD_NARF(11) /*!< 12 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_13_SDCLK SDCMD_NARF(12) /*!< 13 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_14_SDCLK SDCMD_NARF(13) /*!< 14 auto-refresh cycles */ +#define EXMC_SDRAM_AUTO_REFLESH_15_SDCLK SDCMD_NARF(14) /*!< 15 auto-refresh cycles */ + +/* SDRAM command selection */ +#define SDCMD_CMD(regval) (BITS(0,2) & ((uint32_t)(regval) << 0)) +#define EXMC_SDRAM_NORMAL_OPERATION SDCMD_CMD(0) /*!< normal operation command */ +#define EXMC_SDRAM_CLOCK_ENABLE SDCMD_CMD(1) /*!< clock enable command */ +#define EXMC_SDRAM_PRECHARGE_ALL SDCMD_CMD(2) /*!< precharge all command */ +#define EXMC_SDRAM_AUTO_REFRESH SDCMD_CMD(3) /*!< auto-refresh command */ +#define EXMC_SDRAM_LOAD_MODE_REGISTER SDCMD_CMD(4) /*!< load mode register command */ +#define EXMC_SDRAM_SELF_REFRESH SDCMD_CMD(5) /*!< self-refresh command */ +#define EXMC_SDRAM_POWERDOWN_ENTRY SDCMD_CMD(6) /*!< power-down entry command */ + +/* SDRAM the delayed sample clock of read data */ +#define SDRSCTL_SDSC(regval) (BITS(4,7) & ((uint32_t)(regval) << 4)) +#define EXMC_SDRAM_0_DELAY_CELL SDRSCTL_SDSC(0) /*!< select the clock after 0 delay cell */ +#define EXMC_SDRAM_1_DELAY_CELL SDRSCTL_SDSC(1) /*!< select the clock after 1 delay cell */ +#define EXMC_SDRAM_2_DELAY_CELL SDRSCTL_SDSC(2) /*!< select the clock after 2 delay cell */ +#define EXMC_SDRAM_3_DELAY_CELL SDRSCTL_SDSC(3) /*!< select the clock after 3 delay cell */ +#define EXMC_SDRAM_4_DELAY_CELL SDRSCTL_SDSC(4) /*!< select the clock after 4 delay cell */ +#define EXMC_SDRAM_5_DELAY_CELL SDRSCTL_SDSC(5) /*!< select the clock after 5 delay cell */ +#define EXMC_SDRAM_6_DELAY_CELL SDRSCTL_SDSC(6) /*!< select the clock after 6 delay cell */ +#define EXMC_SDRAM_7_DELAY_CELL SDRSCTL_SDSC(7) /*!< select the clock after 7 delay cell */ +#define EXMC_SDRAM_8_DELAY_CELL SDRSCTL_SDSC(8) /*!< select the clock after 8 delay cell */ +#define EXMC_SDRAM_9_DELAY_CELL SDRSCTL_SDSC(9) /*!< select the clock after 9 delay cell */ +#define EXMC_SDRAM_10_DELAY_CELL SDRSCTL_SDSC(10) /*!< select the clock after 10 delay cell */ +#define EXMC_SDRAM_11_DELAY_CELL SDRSCTL_SDSC(11) /*!< select the clock after 11 delay cell */ +#define EXMC_SDRAM_12_DELAY_CELL SDRSCTL_SDSC(12) /*!< select the clock after 12 delay cell */ +#define EXMC_SDRAM_13_DELAY_CELL SDRSCTL_SDSC(13) /*!< select the clock after 13 delay cell */ +#define EXMC_SDRAM_14_DELAY_CELL SDRSCTL_SDSC(14) /*!< select the clock after 14 delay cell */ +#define EXMC_SDRAM_15_DELAY_CELL SDRSCTL_SDSC(15) /*!< select the clock after 15 delay cell */ + +/* SPI PSRAM ID length */ +#define SINIT_IDL(regval) (BITS(29,30) & ((uint32_t)(regval) << 29)) +#define EXMC_SQPIPSRAM_ID_LENGTH_64B SINIT_IDL(0) /*!< SPI PSRAM ID length is 64 bits */ +#define EXMC_SQPIPSRAM_ID_LENGTH_32B SINIT_IDL(1) /*!< SPI PSRAM ID length is 32 bits */ +#define EXMC_SQPIPSRAM_ID_LENGTH_16B SINIT_IDL(2) /*!< SPI PSRAM ID length is 16 bits */ +#define EXMC_SQPIPSRAM_ID_LENGTH_8B SINIT_IDL(3) /*!< SPI PSRAM ID length is 8 bits */ + +/* SPI PSRAM bit number of address phase */ +#define SINIT_ADRBIT(regval) (BITS(24,28) & ((uint32_t)(regval) << 24)) +#define EXMC_SQPIPSRAM_ADDR_LENGTH_1B SINIT_ADRBIT(1) /*!< SPI PSRAM address is 1 bit */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_2B SINIT_ADRBIT(2) /*!< SPI PSRAM address is 2 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_3B SINIT_ADRBIT(3) /*!< SPI PSRAM address is 3 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_4B SINIT_ADRBIT(4) /*!< SPI PSRAM address is 4 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_5B SINIT_ADRBIT(5) /*!< SPI PSRAM address is 5 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_6B SINIT_ADRBIT(6) /*!< SPI PSRAM address is 6 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_7B SINIT_ADRBIT(7) /*!< SPI PSRAM address is 7 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_8B SINIT_ADRBIT(8) /*!< SPI PSRAM address is 8 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_9B SINIT_ADRBIT(9) /*!< SPI PSRAM address is 9 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_10B SINIT_ADRBIT(10) /*!< SPI PSRAM address is 10 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_11B SINIT_ADRBIT(11) /*!< SPI PSRAM address is 11 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_12B SINIT_ADRBIT(12) /*!< SPI PSRAM address is 12 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_13B SINIT_ADRBIT(13) /*!< SPI PSRAM address is 13 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_14B SINIT_ADRBIT(14) /*!< SPI PSRAM address is 14 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_15B SINIT_ADRBIT(15) /*!< SPI PSRAM address is 15 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_16B SINIT_ADRBIT(16) /*!< SPI PSRAM address is 16 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_17B SINIT_ADRBIT(17) /*!< SPI PSRAM address is 17 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_18B SINIT_ADRBIT(18) /*!< SPI PSRAM address is 18 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_19B SINIT_ADRBIT(19) /*!< SPI PSRAM address is 19 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_20B SINIT_ADRBIT(20) /*!< SPI PSRAM address is 20 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_21B SINIT_ADRBIT(21) /*!< SPI PSRAM address is 21 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_22B SINIT_ADRBIT(22) /*!< SPI PSRAM address is 22 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_23B SINIT_ADRBIT(23) /*!< SPI PSRAM address is 23 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_24B SINIT_ADRBIT(24) /*!< SPI PSRAM address is 24 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_25B SINIT_ADRBIT(25) /*!< SPI PSRAM address is 25 bits */ +#define EXMC_SQPIPSRAM_ADDR_LENGTH_26B SINIT_ADRBIT(26) /*!< SPI PSRAM address is 26 bits */ + +/* SPI PSRAM bit number of command phase */ +#define SINIT_CMDBIT(regval) (BITS(16,17) & ((uint32_t)(regval) << 16)) +#define EXMC_SQPIPSRAM_COMMAND_LENGTH_4B SINIT_CMDBIT(0) /*!< SPI PSRAM command is 4 bits */ +#define EXMC_SQPIPSRAM_COMMAND_LENGTH_8B SINIT_CMDBIT(1) /*!< SPI PSRAM command is 8 bits */ +#define EXMC_SQPIPSRAM_COMMAND_LENGTH_16B SINIT_CMDBIT(2) /*!< SPI PSRAM command is 16 bits */ + +/* SPI PSRAM read command mode */ +#define SRCMD_RMODE(regval) (BITS(20,21) & ((uint32_t)(regval) << 20)) +#define EXMC_SQPIPSRAM_READ_MODE_DISABLE SRCMD_RMODE(0) /*!< not SPI mode */ +#define EXMC_SQPIPSRAM_READ_MODE_SPI SRCMD_RMODE(1) /*!< SPI mode */ +#define EXMC_SQPIPSRAM_READ_MODE_SQPI SRCMD_RMODE(2) /*!< SQPI mode */ +#define EXMC_SQPIPSRAM_READ_MODE_QPI SRCMD_RMODE(3) /*!< QPI mode */ + +/* SPI PSRAM write command mode */ +#define SRCMD_WMODE(regval) (BITS(20,21) & ((uint32_t)(regval) << 20)) +#define EXMC_SQPIPSRAM_WRITE_MODE_DISABLE SRCMD_WMODE(0) /*!< not SPI mode */ +#define EXMC_SQPIPSRAM_WRITE_MODE_SPI SRCMD_WMODE(1) /*!< SPI mode */ +#define EXMC_SQPIPSRAM_WRITE_MODE_SQPI SRCMD_WMODE(2) /*!< SQPI mode */ +#define EXMC_SQPIPSRAM_WRITE_MODE_QPI SRCMD_WMODE(3) /*!< QPI mode */ + +/* EXMC NOR/SRAM bank region definition */ +#define EXMC_BANK0_NORSRAM_REGION0 ((uint32_t)0x00000000U) /*!< bank0 NOR/SRAM region0 */ +#define EXMC_BANK0_NORSRAM_REGION1 ((uint32_t)0x00000001U) /*!< bank0 NOR/SRAM region1 */ +#define EXMC_BANK0_NORSRAM_REGION2 ((uint32_t)0x00000002U) /*!< bank0 NOR/SRAM region2 */ +#define EXMC_BANK0_NORSRAM_REGION3 ((uint32_t)0x00000003U) /*!< bank0 NOR/SRAM region3 */ + +/* EXMC consecutive clock */ +#define EXMC_CLOCK_SYN_MODE ((uint32_t)0x00000000U) /*!< EXMC_CLK is generated only during synchronous access */ +#define EXMC_CLOCK_UNCONDITIONALLY EXMC_SNCTL_CCK /*!< EXMC_CLK is generated unconditionally */ + +/* EXMC NOR/SRAM write mode */ +#define EXMC_ASYN_WRITE ((uint32_t)0x00000000U) /*!< asynchronous write mode */ +#define EXMC_SYN_WRITE EXMC_SNCTL_SYNCWR /*!< synchronous write mode */ + +/* EXMC NWAIT signal configuration */ +#define EXMC_NWAIT_CONFIG_BEFORE ((uint32_t)0x00000000U) /*!< NWAIT signal is active one data cycle before wait state */ +#define EXMC_NWAIT_CONFIG_DURING EXMC_SNCTL_NRWTCFG /*!< NWAIT signal is active during wait state */ + +/* EXMC NWAIT signal polarity configuration */ +#define EXMC_NWAIT_POLARITY_LOW ((uint32_t)0x00000000U) /*!< low level is active of NWAIT */ +#define EXMC_NWAIT_POLARITY_HIGH EXMC_SNCTL_NRWTPOL /*!< high level is active of NWAIT */ + +/* EXMC NAND/PC card bank definition */ +#define EXMC_BANK1_NAND ((uint32_t)0x00000001U) /*!< NAND flash bank1 */ +#define EXMC_BANK2_NAND ((uint32_t)0x00000002U) /*!< NAND flash bank2 */ +#define EXMC_BANK3_PCCARD ((uint32_t)0x00000003U) /*!< PC card bank3 */ + +/* EXMC SDRAM bank definition */ +#define EXMC_SDRAM_DEVICE0 ((uint32_t)0x00000004U) /*!< SDRAM device0 */ +#define EXMC_SDRAM_DEVICE1 ((uint32_t)0x00000005U) /*!< SDRAM device1 */ + +/* EXMC SDRAM internal banks */ +#define EXMC_SDRAM_2_INTER_BANK ((uint32_t)0x00000000U) /*!< 2 internal banks */ +#define EXMC_SDRAM_4_INTER_BANK EXMC_SDCTL_NBK /*!< 4 internal banks */ + +/* SDRAM device0 selection */ +#define EXMC_SDRAM_DEVICE0_UNSELECT ((uint32_t)0x00000000U) /*!< unselect SDRAM device0 */ +#define EXMC_SDRAM_DEVICE0_SELECT EXMC_SDCMD_DS0 /*!< select SDRAM device0 */ + +/* SDRAM device1 selection */ +#define EXMC_SDRAM_DEVICE1_UNSELECT ((uint32_t)0x00000000U) /*!< unselect SDRAM device1 */ +#define EXMC_SDRAM_DEVICE1_SELECT EXMC_SDCMD_DS1 /*!< select SDRAM device1 */ + +/* SDRAM device status */ +#define EXMC_SDRAM_DEVICE_NORMAL ((uint32_t)0x00000000U) /*!< normal status */ +#define EXMC_SDRAM_DEVICE_SELF_REFRESH ((uint32_t)0x00000001U) /*!< self refresh status */ +#define EXMC_SDRAM_DEVICE_POWER_DOWN ((uint32_t)0x00000002U) /*!< power down status */ + +/* sample cycle of read data */ +#define EXMC_SDRAM_READSAMPLE_0_EXTRAHCLK ((uint32_t)0x00000000U) /*!< add 0 extra HCLK cycle to the read data sample clock besides the delay chain */ +#define EXMC_SDRAM_READSAMPLE_1_EXTRAHCLK EXMC_SDRSCTL_SSCR /*!< add 1 extra HCLK cycle to the read data sample clock besides the delay chain */ + +/* read data sample polarity */ +#define EXMC_SQPIPSRAM_SAMPLE_RISING_EDGE ((uint32_t)0x00000000U) /*!< sample data at rising edge */ +#define EXMC_SQPIPSRAM_SAMPLE_FALLING_EDGE EXMC_SINIT_POL /*!< sample data at falling edge */ + +/* SQPI SRAM command flag */ +#define EXMC_SEND_COMMAND_FLAG_RDID EXMC_SRCMD_RDID /*!< EXMC_SRCMD_RDID flag bit */ +#define EXMC_SEND_COMMAND_FLAG_SC EXMC_SWCMD_SC /*!< EXMC_SWCMD_SC flag bit */ + +/* EXMC flag bits */ +#define EXMC_NAND_PCCARD_FLAG_RISE EXMC_NPINTEN_INTRS /*!< interrupt rising edge status */ +#define EXMC_NAND_PCCARD_FLAG_LEVEL EXMC_NPINTEN_INTHS /*!< interrupt high-level status */ +#define EXMC_NAND_PCCARD_FLAG_FALL EXMC_NPINTEN_INTFS /*!< interrupt falling edge status */ +#define EXMC_NAND_PCCARD_FLAG_FIFOE EXMC_NPINTEN_FFEPT /*!< FIFO empty flag */ +#define EXMC_SDRAM_FLAG_REFRESH EXMC_SDSDAT_REIF /*!< refresh error interrupt flag */ +#define EXMC_SDRAM_FLAG_NREADY EXMC_SDSDAT_NRDY /*!< not ready status */ + +/* EXMC interrupt flag bits */ +#define EXMC_NAND_PCCARD_INT_FLAG_RISE EXMC_NPINTEN_INTREN /*!< rising edge interrupt and flag */ +#define EXMC_NAND_PCCARD_INT_FLAG_LEVEL EXMC_NPINTEN_INTHEN /*!< high-level interrupt and flag */ +#define EXMC_NAND_PCCARD_INT_FLAG_FALL EXMC_NPINTEN_INTFEN /*!< falling edge interrupt and flag */ +#define EXMC_SDRAM_INT_FLAG_REFRESH EXMC_SDARI_REIE /*!< refresh error interrupt and flag */ + +/* function declarations */ +/* initialization functions */ +/* NOR/SRAM */ +/* deinitialize EXMC NOR/SRAM region */ +void exmc_norsram_deinit(uint32_t exmc_norsram_region); +/* initialize exmc_norsram_parameter_struct with the default values */ +void exmc_norsram_struct_para_init(exmc_norsram_parameter_struct *exmc_norsram_init_struct); +/* initialize EXMC NOR/SRAM region */ +void exmc_norsram_init(exmc_norsram_parameter_struct *exmc_norsram_init_struct); +/* enable EXMC NOR/SRAM region */ +void exmc_norsram_enable(uint32_t exmc_norsram_region); +/* disable EXMC NOR/SRAM region */ +void exmc_norsram_disable(uint32_t exmc_norsram_region); +/* NAND */ +/* deinitialize EXMC NAND bank */ +void exmc_nand_deinit(uint32_t exmc_nand_bank); +/* initialize exmc_nand_parameter_struct with the default values */ +void exmc_nand_struct_para_init(exmc_nand_parameter_struct *exmc_nand_init_struct); +/* initialize EXMC NAND bank */ +void exmc_nand_init(exmc_nand_parameter_struct *exmc_nand_init_struct); +/* enable EXMC NAND bank */ +void exmc_nand_enable(uint32_t exmc_nand_bank); +/* disable EXMC NAND bank */ +void exmc_nand_disable(uint32_t exmc_nand_bank); +/* PC card */ +/* deinitialize EXMC PC card bank */ +void exmc_pccard_deinit(void); +/* initialize exmc_pccard_parameter_struct with the default values */ +void exmc_pccard_struct_para_init(exmc_pccard_parameter_struct *exmc_pccard_init_struct); +/* initialize EXMC PC card bank */ +void exmc_pccard_init(exmc_pccard_parameter_struct *exmc_pccard_init_struct); +/* enable EXMC PC card bank */ +void exmc_pccard_enable(void); +/* disable EXMC PC card bank */ +void exmc_pccard_disable(void); +/* SDRAM */ +/* deinitialize EXMC SDRAM device */ +void exmc_sdram_deinit(uint32_t exmc_sdram_device); +/* initialize exmc_sdram_parameter_struct with the default values */ +void exmc_sdram_struct_para_init(exmc_sdram_parameter_struct *exmc_sdram_init_struct); +/* initialize EXMC SDRAM device */ +void exmc_sdram_init(exmc_sdram_parameter_struct *exmc_sdram_init_struct); +/* initialize exmc_sdram_command_parameter_struct with the default values */ +void exmc_sdram_struct_command_para_init(exmc_sdram_command_parameter_struct *exmc_sdram_command_init_struct); +/* SQPIPSRAM */ +/* deinitialize EXMC SQPIPSRAM */ +void exmc_sqpipsram_deinit(void); +/* initialize exmc_sqpipsram_parameter_struct with the default values */ +void exmc_sqpipsram_struct_para_init(exmc_sqpipsram_parameter_struct *exmc_sqpipsram_init_struct); +/* initialize EXMC SQPIPSRAM */ +void exmc_sqpipsram_init(exmc_sqpipsram_parameter_struct *exmc_sqpipsram_init_struct); + +/* function configuration */ +/* NOR/SRAM */ +/* configure consecutive clock */ +void exmc_norsram_consecutive_clock_config(uint32_t clock_mode); +/* configure CRAM page size */ +void exmc_norsram_page_size_config(uint32_t exmc_norsram_region, uint32_t page_size); +/* NAND */ +/* enable or disable the EXMC NAND ECC function */ +void exmc_nand_ecc_config(uint32_t exmc_nand_bank, ControlStatus newvalue); +/* get the EXMC ECC value */ +uint32_t exmc_ecc_get(uint32_t exmc_nand_bank); +/* SDRAM */ +/* enable or disable read sample */ +void exmc_sdram_readsample_enable(ControlStatus newvalue); +/* configure the delayed sample clock of read data */ +void exmc_sdram_readsample_config(uint32_t delay_cell, uint32_t extra_hclk); +/* configure the SDRAM memory command */ +void exmc_sdram_command_config(exmc_sdram_command_parameter_struct *exmc_sdram_command_init_struct); +/* set auto-refresh interval */ +void exmc_sdram_refresh_count_set(uint32_t exmc_count); +/* set the number of successive auto-refresh command */ +void exmc_sdram_autorefresh_number_set(uint32_t exmc_number); +/* configure the write protection function */ +void exmc_sdram_write_protection_config(uint32_t exmc_sdram_device, ControlStatus newvalue); +/* get the status of SDRAM device0 or device1 */ +uint32_t exmc_sdram_bankstatus_get(uint32_t exmc_sdram_device); +/* SQPIPSRAM */ +/* set the read command */ +void exmc_sqpipsram_read_command_set(uint32_t read_command_mode, uint32_t read_wait_cycle, uint32_t read_command_code); +/* set the write command */ +void exmc_sqpipsram_write_command_set(uint32_t write_command_mode, uint32_t write_wait_cycle, uint32_t write_command_code); +/* send SPI read ID command */ +void exmc_sqpipsram_read_id_command_send(void); +/* send SPI special command which does not have address and data phase */ +void exmc_sqpipsram_write_cmd_send(void); +/* get the EXMC SPI ID low data */ +uint32_t exmc_sqpipsram_low_id_get(void); +/* get the EXMC SPI ID high data */ +uint32_t exmc_sqpipsram_high_id_get(void); +/* get the bit value of EXMC send write command bit or read ID command */ +FlagStatus exmc_sqpipsram_send_command_state_get(uint32_t send_command_flag); + +/* interrupt & flag functions */ +/* enable EXMC interrupt */ +void exmc_interrupt_enable(uint32_t exmc_bank, uint32_t interrupt); +/* disable EXMC interrupt */ +void exmc_interrupt_disable(uint32_t exmc_bank, uint32_t interrupt); +/* get EXMC flag status */ +FlagStatus exmc_flag_get(uint32_t exmc_bank, uint32_t flag); +/* clear EXMC flag status */ +void exmc_flag_clear(uint32_t exmc_bank, uint32_t flag); +/* get EXMC interrupt flag */ +FlagStatus exmc_interrupt_flag_get(uint32_t exmc_bank, uint32_t int_flag); +/* clear EXMC interrupt flag */ +void exmc_interrupt_flag_clear(uint32_t exmc_bank, uint32_t int_flag); + +#endif /* GD32F5XX_EXMC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_exti.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_exti.h new file mode 100644 index 0000000..edcac6b --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_exti.h @@ -0,0 +1,296 @@ +/*! + \file gd32f5xx_exti.h + \brief definitions for the EXTI + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_EXTI_H +#define GD32F5XX_EXTI_H + +#include "gd32f5xx.h" + +/* EXTI definitions */ +#define EXTI EXTI_BASE + +/* registers definitions */ +#define EXTI_INTEN REG32(EXTI + 0x00U) /*!< interrupt enable register */ +#define EXTI_EVEN REG32(EXTI + 0x04U) /*!< event enable register */ +#define EXTI_RTEN REG32(EXTI + 0x08U) /*!< rising edge trigger enable register */ +#define EXTI_FTEN REG32(EXTI + 0x0CU) /*!< falling edge trigger enable register */ +#define EXTI_SWIEV REG32(EXTI + 0x10U) /*!< software interrupt event register */ +#define EXTI_PD REG32(EXTI + 0x14U) /*!< pending register */ + +/* bits definitions */ +/* EXTI_INTEN */ +#define EXTI_INTEN_INTEN0 BIT(0) /*!< interrupt from line 0 */ +#define EXTI_INTEN_INTEN1 BIT(1) /*!< interrupt from line 1 */ +#define EXTI_INTEN_INTEN2 BIT(2) /*!< interrupt from line 2 */ +#define EXTI_INTEN_INTEN3 BIT(3) /*!< interrupt from line 3 */ +#define EXTI_INTEN_INTEN4 BIT(4) /*!< interrupt from line 4 */ +#define EXTI_INTEN_INTEN5 BIT(5) /*!< interrupt from line 5 */ +#define EXTI_INTEN_INTEN6 BIT(6) /*!< interrupt from line 6 */ +#define EXTI_INTEN_INTEN7 BIT(7) /*!< interrupt from line 7 */ +#define EXTI_INTEN_INTEN8 BIT(8) /*!< interrupt from line 8 */ +#define EXTI_INTEN_INTEN9 BIT(9) /*!< interrupt from line 9 */ +#define EXTI_INTEN_INTEN10 BIT(10) /*!< interrupt from line 10 */ +#define EXTI_INTEN_INTEN11 BIT(11) /*!< interrupt from line 11 */ +#define EXTI_INTEN_INTEN12 BIT(12) /*!< interrupt from line 12 */ +#define EXTI_INTEN_INTEN13 BIT(13) /*!< interrupt from line 13 */ +#define EXTI_INTEN_INTEN14 BIT(14) /*!< interrupt from line 14 */ +#define EXTI_INTEN_INTEN15 BIT(15) /*!< interrupt from line 15 */ +#define EXTI_INTEN_INTEN16 BIT(16) /*!< interrupt from line 16 */ +#define EXTI_INTEN_INTEN17 BIT(17) /*!< interrupt from line 17 */ +#define EXTI_INTEN_INTEN18 BIT(18) /*!< interrupt from line 18 */ +#define EXTI_INTEN_INTEN19 BIT(19) /*!< interrupt from line 19 */ +#define EXTI_INTEN_INTEN20 BIT(20) /*!< interrupt from line 20 */ +#define EXTI_INTEN_INTEN21 BIT(21) /*!< interrupt from line 21 */ +#define EXTI_INTEN_INTEN22 BIT(22) /*!< interrupt from line 22 */ +#define EXTI_INTEN_INTEN23 BIT(23) /*!< interrupt from line 23 */ +#define EXTI_INTEN_INTEN24 BIT(24) /*!< interrupt from line 24 */ +#define EXTI_INTEN_INTEN25 BIT(25) /*!< interrupt from line 25 */ + +/* EXTI_EVEN */ +#define EXTI_EVEN_EVEN0 BIT(0) /*!< event from line 0 */ +#define EXTI_EVEN_EVEN1 BIT(1) /*!< event from line 1 */ +#define EXTI_EVEN_EVEN2 BIT(2) /*!< event from line 2 */ +#define EXTI_EVEN_EVEN3 BIT(3) /*!< event from line 3 */ +#define EXTI_EVEN_EVEN4 BIT(4) /*!< event from line 4 */ +#define EXTI_EVEN_EVEN5 BIT(5) /*!< event from line 5 */ +#define EXTI_EVEN_EVEN6 BIT(6) /*!< event from line 6 */ +#define EXTI_EVEN_EVEN7 BIT(7) /*!< event from line 7 */ +#define EXTI_EVEN_EVEN8 BIT(8) /*!< event from line 8 */ +#define EXTI_EVEN_EVEN9 BIT(9) /*!< event from line 9 */ +#define EXTI_EVEN_EVEN10 BIT(10) /*!< event from line 10 */ +#define EXTI_EVEN_EVEN11 BIT(11) /*!< event from line 11 */ +#define EXTI_EVEN_EVEN12 BIT(12) /*!< event from line 12 */ +#define EXTI_EVEN_EVEN13 BIT(13) /*!< event from line 13 */ +#define EXTI_EVEN_EVEN14 BIT(14) /*!< event from line 14 */ +#define EXTI_EVEN_EVEN15 BIT(15) /*!< event from line 15 */ +#define EXTI_EVEN_EVEN16 BIT(16) /*!< event from line 16 */ +#define EXTI_EVEN_EVEN17 BIT(17) /*!< event from line 17 */ +#define EXTI_EVEN_EVEN18 BIT(18) /*!< event from line 18 */ +#define EXTI_EVEN_EVEN19 BIT(19) /*!< event from line 19 */ +#define EXTI_EVEN_EVEN20 BIT(20) /*!< event from line 20 */ +#define EXTI_EVEN_EVEN21 BIT(21) /*!< event from line 21 */ +#define EXTI_EVEN_EVEN22 BIT(22) /*!< event from line 22 */ +#define EXTI_EVEN_EVEN23 BIT(23) /*!< event from line 23 */ +#define EXTI_EVEN_EVEN24 BIT(24) /*!< event from line 24 */ +#define EXTI_EVEN_EVEN25 BIT(25) /*!< event from line 25 */ + +/* EXTI_RTEN */ +#define EXTI_RTEN_RTEN0 BIT(0) /*!< rising edge from line 0 */ +#define EXTI_RTEN_RTEN1 BIT(1) /*!< rising edge from line 1 */ +#define EXTI_RTEN_RTEN2 BIT(2) /*!< rising edge from line 2 */ +#define EXTI_RTEN_RTEN3 BIT(3) /*!< rising edge from line 3 */ +#define EXTI_RTEN_RTEN4 BIT(4) /*!< rising edge from line 4 */ +#define EXTI_RTEN_RTEN5 BIT(5) /*!< rising edge from line 5 */ +#define EXTI_RTEN_RTEN6 BIT(6) /*!< rising edge from line 6 */ +#define EXTI_RTEN_RTEN7 BIT(7) /*!< rising edge from line 7 */ +#define EXTI_RTEN_RTEN8 BIT(8) /*!< rising edge from line 8 */ +#define EXTI_RTEN_RTEN9 BIT(9) /*!< rising edge from line 9 */ +#define EXTI_RTEN_RTEN10 BIT(10) /*!< rising edge from line 10 */ +#define EXTI_RTEN_RTEN11 BIT(11) /*!< rising edge from line 11 */ +#define EXTI_RTEN_RTEN12 BIT(12) /*!< rising edge from line 12 */ +#define EXTI_RTEN_RTEN13 BIT(13) /*!< rising edge from line 13 */ +#define EXTI_RTEN_RTEN14 BIT(14) /*!< rising edge from line 14 */ +#define EXTI_RTEN_RTEN15 BIT(15) /*!< rising edge from line 15 */ +#define EXTI_RTEN_RTEN16 BIT(16) /*!< rising edge from line 16 */ +#define EXTI_RTEN_RTEN17 BIT(17) /*!< rising edge from line 17 */ +#define EXTI_RTEN_RTEN18 BIT(18) /*!< rising edge from line 18 */ +#define EXTI_RTEN_RTEN19 BIT(19) /*!< rising edge from line 19 */ +#define EXTI_RTEN_RTEN20 BIT(20) /*!< rising edge from line 20 */ +#define EXTI_RTEN_RTEN21 BIT(21) /*!< rising edge from line 21 */ +#define EXTI_RTEN_RTEN22 BIT(22) /*!< rising edge from line 22 */ +#define EXTI_RTEN_RTEN23 BIT(23) /*!< rising edge from line 23 */ +#define EXTI_RTEN_RTEN24 BIT(24) /*!< rising edge from line 24 */ +#define EXTI_RTEN_RTEN25 BIT(25) /*!< rising edge from line 25 */ + +/* EXTI_FTEN */ +#define EXTI_FTEN_FTEN0 BIT(0) /*!< falling edge from line 0 */ +#define EXTI_FTEN_FTEN1 BIT(1) /*!< falling edge from line 1 */ +#define EXTI_FTEN_FTEN2 BIT(2) /*!< falling edge from line 2 */ +#define EXTI_FTEN_FTEN3 BIT(3) /*!< falling edge from line 3 */ +#define EXTI_FTEN_FTEN4 BIT(4) /*!< falling edge from line 4 */ +#define EXTI_FTEN_FTEN5 BIT(5) /*!< falling edge from line 5 */ +#define EXTI_FTEN_FTEN6 BIT(6) /*!< falling edge from line 6 */ +#define EXTI_FTEN_FTEN7 BIT(7) /*!< falling edge from line 7 */ +#define EXTI_FTEN_FTEN8 BIT(8) /*!< falling edge from line 8 */ +#define EXTI_FTEN_FTEN9 BIT(9) /*!< falling edge from line 9 */ +#define EXTI_FTEN_FTEN10 BIT(10) /*!< falling edge from line 10 */ +#define EXTI_FTEN_FTEN11 BIT(11) /*!< falling edge from line 11 */ +#define EXTI_FTEN_FTEN12 BIT(12) /*!< falling edge from line 12 */ +#define EXTI_FTEN_FTEN13 BIT(13) /*!< falling edge from line 13 */ +#define EXTI_FTEN_FTEN14 BIT(14) /*!< falling edge from line 14 */ +#define EXTI_FTEN_FTEN15 BIT(15) /*!< falling edge from line 15 */ +#define EXTI_FTEN_FTEN16 BIT(16) /*!< falling edge from line 16 */ +#define EXTI_FTEN_FTEN17 BIT(17) /*!< falling edge from line 17 */ +#define EXTI_FTEN_FTEN18 BIT(18) /*!< falling edge from line 18 */ +#define EXTI_FTEN_FTEN19 BIT(19) /*!< falling edge from line 19 */ +#define EXTI_FTEN_FTEN20 BIT(20) /*!< falling edge from line 20 */ +#define EXTI_FTEN_FTEN21 BIT(21) /*!< falling edge from line 21 */ +#define EXTI_FTEN_FTEN22 BIT(22) /*!< falling edge from line 22 */ +#define EXTI_FTEN_FTEN23 BIT(23) /*!< falling edge from line 23 */ +#define EXTI_FTEN_FTEN24 BIT(24) /*!< falling edge from line 24 */ +#define EXTI_FTEN_FTEN25 BIT(25) /*!< falling edge from line 25 */ + +/* EXTI_SWIEV */ +#define EXTI_SWIEV_SWIEV0 BIT(0) /*!< software interrupt/event request from line 0 */ +#define EXTI_SWIEV_SWIEV1 BIT(1) /*!< software interrupt/event request from line 1 */ +#define EXTI_SWIEV_SWIEV2 BIT(2) /*!< software interrupt/event request from line 2 */ +#define EXTI_SWIEV_SWIEV3 BIT(3) /*!< software interrupt/event request from line 3 */ +#define EXTI_SWIEV_SWIEV4 BIT(4) /*!< software interrupt/event request from line 4 */ +#define EXTI_SWIEV_SWIEV5 BIT(5) /*!< software interrupt/event request from line 5 */ +#define EXTI_SWIEV_SWIEV6 BIT(6) /*!< software interrupt/event request from line 6 */ +#define EXTI_SWIEV_SWIEV7 BIT(7) /*!< software interrupt/event request from line 7 */ +#define EXTI_SWIEV_SWIEV8 BIT(8) /*!< software interrupt/event request from line 8 */ +#define EXTI_SWIEV_SWIEV9 BIT(9) /*!< software interrupt/event request from line 9 */ +#define EXTI_SWIEV_SWIEV10 BIT(10) /*!< software interrupt/event request from line 10 */ +#define EXTI_SWIEV_SWIEV11 BIT(11) /*!< software interrupt/event request from line 11 */ +#define EXTI_SWIEV_SWIEV12 BIT(12) /*!< software interrupt/event request from line 12 */ +#define EXTI_SWIEV_SWIEV13 BIT(13) /*!< software interrupt/event request from line 13 */ +#define EXTI_SWIEV_SWIEV14 BIT(14) /*!< software interrupt/event request from line 14 */ +#define EXTI_SWIEV_SWIEV15 BIT(15) /*!< software interrupt/event request from line 15 */ +#define EXTI_SWIEV_SWIEV16 BIT(16) /*!< software interrupt/event request from line 16 */ +#define EXTI_SWIEV_SWIEV17 BIT(17) /*!< software interrupt/event request from line 17 */ +#define EXTI_SWIEV_SWIEV18 BIT(18) /*!< software interrupt/event request from line 18 */ +#define EXTI_SWIEV_SWIEV19 BIT(19) /*!< software interrupt/event request from line 19 */ +#define EXTI_SWIEV_SWIEV20 BIT(20) /*!< software interrupt/event request from line 20 */ +#define EXTI_SWIEV_SWIEV21 BIT(21) /*!< software interrupt/event request from line 21 */ +#define EXTI_SWIEV_SWIEV22 BIT(22) /*!< software interrupt/event request from line 22 */ +#define EXTI_SWIEV_SWIEV23 BIT(23) /*!< software interrupt/event request from line 23 */ +#define EXTI_SWIEV_SWIEV24 BIT(24) /*!< software interrupt/event request from line 24 */ +#define EXTI_SWIEV_SWIEV25 BIT(25) /*!< software interrupt/event request from line 25 */ + +/* EXTI_PD */ +#define EXTI_PD_PD0 BIT(0) /*!< interrupt pending status from line 0 */ +#define EXTI_PD_PD1 BIT(1) /*!< interrupt pending status from line 1 */ +#define EXTI_PD_PD2 BIT(2) /*!< interrupt pending status from line 2 */ +#define EXTI_PD_PD3 BIT(3) /*!< interrupt pending status from line 3 */ +#define EXTI_PD_PD4 BIT(4) /*!< interrupt pending status from line 4 */ +#define EXTI_PD_PD5 BIT(5) /*!< interrupt pending status from line 5 */ +#define EXTI_PD_PD6 BIT(6) /*!< interrupt pending status from line 6 */ +#define EXTI_PD_PD7 BIT(7) /*!< interrupt pending status from line 7 */ +#define EXTI_PD_PD8 BIT(8) /*!< interrupt pending status from line 8 */ +#define EXTI_PD_PD9 BIT(9) /*!< interrupt pending status from line 9 */ +#define EXTI_PD_PD10 BIT(10) /*!< interrupt pending status from line 10 */ +#define EXTI_PD_PD11 BIT(11) /*!< interrupt pending status from line 11 */ +#define EXTI_PD_PD12 BIT(12) /*!< interrupt pending status from line 12 */ +#define EXTI_PD_PD13 BIT(13) /*!< interrupt pending status from line 13 */ +#define EXTI_PD_PD14 BIT(14) /*!< interrupt pending status from line 14 */ +#define EXTI_PD_PD15 BIT(15) /*!< interrupt pending status from line 15 */ +#define EXTI_PD_PD16 BIT(16) /*!< interrupt pending status from line 16 */ +#define EXTI_PD_PD17 BIT(17) /*!< interrupt pending status from line 17 */ +#define EXTI_PD_PD18 BIT(18) /*!< interrupt pending status from line 18 */ +#define EXTI_PD_PD19 BIT(19) /*!< interrupt pending status from line 19 */ +#define EXTI_PD_PD20 BIT(20) /*!< interrupt pending status from line 20 */ +#define EXTI_PD_PD21 BIT(21) /*!< interrupt pending status from line 21 */ +#define EXTI_PD_PD22 BIT(22) /*!< interrupt pending status from line 22 */ +#define EXTI_PD_PD23 BIT(23) /*!< interrupt pending status from line 23 */ +#define EXTI_PD_PD24 BIT(24) /*!< interrupt pending status from line 24 */ +#define EXTI_PD_PD25 BIT(25) /*!< interrupt pending status from line 25 */ + +/* constants definitions */ +/* EXTI line number */ +typedef enum +{ + EXTI_0 = BIT(0), /*!< EXTI line 0 */ + EXTI_1 = BIT(1), /*!< EXTI line 1 */ + EXTI_2 = BIT(2), /*!< EXTI line 2 */ + EXTI_3 = BIT(3), /*!< EXTI line 3 */ + EXTI_4 = BIT(4), /*!< EXTI line 4 */ + EXTI_5 = BIT(5), /*!< EXTI line 5 */ + EXTI_6 = BIT(6), /*!< EXTI line 6 */ + EXTI_7 = BIT(7), /*!< EXTI line 7 */ + EXTI_8 = BIT(8), /*!< EXTI line 8 */ + EXTI_9 = BIT(9), /*!< EXTI line 9 */ + EXTI_10 = BIT(10), /*!< EXTI line 10 */ + EXTI_11 = BIT(11), /*!< EXTI line 11 */ + EXTI_12 = BIT(12), /*!< EXTI line 12 */ + EXTI_13 = BIT(13), /*!< EXTI line 13 */ + EXTI_14 = BIT(14), /*!< EXTI line 14 */ + EXTI_15 = BIT(15), /*!< EXTI line 15 */ + EXTI_16 = BIT(16), /*!< EXTI line 16 */ + EXTI_17 = BIT(17), /*!< EXTI line 17 */ + EXTI_18 = BIT(18), /*!< EXTI line 18 */ + EXTI_19 = BIT(19), /*!< EXTI line 19 */ + EXTI_20 = BIT(20), /*!< EXTI line 20 */ + EXTI_21 = BIT(21), /*!< EXTI line 21 */ + EXTI_22 = BIT(22), /*!< EXTI line 22 */ + EXTI_23 = BIT(23), /*!< EXTI line 23 */ + EXTI_24 = BIT(24), /*!< EXTI line 24 */ + EXTI_25 = BIT(25) /*!< EXTI line 25 */ +}exti_line_enum; + +/* external interrupt and event */ +typedef enum +{ + EXTI_INTERRUPT = 0, /*!< EXTI interrupt mode */ + EXTI_EVENT /*!< EXTI event mode */ +}exti_mode_enum; + +/* interrupt trigger mode */ +typedef enum +{ + EXTI_TRIG_RISING = 0, /*!< EXTI rising edge trigger */ + EXTI_TRIG_FALLING, /*!< EXTI falling edge trigger */ + EXTI_TRIG_BOTH, /*!< EXTI rising and falling edge trigger */ + EXTI_TRIG_NONE /*!< EXTI without rising or falling edge trigger */ +}exti_trig_type_enum; + +/* function declarations */ +/* deinitialize the EXTI */ +void exti_deinit(void); +/* initialize the EXTI line x */ +void exti_init(exti_line_enum linex, exti_mode_enum mode, exti_trig_type_enum trig_type); +/* enable the interrupts from EXTI line x */ +void exti_interrupt_enable(exti_line_enum linex); +/* disable the interrupts from EXTI line x */ +void exti_interrupt_disable(exti_line_enum linex); +/* enable the events from EXTI line x */ +void exti_event_enable(exti_line_enum linex); +/* disable the events from EXTI line x */ +void exti_event_disable(exti_line_enum linex); +/* enable the software interrupt event from EXTI line x */ +void exti_software_interrupt_enable(exti_line_enum linex); +/* disable the software interrupt event from EXTI line x */ +void exti_software_interrupt_disable(exti_line_enum linex); + +/* interrupt & flag functions */ +/* get EXTI line x interrupt pending flag */ +FlagStatus exti_flag_get(exti_line_enum linex); +/* clear EXTI line x interrupt pending flag */ +void exti_flag_clear(exti_line_enum linex); +/* get EXTI line x interrupt pending flag */ +FlagStatus exti_interrupt_flag_get(exti_line_enum linex); +/* clear EXTI line x interrupt pending flag */ +void exti_interrupt_flag_clear(exti_line_enum linex); + +#endif /* GD32F5XX_EXTI_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_fmc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_fmc.h new file mode 100644 index 0000000..3c2ee22 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_fmc.h @@ -0,0 +1,644 @@ +/*! + \file gd32f5xx_fmc.h + \brief definitions for the FMC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_FMC_H +#define GD32F5XX_FMC_H + +#include "gd32f5xx.h" + +/* FMC and option byte definition */ +#define FMC FMC_BASE /*!< FMC register base address */ +#define OB OB_BASE /*!< option byte base address */ + +/* registers definitions */ +#define FMC_KEY REG32((FMC) + 0x00000004U) /*!< FMC unlock key register */ +#define FMC_OBKEY REG32((FMC) + 0x00000008U) /*!< FMC option byte unlock key register */ +#define FMC_STAT REG32((FMC) + 0x0000000CU) /*!< FMC status register */ +#define FMC_CTL REG32((FMC) + 0x00000010U) /*!< FMC control register */ +#define FMC_OBCTL0 REG32((FMC) + 0x00000014U) /*!< FMC option byte control register 0 */ +#define FMC_OBCTL1 REG32((FMC) + 0x00000018U) /*!< FMC option byte control register 1 */ +#define FMC_PECFG REG32((FMC) + 0x00000020U) /*!< FMC page erase configuration register */ +#define FMC_PEKEY REG32((FMC) + 0x00000024U) /*!< FMC unlock page erase key register */ +#define FMC_OTP1CFG REG32((FMC) + 0x00000028U) /*!< FMC OTP1 configuration register */ +#define FMC_LDECCADDR0 REG32((FMC) + 0x0000002CU) /*!< FMC two bits ECC error address0 when load code from flash/bootloader/OTP1 */ +#define FMC_LDECCADDR1 REG32((FMC) + 0x00000030U) /*!< FMC two bits ECC error address1 when load code from flash/bootloader/OTP1 */ +#define FMC_LDECCADDR2 REG32((FMC) + 0x00000034U) /*!< FMC two bits ECC error address2 when load code from flash/bootloader/OTP1 */ +#define FMC_OBSTAT REG32((FMC) + 0x00000040U) /*!< FMC option bytes status register */ +#define FMC_PID REG32((FMC) + 0x00000100U) /*!< FMC product ID register */ +#define EFUSE_CS REG32((FMC) + 0x00000200U) /*!< EFUSE control and status register */ +#define EFUSE_ADDR REG32((FMC) + 0x00000204U) /*!< EFUSE address register */ +#define EFUSE_CTL REG32((FMC) + 0x00000208U) /*!< EFUSE efuse controlregister */ +#define EFUSE_USER_DATA REG32((FMC) + 0x0000020CU) /*!< EFUSE user data register */ + +#define OB_USER REG8((OB) + 0x00010000U) /*!< option byte user value*/ +#define OB_SPC REG8((OB) + 0x00010001U) /*!< option byte security protection value */ +#define OB_WP0_0 REG8((OB) + 0x00010008U) /*!< option byte write protection 0 */ +#define OB_WP0_1 REG8((OB) + 0x00010009U) /*!< option byte write protection 0 */ +#define OB_WP0_2 REG8((OB) + 0x0001000CU) /*!< option byte write protection 0 */ +#define OB_WP1_0 REG8((OB) + 0x00000008U) /*!< option byte write protection 1 */ +#define OB_WP1_1 REG8((OB) + 0x00000009U) /*!< option byte write protection 1 */ +#define OB_WP1_2 REG8((OB) + 0x0000000CU) /*!< option byte write protection 1 */ + +/* registers offset */ +#define EFUSE_CTL_OFFSET ((uint32_t)0x00000208U) /*!< EFUSE efuse control register offset */ +#define EFUSE_USER_DATA_OFFSET ((uint32_t)0x0000020CU) /*!< EFUSE user data register offset */ + +/* bits definitions */ +/* FMC_KEY */ +#define FMC_KEY_KEY BITS(0,31) /*!< FMC main flash key bits */ + +/* FMC_OBKEY */ +#define FMC_OBKEY_OBKEY BITS(0,31) /*!< option byte key bits */ + +/* FMC_STAT */ +#define FMC_STAT_END BIT(0) /*!< end of operation flag bit */ +#define FMC_STAT_OPERR BIT(1) /*!< flash operation error flag bit */ +#define FMC_STAT_LDECCDET BIT(2) /*!< two bits ECC error when load code from flash/OTP1/bootloader */ +#define FMC_STAT_WPERR BIT(4) /*!< erase/Program protection error flag bit */ +#define FMC_STAT_PGAERR BIT(5) /*!< Program alignment error flag bit */ +#define FMC_STAT_PGMERR BIT(6) /*!< program size not match error flag bit */ +#define FMC_STAT_PGSERR BIT(7) /*!< program sequence error flag bit */ +#define FMC_STAT_RDCERR BIT(8) /*!< CBUS data read protection error flag bit */ +#define FMC_STAT_BUSY BIT(16) /*!< flash busy flag bit */ + +/* FMC_CTL */ +#define FMC_CTL_PG BIT(0) /*!< main flash program command bit */ +#define FMC_CTL_SER BIT(1) /*!< main flash sector erase command bit */ +#define FMC_CTL_MER0 BIT(2) /*!< main flash mass erase for bank0 command bit */ +#define FMC_CTL_SN BITS(3,7) /*!< select which sector number to be erased */ +#define FMC_CTL_PSZ BITS(8,9) /*!< program size bit */ +#define FMC_CTL_DWPGE BIT(10) /*!< double word Program size bit enable bit */ +#define FMC_CTL_SN_5 BIT(11) /*!< bit 5 of SN */ +#define FMC_CTL_MER1 BIT(15) /*!< main flash mass erase for bank1 command bit */ +#define FMC_CTL_START BIT(16) /*!< send erase command to FMC bit */ +#define FMC_CTL_ENDIE BIT(24) /*!< end of operation interrupt enable bit */ +#define FMC_CTL_ERRIE BIT(25) /*!< error interrupt enable bit */ +#define FMC_CTL_LDECCIE BIT(26) /*!< load code ECC error interrupt enable bit */ +#define FMC_CTL_NWLDE BIT(29) /*!< No wait time area load enable when system reset */ +#define FMC_CTL_RLBP BIT(30) /*!< Read lock block protection for OTP2 */ +#define FMC_CTL_LK BIT(31) /*!< FMC_CTL lock bit */ + +/* FMC_OBCTL0 */ +#define FMC_OBCTL0_OB_LK BIT(0) /*!< FMC_OBCTL0 lock bit */ +#define FMC_OBCTL0_OB_START BIT(1) /*!< send option byte change command to FMC bit */ +#define FMC_OBCTL0_BOR_TH BITS(2,3) /*!< option byte BOR threshold value */ +#define FMC_OBCTL0_BB BIT(4) /*!< option byte boot bank value */ +#define FMC_OBCTL0_NWDG_HW BIT(5) /*!< option byte watchdog value */ +#define FMC_OBCTL0_NRST_DPSLP BIT(6) /*!< option byte deepsleep reset value */ +#define FMC_OBCTL0_NRST_STDBY BIT(7) /*!< option byte standby reset value */ +#define FMC_OBCTL0_SPC BITS(8,15) /*!< option byte Security Protection code */ +#define FMC_OBCTL0_WP0 BITS(16,27) /*!< erase/program protection of low 12 sectors of bank0 when DRP is 0 */ +#define FMC_OBCTL0_ECCEN BIT(28) /*!< ECC enable bit */ +#define FMC_OBCTL0_NWA BIT(29) /*!< no waiting time area select bit */ +#define FMC_OBCTL0_DRP BIT(31) /*!< CBUS read protection bit */ + +/* FMC_OBCTL1 */ +#define FMC_OBCTL1_WP0_H BITS(0,7) /*!< erase/program protection of high 8 sectors of bank0 when DRP is 0 */ +#define FMC_OBCTL1_WP1_H BITS(8,15) /*!< erase/program protection of high 8 sectors of bank1 when DRP is 0 */ +#define FMC_OBCTL1_WP1_L BITS(16,27) /*!< erase/program protection of low 12 sectors of bank1 when DRP is 0 */ + +/* FMC_PECFG */ +#define FMC_PECFG_PE_ADDR BITS(0,28) /*!< page address (4KB alignment) */ +#define FMC_PECFG_PE_EN BIT(31) /*!< the enable bit of page erase function */ + +/* FMC_PEKEY */ +#define FMC_PEKEY_PE_KEY BITS(0,31) /*!< FMC_PECFG unlock key value */ + +/* FMC_OTP1CFG */ +#define FMC_OTP1CFG_OTP1REN BITS(0,15) /*!< FMC OTP1 read enable bits */ + +/* FMC_LDECCADDR0 */ +#define FMC_LDECCADDR0_LDECCADDR0 BITS(0,31) /*!< ECC two bits error address0 when load code from flash/bootloader/OTP1 */ + +/* FMC_LDECCADDR1 */ +#define FMC_LDECCADDR1_LDECCADDR1 BITS(0,31) /*!< ECC two bits error address1 when load code from flash/bootloader/OTP1 */ + +/* FMC_LDECCADDR2 */ +#define FMC_LDECCADDR2_LDECCADDR2 BITS(0,31) /*!< ECC two bits error address2 when load code from flash/bootloader/OTP1 */ + +/* FMC_OBSTAT */ +#define FMC_OB_SPCL BIT(1) /*!< security protection is level low */ +#define FMC_OB_SPCH BIT(2) /*!< security protection is level high */ + +/* FMC_PID */ +#define FMC_PID_PID BITS(0,31) /*!< product ID bits */ + +/* EFUSE_CS */ +#define EFUSE_CS_EFSTR BIT(0) /*!< start efuse operation */ +#define EFUSE_CS_EFRW BIT(1) /*!< the selection of efuse operation */ +#define EFUSE_CS_EFBYP BIT(2) /*!< EFUSE program supply selection */ +#define EFUSE_CS_PGIF BIT(16) /*!< program operation complete flag */ +#define EFUSE_CS_RDIF BIT(17) /*!< read operation complete flag */ +#define EFUSE_CS_OVBERIF BIT(18) /*!< overstep boundary error flag */ +#define EFUSE_CS_PGIE BIT(20) /*!< enable bit for program operation completed interrupt */ +#define EFUSE_CS_RDIE BIT(21) /*!< enable bit for read operation completed interrupt */ +#define EFUSE_CS_OVBERIE BIT(22) /*!< enable bit for overstep boundary error interrupt */ +#define EFUSE_CS_PGIC BIT(24) /*!< clear bit for program operation completed interrupt flag */ +#define EFUSE_CS_RDIC BIT(25) /*!< clear bit for read operation completed interrupt flag */ +#define EFUSE_CS_OVBERIC BIT(26) /*!< clear bit for overstep boundary error interrupt flag */ + +/* EFUSE_ADDR */ +#define EFUSE_ADDR_EFADDR BITS(0,4) /*!< read or program efuse data start address */ +#define EFUSE_ADDR_EFSIZE BITS(8,12) /*!< read or program efuse data size */ + +/* EFUSE_CTL */ +#define EFUSE_CTL_EFSPC BIT(0) /*!< EFUSE security protection level */ +#define EFUSE_CTL_NDBG BIT(1) /*!< debugging permission setting */ +#define EFUSE_CTL_NBTSB BIT(2) /*!< not boot from sram or bootloader */ +#define EFUSE_CTL_BTFOSEL BIT(3) /*!< select boot from flash or OTP1 when NBTSB is 1 or BOOT0 is 0 */ +#define EFUSE_CTL_UDLK BIT(6) /*!< EFUSE_USER_DATA register lock bit */ +#define EFUSE_CTL_LK BIT(7) /*!< EFUSE_CTL register lock bit */ + +/* EFUSE_USER_DATA */ +#define EFUSE_USER_DATA_USERDATA BITS(0,7) /*!< EFUSE USER_DATA value */ + +/* unlock key */ +#define UNLOCK_KEY0 ((uint32_t)0x45670123U) /*!< unlock key 0 */ +#define UNLOCK_KEY1 ((uint32_t)0xCDEF89ABU) /*!< unlock key 1 */ +#define UNLOCK_PE_KEY ((uint32_t)0xA9B8C7D6U) /*!< unlock page erase function key */ + +#define OB_UNLOCK_KEY0 ((uint32_t)0x08192A3BU) /*!< ob unlock key 0 */ +#define OB_UNLOCK_KEY1 ((uint32_t)0x4C5D6E7FU) /*!< ob unlock key 1 */ + +/* option byte BOR threshold value */ +#define OBCTL0_BOR_TH(regval) (BITS(2,3) & ((uint32_t)(regval)) << 2U) +#define OB_BOR_TH_VALUE3 OBCTL0_BOR_TH(0) /*!< BOR threshold value 3 */ +#define OB_BOR_TH_VALUE2 OBCTL0_BOR_TH(1) /*!< BOR threshold value 2 */ +#define OB_BOR_TH_VALUE1 OBCTL0_BOR_TH(2) /*!< BOR threshold value 1 */ +#define OB_BOR_TH_OFF OBCTL0_BOR_TH(3) /*!< no BOR function */ + +/* option byte boot bank value */ +#define OBCTL0_BB(regval) (BIT(4) & ((uint32_t)(regval) << 4U)) +#define OB_BB_DISABLE OBCTL0_BB(0) /*!< boot from bank0 */ +#define OB_BB_ENABLE OBCTL0_BB(1) /*!< boot from bank1 or bank0 if bank1 is void */ + +/* option byte software/hardware free watch dog timer */ +#define OBCTL0_NWDG_HW(regval) (BIT(5) & ((uint32_t)(regval)) << 5U) +#define OB_FWDGT_SW OBCTL0_NWDG_HW(1) /*!< software free watchdog */ +#define OB_FWDGT_HW OBCTL0_NWDG_HW(0) /*!< hardware free watchdog */ + +/* option byte reset or not entering deep sleep mode */ +#define OBCTL0_NRST_DPSLP(regval) (BIT(6) & ((uint32_t)(regval)) << 6U) +#define OB_DEEPSLEEP_NRST OBCTL0_NRST_DPSLP(1) /*!< no reset when entering deepsleep mode */ +#define OB_DEEPSLEEP_RST OBCTL0_NRST_DPSLP(0) /*!< generate a reset instead of entering deepsleep mode */ + +/* option byte reset or not entering standby mode */ +#define OBCTL0_NRST_STDBY(regval) (BIT(7) & ((uint32_t)(regval)) << 7U) +#define OB_STDBY_NRST OBCTL0_NRST_STDBY(1) /*!< no reset when entering deepsleep mode */ +#define OB_STDBY_RST OBCTL0_NRST_STDBY(0) /*!< generate a reset instead of entering standby mode */ + +/* option byte sram/flash ECC configure */ +#define OBCTL0_ECCEN(regval) (BIT(28) & ((uint32_t)(regval) << 28U)) +#define OB_ECC_DISABLE OBCTL0_ECCEN(0) /*!< sram/flash ECC disable */ +#define OB_ECC_ENABLE OBCTL0_ECCEN(1) /*!< sram/flash ECC enable */ + +/* option byte no waiting time area select */ +#define OBCTL0_NWA(regval) (BIT(29) & ((uint32_t)(regval) << 29U)) +#define OB_NWA_BANK1 OBCTL0_NWA(0) /*!< bank1 is no waiting time area */ +#define OB_NWA_BANK0 OBCTL0_NWA(1) /*!< bank0 is no waiting time area */ + +/* read protect configure */ +#define FMC_NSPC ((uint8_t)0xAAU) /*!< no security protection */ +#define FMC_LSPC ((uint8_t)0xBBU) /*!< low security protection */ +#define FMC_HSPC ((uint8_t)0xCCU) /*!< high security protection */ + +/* option bytes write protection */ +#define OB_WP_0 ((uint64_t)0x0000000000000001U) /*!< erase/program protection of sector 0 */ +#define OB_WP_1 ((uint64_t)0x0000000000000002U) /*!< erase/program protection of sector 1 */ +#define OB_WP_2 ((uint64_t)0x0000000000000004U) /*!< erase/program protection of sector 2 */ +#define OB_WP_3 ((uint64_t)0x0000000000000008U) /*!< erase/program protection of sector 3 */ +#define OB_WP_4 ((uint64_t)0x0000000000000010U) /*!< erase/program protection of sector 4 */ +#define OB_WP_5 ((uint64_t)0x0000000000000020U) /*!< erase/program protection of sector 5 */ +#define OB_WP_6 ((uint64_t)0x0000000000000040U) /*!< erase/program protection of sector 6 */ +#define OB_WP_7 ((uint64_t)0x0000000000000080U) /*!< erase/program protection of sector 7 */ +#define OB_WP_8 ((uint64_t)0x0000000000000100U) /*!< erase/program protection of sector 8 */ +#define OB_WP_9 ((uint64_t)0x0000000000000200U) /*!< erase/program protection of sector 9 */ +#define OB_WP_10 ((uint64_t)0x0000000000000400U) /*!< erase/program protection of sector 10 */ +#define OB_WP_11 ((uint64_t)0x0000000000000800U) /*!< erase/program protection of sector 11 */ +#define OB_WP_12 ((uint64_t)0x0000000000001000U) /*!< erase/program protection of sector 12 */ +#define OB_WP_13 ((uint64_t)0x0000000000002000U) /*!< erase/program protection of sector 13 */ +#define OB_WP_14 ((uint64_t)0x0000000000004000U) /*!< erase/program protection of sector 14 */ +#define OB_WP_15 ((uint64_t)0x0000000000008000U) /*!< erase/program protection of sector 15 */ +#define OB_WP_16 ((uint64_t)0x0000000000010000U) /*!< erase/program protection of sector 16 */ +#define OB_WP_17 ((uint64_t)0x0000000000020000U) /*!< erase/program protection of sector 17 */ +#define OB_WP_18 ((uint64_t)0x0000000000040000U) /*!< erase/program protection of sector 18 */ +#define OB_WP_19 ((uint64_t)0x0000000000080000U) /*!< erase/program protection of sector 19 */ +#define OB_WP_20 ((uint64_t)0x0000000000100000U) /*!< erase/program protection of sector 20 */ +#define OB_WP_21 ((uint64_t)0x0000000000200000U) /*!< erase/program protection of sector 21 */ +#define OB_WP_22 ((uint64_t)0x0000000000400000U) /*!< erase/program protection of sector 22 */ +#define OB_WP_23 ((uint64_t)0x0000000000800000U) /*!< erase/program protection of sector 23 */ +#define OB_WP_24 ((uint64_t)0x0000000001000000U) /*!< erase/program protection of sector 24 */ +#define OB_WP_25 ((uint64_t)0x0000000002000000U) /*!< erase/program protection of sector 25 */ +#define OB_WP_26 ((uint64_t)0x0000000004000000U) /*!< erase/program protection of sector 26 */ +#define OB_WP_27 ((uint64_t)0x0000000008000000U) /*!< erase/program protection of sector 27 */ +#define OB_WP_28 ((uint64_t)0x0000000010000000U) /*!< erase/program protection of sector 28 */ +#define OB_WP_29 ((uint64_t)0x0000000020000000U) /*!< erase/program protection of sector 29 */ +#define OB_WP_30 ((uint64_t)0x0000000040000000U) /*!< erase/program protection of sector 30 */ +#define OB_WP_31 ((uint64_t)0x0000000080000000U) /*!< erase/program protection of sector 31 */ +#define OB_WP_32 ((uint64_t)0x0000000100000000U) /*!< erase/program protection of sector 32 */ +#define OB_WP_33 ((uint64_t)0x0000000200000000U) /*!< erase/program protection of sector 33 */ +#define OB_WP_34 ((uint64_t)0x0000000400000000U) /*!< erase/program protection of sector 34 */ +#define OB_WP_35 ((uint64_t)0x0000000800000000U) /*!< erase/program protection of sector 35 */ +#define OB_WP_36 ((uint64_t)0x0000001000000000U) /*!< erase/program protection of sector 36 */ +#define OB_WP_37 ((uint64_t)0x0000002000000000U) /*!< erase/program protection of sector 37 */ +#define OB_WP_38 ((uint64_t)0x0000004000000000U) /*!< erase/program protection of sector 38 */ +#define OB_WP_39_53 ((uint64_t)0x0000008000000000U) /*!< erase/program protection of sector 39~53 */ +#define OB_WP_ALL ((uint64_t)0x000000FFFFFFFFFFU) /*!< erase/program protection of all sectors */ + +/* option bytes CBUS read protection */ +#define OB_DRP_0 ((uint64_t)0x0000000000000001U) /*!< CBUS read protection protection of sector 0 */ +#define OB_DRP_1 ((uint64_t)0x0000000000000002U) /*!< CBUS read protection protection of sector 1 */ +#define OB_DRP_2 ((uint64_t)0x0000000000000004U) /*!< CBUS read protection protection of sector 2 */ +#define OB_DRP_3 ((uint64_t)0x0000000000000008U) /*!< CBUS read protection protection of sector 3 */ +#define OB_DRP_4 ((uint64_t)0x0000000000000010U) /*!< CBUS read protection protection of sector 4 */ +#define OB_DRP_5 ((uint64_t)0x0000000000000020U) /*!< CBUS read protection protection of sector 5 */ +#define OB_DRP_6 ((uint64_t)0x0000000000000040U) /*!< CBUS read protection protection of sector 6 */ +#define OB_DRP_7 ((uint64_t)0x0000000000000080U) /*!< CBUS read protection protection of sector 7 */ +#define OB_DRP_8 ((uint64_t)0x0000000000000100U) /*!< CBUS read protection protection of sector 8 */ +#define OB_DRP_9 ((uint64_t)0x0000000000000200U) /*!< CBUS read protection protection of sector 9 */ +#define OB_DRP_10 ((uint64_t)0x0000000000000400U) /*!< CBUS read protection protection of sector 10 */ +#define OB_DRP_11 ((uint64_t)0x0000000000000800U) /*!< CBUS read protection protection of sector 11 */ +#define OB_DRP_12 ((uint64_t)0x0000000000001000U) /*!< CBUS read protection protection of sector 12 */ +#define OB_DRP_13 ((uint64_t)0x0000000000002000U) /*!< CBUS read protection protection of sector 13 */ +#define OB_DRP_14 ((uint64_t)0x0000000000004000U) /*!< CBUS read protection protection of sector 14 */ +#define OB_DRP_15 ((uint64_t)0x0000000000008000U) /*!< CBUS read protection protection of sector 15 */ +#define OB_DRP_16 ((uint64_t)0x0000000000010000U) /*!< CBUS read protection protection of sector 16 */ +#define OB_DRP_17 ((uint64_t)0x0000000000020000U) /*!< CBUS read protection protection of sector 17 */ +#define OB_DRP_18 ((uint64_t)0x0000000000040000U) /*!< CBUS read protection protection of sector 18 */ +#define OB_DRP_19 ((uint64_t)0x0000000000080000U) /*!< CBUS read protection protection of sector 19 */ +#define OB_DRP_20 ((uint64_t)0x0000000000100000U) /*!< CBUS read protection protection of sector 20 */ +#define OB_DRP_21 ((uint64_t)0x0000000000200000U) /*!< CBUS read protection protection of sector 21 */ +#define OB_DRP_22 ((uint64_t)0x0000000000400000U) /*!< CBUS read protection protection of sector 22 */ +#define OB_DRP_23 ((uint64_t)0x0000000000800000U) /*!< CBUS read protection protection of sector 23 */ +#define OB_DRP_24 ((uint64_t)0x0000000001000000U) /*!< CBUS read protection protection of sector 24 */ +#define OB_DRP_25 ((uint64_t)0x0000000002000000U) /*!< CBUS read protection protection of sector 25 */ +#define OB_DRP_26 ((uint64_t)0x0000000004000000U) /*!< CBUS read protection protection of sector 26 */ +#define OB_DRP_27 ((uint64_t)0x0000000008000000U) /*!< CBUS read protection protection of sector 27 */ +#define OB_DRP_28 ((uint64_t)0x0000000010000000U) /*!< CBUS read protection protection of sector 28 */ +#define OB_DRP_29 ((uint64_t)0x0000000020000000U) /*!< CBUS read protection protection of sector 29 */ +#define OB_DRP_30 ((uint64_t)0x0000000040000000U) /*!< CBUS read protection protection of sector 30 */ +#define OB_DRP_31 ((uint64_t)0x0000000080000000U) /*!< CBUS read protection protection of sector 31 */ +#define OB_DRP_32 ((uint64_t)0x0000000100000000U) /*!< CBUS read protection protection of sector 32 */ +#define OB_DRP_33 ((uint64_t)0x0000000200000000U) /*!< CBUS read protection protection of sector 33 */ +#define OB_DRP_34 ((uint64_t)0x0000000400000000U) /*!< CBUS read protection protection of sector 34 */ +#define OB_DRP_35 ((uint64_t)0x0000000800000000U) /*!< CBUS read protection protection of sector 35 */ +#define OB_DRP_36 ((uint64_t)0x0000001000000000U) /*!< CBUS read protection protection of sector 36 */ +#define OB_DRP_37 ((uint64_t)0x0000002000000000U) /*!< CBUS read protection protection of sector 37 */ +#define OB_DRP_38 ((uint64_t)0x0000004000000000U) /*!< CBUS read protection protection of sector 38 */ +#define OB_DRP_39_53 ((uint64_t)0x0000008000000000U) /*!< CBUS read protection protection of sector 39~53 */ +#define OB_DRP_ALL ((uint64_t)0x000000FFFFFFFFFFU) /*!< CBUS read protection protection of all sectors */ + +/* option bytes CBUS read protection mode */ +#define OBCTL0_DRP(regval) (BIT(31) & ((uint32_t)(regval) << 31U)) +#define OB_DRP_DISABLE OBCTL0_DRP(0) /*!< the WPx bits used as erase/program protection of each sector */ +#define OB_DRP_ENABLE OBCTL0_DRP(1) /*!< the WPx bits used as erase/program protection and CBUS read protection of each sector */ + +/* FMC sectors */ +#define SN_5 FMC_CTL_SN_5 /* bit 5 of sector number */ +#define CTL_SN(regval) (BITS(3,7) & ((uint32_t)(regval)) << 3) +#define CTL_SECTOR_NUMBER_0 CTL_SN(0) /*!< sector 0 */ +#define CTL_SECTOR_NUMBER_1 CTL_SN(1) /*!< sector 1 */ +#define CTL_SECTOR_NUMBER_2 CTL_SN(2) /*!< sector 2 */ +#define CTL_SECTOR_NUMBER_3 CTL_SN(3) /*!< sector 3 */ +#define CTL_SECTOR_NUMBER_4 CTL_SN(4) /*!< sector 4 */ +#define CTL_SECTOR_NUMBER_5 CTL_SN(5) /*!< sector 5 */ +#define CTL_SECTOR_NUMBER_6 CTL_SN(6) /*!< sector 6 */ +#define CTL_SECTOR_NUMBER_7 CTL_SN(7) /*!< sector 7 */ +#define CTL_SECTOR_NUMBER_8 CTL_SN(8) /*!< sector 8 */ +#define CTL_SECTOR_NUMBER_9 CTL_SN(9) /*!< sector 9 */ +#define CTL_SECTOR_NUMBER_10 CTL_SN(10) /*!< sector 10 */ +#define CTL_SECTOR_NUMBER_11 CTL_SN(11) /*!< sector 11 */ +#define CTL_SECTOR_NUMBER_12 CTL_SN(12) /*!< sector 12 */ +#define CTL_SECTOR_NUMBER_13 CTL_SN(13) /*!< sector 13 */ +#define CTL_SECTOR_NUMBER_14 CTL_SN(14) /*!< sector 14 */ +#define CTL_SECTOR_NUMBER_15 CTL_SN(15) /*!< sector 15 */ +#define CTL_SECTOR_NUMBER_16 CTL_SN(16) /*!< sector 16 */ +#define CTL_SECTOR_NUMBER_17 CTL_SN(17) /*!< sector 17 */ +#define CTL_SECTOR_NUMBER_18 CTL_SN(18) /*!< sector 18 */ +#define CTL_SECTOR_NUMBER_19 CTL_SN(19) /*!< sector 19 */ +#define CTL_SECTOR_NUMBER_20 CTL_SN(20) /*!< sector 20 */ +#define CTL_SECTOR_NUMBER_21 CTL_SN(21) /*!< sector 21 */ +#define CTL_SECTOR_NUMBER_22 CTL_SN(22) /*!< sector 22 */ +#define CTL_SECTOR_NUMBER_23 CTL_SN(23) /*!< sector 23 */ +#define CTL_SECTOR_NUMBER_24 CTL_SN(24) /*!< sector 24 */ +#define CTL_SECTOR_NUMBER_25 CTL_SN(25) /*!< sector 25 */ +#define CTL_SECTOR_NUMBER_26 CTL_SN(26) /*!< sector 26 */ +#define CTL_SECTOR_NUMBER_27 CTL_SN(27) /*!< sector 27 */ +#define CTL_SECTOR_NUMBER_28 CTL_SN(28) /*!< sector 28 */ +#define CTL_SECTOR_NUMBER_29 CTL_SN(29) /*!< sector 29 */ +#define CTL_SECTOR_NUMBER_30 CTL_SN(30) /*!< sector 30 */ +#define CTL_SECTOR_NUMBER_31 CTL_SN(31) /*!< sector 31 */ +#define CTL_SECTOR_NUMBER_32 (SN_5 | CTL_SN(0)) /*!< sector 32 */ +#define CTL_SECTOR_NUMBER_33 (SN_5 | CTL_SN(1)) /*!< sector 33 */ +#define CTL_SECTOR_NUMBER_34 (SN_5 | CTL_SN(2)) /*!< sector 34 */ +#define CTL_SECTOR_NUMBER_35 (SN_5 | CTL_SN(3)) /*!< sector 35 */ +#define CTL_SECTOR_NUMBER_36 (SN_5 | CTL_SN(4)) /*!< sector 36 */ +#define CTL_SECTOR_NUMBER_37 (SN_5 | CTL_SN(5)) /*!< sector 37 */ +#define CTL_SECTOR_NUMBER_38 (SN_5 | CTL_SN(6)) /*!< sector 38 */ +#define CTL_SECTOR_NUMBER_39 (SN_5 | CTL_SN(7)) /*!< sector 39 */ +#define CTL_SECTOR_NUMBER_40 (SN_5 | CTL_SN(8)) /*!< sector 40 */ +#define CTL_SECTOR_NUMBER_41 (SN_5 | CTL_SN(9)) /*!< sector 41 */ +#define CTL_SECTOR_NUMBER_42 (SN_5 | CTL_SN(10)) /*!< sector 42 */ +#define CTL_SECTOR_NUMBER_43 (SN_5 | CTL_SN(11)) /*!< sector 43 */ +#define CTL_SECTOR_NUMBER_44 (SN_5 | CTL_SN(12)) /*!< sector 44 */ +#define CTL_SECTOR_NUMBER_45 (SN_5 | CTL_SN(13)) /*!< sector 45 */ +#define CTL_SECTOR_NUMBER_46 (SN_5 | CTL_SN(14)) /*!< sector 46 */ +#define CTL_SECTOR_NUMBER_47 (SN_5 | CTL_SN(15)) /*!< sector 47 */ +#define CTL_SECTOR_NUMBER_48 (SN_5 | CTL_SN(16)) /*!< sector 48 */ +#define CTL_SECTOR_NUMBER_49 (SN_5 | CTL_SN(17)) /*!< sector 49 */ +#define CTL_SECTOR_NUMBER_50 (SN_5 | CTL_SN(18)) /*!< sector 50 */ +#define CTL_SECTOR_NUMBER_51 (SN_5 | CTL_SN(19)) /*!< sector 51 */ +#define CTL_SECTOR_NUMBER_52 (SN_5 | CTL_SN(20)) /*!< sector 52 */ +#define CTL_SECTOR_NUMBER_53 (SN_5 | CTL_SN(21)) /*!< sector 53 */ + +/* FMC program size */ +#define CTL_PSZ(regval) (BITS(8,9) & ((uint32_t)(regval)) << 8U) +#define CTL_PSZ_BYTE CTL_PSZ(0) /*!< FMC program by byte access */ +#define CTL_PSZ_HALF_WORD CTL_PSZ(1) /*!< FMC program by half-word access */ +#define CTL_PSZ_WORD CTL_PSZ(2) /*!< FMC program by word access */ + +/* FMC interrupt enable */ +#define FMC_INT_END FMC_CTL_ENDIE /*!< enable FMC end of program interrupt */ +#define FMC_INT_ERR FMC_CTL_ERRIE /*!< enable FMC error interrupt */ +#define FMC_INT_LDECC FMC_CTL_LDECCIE /*!< enable FMC load code ECC error interrupt */ + +/* FMC flags */ +#define FMC_FLAG_END FMC_STAT_END /*!< FMC end of operation flag bit */ +#define FMC_FLAG_OPERR FMC_STAT_OPERR /*!< FMC operation error flag bit */ +#define FMC_FLAG_LDECCDET FMC_STAT_LDECCDET /*!< FMC two bits ECC error when load code from flash/OTP1/bootloader */ +#define FMC_FLAG_WPERR FMC_STAT_WPERR /*!< FMC erase/program protection error flag bit */ +#define FMC_FLAG_PGAERR FMC_STAT_PGAERR /*!< FMC program alignment error flag bit */ +#define FMC_FLAG_PGMERR FMC_STAT_PGMERR /*!< FMC program size not match error flag bit */ +#define FMC_FLAG_PGSERR FMC_STAT_PGSERR /*!< FMC program sequence error flag bit */ +#define FMC_FLAG_RDCERR FMC_STAT_RDCERR /*!< FMC CBUS data read protection error flag bit */ +#define FMC_FLAG_BUSY FMC_STAT_BUSY /*!< FMC busy flag */ + +/* FMC interrupt flags */ +#define FMC_INT_FLAG_END FMC_STAT_END /*!< FMC end of operation interrupt flag */ +#define FMC_INT_FLAG_OPERR FMC_STAT_OPERR /*!< FMC operation error interrupt flag */ +#define FMC_INT_FLAG_LDECCDET FMC_STAT_LDECCDET /*!< FMC two bits ECC error when load code from flash/OTP1/bootloader interrupt flag */ +#define FMC_INT_FLAG_WPERR FMC_STAT_WPERR /*!< FMC erase/program protection error interrupt flag */ +#define FMC_INT_FLAG_PGAERR FMC_STAT_PGAERR /*!< FMC program alignment error interrupt flag */ +#define FMC_INT_FLAG_PGMERR FMC_STAT_PGMERR /*!< FMC program size not match error interrupt flag */ +#define FMC_INT_FLAG_PGSERR FMC_STAT_PGSERR /*!< FMC program sequence error interrupt flag */ +#define FMC_INT_FLAG_RDCERR FMC_STAT_RDCERR /*!< FMC CBUS data read protection error interrupt flag */ + +/* FMC time out */ +#define FMC_TIMEOUT_COUNT ((uint32_t)0x4FFFFFFFU) /*!< count to judge of FMC timeout */ + +/* EFUSE flags */ +#define EFUSE_PGIF EFUSE_CS_PGIF /*!< programming operation completion flag */ +#define EFUSE_RDIF EFUSE_CS_RDIF /*!< read operation completion flag */ +#define EFUSE_OBERIF EFUSE_CS_OVBERIF /*!< overstep boundary error flag */ + +/* EFUSE flags clear */ +#define EFUSE_PGIC EFUSE_CS_PGIC /*!< clear programming operation completion flag */ +#define EFUSE_RDIC EFUSE_CS_RDIC /*!< clear read operation completion flag */ +#define EFUSE_OBERIC EFUSE_CS_OVBERIC /*!< clear overstep boundary error flag */ + +/* EFUSE interrupt enable */ +#define EFUSE_INT_OBER EFUSE_CS_OVBERIE /*!< overstep boundary error interrupt enable */ +#define EFUSE_INT_PG EFUSE_CS_PGIE /*!< programming operation completion interrupt enable */ +#define EFUSE_INT_RD EFUSE_CS_RDIE /*!< read operation completion interrupt enable */ + +/* EFUSE interrupt flags */ +#define EFUSE_INT_OBERIF EFUSE_CS_OVBERIF /*!< overstep boundary error interrupt flag */ +#define EFUSE_INT_PGIF EFUSE_CS_PGIF /*!< programming operation completion interrupt flag */ +#define EFUSE_INT_RDIF EFUSE_CS_RDIF /*!< read operation completion interrupt flag */ + +/* EFUSE interrupt flags clear */ +#define EFUSE_INT_OBERIC EFUSE_CS_OVBERIC /*!< clear overstep boundary error interrupt flag */ +#define EFUSE_INT_PGIC EFUSE_CS_PGIC /*!< clear programming operation completion interrupt flag */ +#define EFUSE_INT_RDIC EFUSE_CS_RDIC /*!< clear read operation completion interrupt flag */ + +/* EFUSE macro address */ +#define EFUSE_CTL_EFADDR ((uint32_t)0x00000001U) /*!< efuse control address */ +#define USER_DATA_EFADDR ((uint32_t)0x00000002U) /*!< user data address */ + +/* EFUSE time out */ +#define EFUSE_TIMEOUT_COUNT ((uint32_t)0x0000FFFFU) /*!< count to judge of EFUSE timeout */ + +/* OTP0 address */ +#define OTP0_DATA_BLOCK_BASE_ADDRESS ((uint32_t)0x1FFF7800U) /*!< OTP0 data block base address */ +#define OTP0_LOCK_BLOCK_BASE_ADDRESS ((uint32_t)0x1FFF7840U) /*!< OTP0 lock block base address */ + +/* OTP1 address */ +#define OTP1_DATA_BLOCK_BASE_ADDRESS ((uint32_t)0x1FF00000U) /*!< OTP1 data block base address */ +#define OTP1_LOCK_BLOCK_BASE_ADDRESS ((uint32_t)0x1FF20200U) /*!< OTP1 lock block base address */ + +/* OTP2 address */ +#define OTP2_DATA_BLOCK_BASE_ADDRESS ((uint32_t)0x1FF20000U) /*!< OTP2 data block base address */ +#define OTP2_WLOCK_BLOCK_BASE_ADDRESS ((uint32_t)0x1FF20210U) /*!< OTP2 write lock block base address */ +#define OTP2_RLOCK_BLOCK_BASE_ADDRESS ((uint32_t)0x1FF20220U) /*!< OTP2 read lock block base address */ + +/* OTP1 data blockx read enable */ +#define OTP1_DATA_BLOCK_0 BIT(0) /*!< erase/program protection of sector 0 */ +#define OTP1_DATA_BLOCK_1 BIT(1) /*!< erase/program protection of sector 1 */ +#define OTP1_DATA_BLOCK_2 BIT(2) /*!< erase/program protection of sector 2 */ +#define OTP1_DATA_BLOCK_3 BIT(3) /*!< erase/program protection of sector 3 */ +#define OTP1_DATA_BLOCK_4 BIT(4) /*!< erase/program protection of sector 4 */ +#define OTP1_DATA_BLOCK_5 BIT(5) /*!< erase/program protection of sector 5 */ +#define OTP1_DATA_BLOCK_6 BIT(6) /*!< erase/program protection of sector 6 */ +#define OTP1_DATA_BLOCK_7 BIT(7) /*!< erase/program protection of sector 7 */ +#define OTP1_DATA_BLOCK_8 BIT(8) /*!< erase/program protection of sector 8 */ +#define OTP1_DATA_BLOCK_9 BIT(9) /*!< erase/program protection of sector 9 */ +#define OTP1_DATA_BLOCK_10 BIT(10) /*!< erase/program protection of sector 10 */ +#define OTP1_DATA_BLOCK_11 BIT(11) /*!< erase/program protection of sector 11 */ +#define OTP1_DATA_BLOCK_12 BIT(12) /*!< erase/program protection of sector 12 */ +#define OTP1_DATA_BLOCK_13 BIT(13) /*!< erase/program protection of sector 13 */ +#define OTP1_DATA_BLOCK_14 BIT(14) /*!< erase/program protection of sector 14 */ +#define OTP1_DATA_BLOCK_15 BIT(15) /*!< erase/program protection of sector 15 */ +#define OTP1_DATA_BLOCK_ALL BITS(0,15) /*!< ALL erase/program protection of sector */ + +/* constants definitions */ +/* fmc state */ +typedef enum { + FMC_READY = 0, /*!< the operation has been completed */ + FMC_BUSY, /*!< the operation is in progress */ + FMC_RDCERR, /*!< CBUS data read protection error */ + FMC_PGSERR, /*!< program sequence error */ + FMC_PGMERR, /*!< program size not match error */ + FMC_PGAERR, /*!< program alignment error */ + FMC_WPERR, /*!< erase/program protection error */ + FMC_OPERR, /*!< operation error */ + FMC_LDECCDET, /*!< two bits ECC error when load code from flash/OTP1/bootloader */ + FMC_TOERR /*!< timeout error */ +} fmc_state_enum; + +/* EFUSE state */ +typedef enum { + EFUSE_READY = 0U, /*!< EFUSE operation has been completed */ + EFUSE_BUSY, /*!< EFUSE operation is in progress */ + EFUSE_OBER, /*!< EFUSE overstep boundary error */ + EFUSE_TOERR /*!< EFUSE timeout error */ +} efuse_state_enum; + +/* function declarations */ +/* FMC main memory programming functions */ +/* unlock the main FMC operation */ +void fmc_unlock(void); +/* lock the main FMC operation */ +void fmc_lock(void); +/* FMC erase page */ +fmc_state_enum fmc_page_erase(uint32_t page_addr); +/* FMC erase sector */ +fmc_state_enum fmc_sector_erase(uint32_t fmc_sector); +/* FMC erase whole chip */ +fmc_state_enum fmc_mass_erase(void); +/* FMC erase whole bank0 */ +fmc_state_enum fmc_bank0_erase(void); +/* FMC erase whole bank1(include bank1_ex) */ +fmc_state_enum fmc_bank1_erase(void); +/* FMC program a double word at the corresponding address */ +fmc_state_enum fmc_doubleword_program(uint32_t address, uint64_t data); +/* FMC program a word at the corresponding address */ +fmc_state_enum fmc_word_program(uint32_t address, uint32_t data); +/* FMC program a half word at the corresponding address */ +fmc_state_enum fmc_halfword_program(uint32_t address, uint16_t data); +/* FMC program a byte at the corresponding address */ +fmc_state_enum fmc_byte_program(uint32_t address, uint8_t data); + +/* enable no waitinging time area load after system reset */ +void fmc_nwa_enable(void); +/* disable no waiting time area load after system reset */ +void fmc_nwa_disable(void); +/* set OTP1 data block not be read */ +void otp1_read_disable(uint32_t block); +/* enable read lock block protection for OTP2 */ +void otp2_rlock_enable(void); + +/* FMC option bytes programming functions */ +/* unlock the option byte operation */ +void ob_unlock(void); +/* lock the option byte operation */ +void ob_lock(void); +/* send option byte change command */ +void ob_start(void); +/* erase option byte */ +void ob_erase(void); +/* enable write protect */ +ErrStatus ob_write_protection_enable(uint64_t ob_wp); +/* disable write protect */ +ErrStatus ob_write_protection_disable(uint64_t ob_wp); +/* enable erase/program protection and CBUS read protection */ +void ob_drp_enable(uint64_t ob_drp); +/* disable all erase/program protection and CBUS read protection */ +void ob_drp_disable(void); +/* configure security protection level */ +void ob_security_protection_config(uint8_t ob_spc); +/* program the FMC user option byte */ +void ob_user_write(uint32_t ob_fwdgt, uint32_t ob_deepsleep, uint32_t ob_stdby); +/* program the option byte BOR threshold value */ +void ob_user_bor_threshold(uint32_t ob_bor_th); +/* configure the option byte boot bank value */ +void ob_boot_mode_config(uint32_t boot_mode); +/* configure FMC/SRAM ECC checking, only valid after power reset */ +void ob_ecc_config(uint32_t ecc_config); +/* select no waiting time area, only valid after power reset, only for 4MB dual bank series */ +void ob_nwa_select(uint32_t nwa_select); +/* get the FMC user option byte */ +uint8_t ob_user_get(void); +/* get the FMC option byte write protection of bank0 */ +uint32_t ob_write_protection0_get(void); +/* get the FMC option byte write protection of bank1 */ +uint32_t ob_write_protection1_get(void); +/* get the FMC erase/program protection and CBUS read protection option bytes value of bank0 */ +uint32_t ob_drp0_get(void); +/* get the FMC erase/program protection and CBUS read protection option bytes value of bank1 */ +uint32_t ob_drp1_get(void); +/* get option byte security protection code value */ +FlagStatus ob_spc_get(void); +/* get the FMC option byte BOR threshold value */ +uint32_t ob_user_bor_threshold_get(void); +/* get the boot mode */ +uint32_t ob_boot_mode_get(void); +/* get FMC/SRAM ECC checking */ +uint32_t ob_ecc_get(void); +/* get no waiting time area */ +uint32_t ob_nwa_get(void); + +/* FMC interrupts and flags management functions */ +/* get flag set or reset */ +FlagStatus fmc_flag_get(uint32_t fmc_flag); +/* clear the FMC pending flag */ +void fmc_flag_clear(uint32_t fmc_flag); +/* enable FMC interrupt */ +void fmc_interrupt_enable(uint32_t fmc_int); +/* disable FMC interrupt */ +void fmc_interrupt_disable(uint32_t fmc_int); +/* get FMC interrupt flag set or reset */ +FlagStatus fmc_interrupt_flag_get(uint32_t fmc_int_flag); +/* clear the FMC interrupt flag */ +void fmc_interrupt_flag_clear(uint32_t fmc_int_flag); +/* get the FMC state */ +fmc_state_enum fmc_state_get(void); +/* check whether FMC is ready or not */ +fmc_state_enum fmc_ready_wait(uint32_t timeout); + +/* EFUSE operation functions */ +/* unlock the EFUSE_CTL register */ +void efuse_ctrl_unlock(void); +/* lock the EFUSE_CTL register */ +void efuse_ctrl_lock(void); +/* unlock the EFUSE_USER_DATA register */ +void efuse_user_data_unlock(void); +/* lock the EFUSE_USER_DATA register */ +void efuse_user_data_lock(void); +/* read EFUSE value */ +efuse_state_enum efuse_read(uint32_t ef_addr, uint32_t size, uint32_t buf[]); +/* write EFUSE */ +efuse_state_enum efuse_write(uint32_t ef_addr, uint32_t size, uint8_t ef_data); +/* write efuse control parameter */ +efuse_state_enum efuse_control_write(uint8_t ef_data); +/* write user data parameter */ +efuse_state_enum efuse_user_data_write(uint8_t ef_data); + +/* flag and interrupt functions */ +/* check EFUSE flag is set or not */ +FlagStatus efuse_flag_get(uint32_t efuse_flag); +/* clear EFUSE pending flag */ +void efuse_flag_clear(uint32_t efuse_cflag); +/* enable EFUSE interrupt */ +void efuse_interrupt_enable(uint32_t source); +/* disable EFUSE interrupt */ +void efuse_interrupt_disable(uint32_t source); +/* check EFUSE interrupt flag is set or not */ +FlagStatus efuse_interrupt_flag_get(uint32_t int_flag); +/* clear EFUSE pending interrupt flag */ +void efuse_interrupt_flag_clear(uint32_t int_cflag); +/* check EFUSE operation ready or not */ +efuse_state_enum efuse_ready_wait(uint32_t efuse_flag, uint32_t timeout); + +#endif /* GD32F5XX_FMC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_fwdgt.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_fwdgt.h new file mode 100644 index 0000000..f73e24f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_fwdgt.h @@ -0,0 +1,118 @@ +/*! + \file gd32f5xx_fwdgt.h + \brief definitions for the FWDGT + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_FWDGT_H +#define GD32F5XX_FWDGT_H + +#include "gd32f5xx.h" + +/* FWDGT definitions */ +#define FWDGT FWDGT_BASE /*!< FWDGT base address */ + +/* registers definitions */ +#define FWDGT_CTL REG32((FWDGT) + 0x00U) /*!< FWDGT control register */ +#define FWDGT_PSC REG32((FWDGT) + 0x04U) /*!< FWDGT prescaler register */ +#define FWDGT_RLD REG32((FWDGT) + 0x08U) /*!< FWDGT reload register */ +#define FWDGT_STAT REG32((FWDGT) + 0x0CU) /*!< FWDGT status register */ + +/* bits definitions */ +/* FWDGT_CTL */ +#define FWDGT_CTL_CMD BITS(0,15) /*!< FWDGT command value */ + +/* FWDGT_PSC */ +#define FWDGT_PSC_PSC BITS(0,3) /*!< FWDGT prescaler divider value */ + +/* FWDGT_RLD */ +#define FWDGT_RLD_RLD BITS(0,11) /*!< FWDGT counter reload value */ + +/* FWDGT_STAT */ +#define FWDGT_STAT_PUD BIT(0) /*!< FWDGT prescaler divider value update */ +#define FWDGT_STAT_RUD BIT(1) /*!< FWDGT counter reload value update */ + +/* constants definitions */ +/* psc register value */ +#define PSC_PSC(regval) (BITS(0,3) & ((uint32_t)(regval) << 0)) +#define FWDGT_PSC_DIV4 ((uint8_t)PSC_PSC(0)) /*!< FWDGT prescaler set to 4 */ +#define FWDGT_PSC_DIV8 ((uint8_t)PSC_PSC(1)) /*!< FWDGT prescaler set to 8 */ +#define FWDGT_PSC_DIV16 ((uint8_t)PSC_PSC(2)) /*!< FWDGT prescaler set to 16 */ +#define FWDGT_PSC_DIV32 ((uint8_t)PSC_PSC(3)) /*!< FWDGT prescaler set to 32 */ +#define FWDGT_PSC_DIV64 ((uint8_t)PSC_PSC(4)) /*!< FWDGT prescaler set to 64 */ +#define FWDGT_PSC_DIV128 ((uint8_t)PSC_PSC(5)) /*!< FWDGT prescaler set to 128 */ +#define FWDGT_PSC_DIV256 ((uint8_t)PSC_PSC(6)) /*!< FWDGT prescaler set to 256 */ +#define FWDGT_PSC_DIV512 ((uint8_t)PSC_PSC(7)) /*!< FWDGT prescaler set to 512 */ +#define FWDGT_PSC_DIV1024 ((uint8_t)PSC_PSC(8)) /*!< FWDGT prescaler set to 1024 */ +#define FWDGT_PSC_DIV2048 ((uint8_t)PSC_PSC(9)) /*!< FWDGT prescaler set to 2048 */ +#define FWDGT_PSC_DIV4096 ((uint8_t)PSC_PSC(10)) /*!< FWDGT prescaler set to 4096 */ +#define FWDGT_PSC_DIV8192 ((uint8_t)PSC_PSC(11)) /*!< FWDGT prescaler set to 8192 */ +#define FWDGT_PSC_DIV16384 ((uint8_t)PSC_PSC(12)) /*!< FWDGT prescaler set to 16384 */ +#define FWDGT_PSC_DIV32768 ((uint8_t)PSC_PSC(13)) /*!< FWDGT prescaler set to 32768 */ + +/* control value */ +#define FWDGT_WRITEACCESS_ENABLE ((uint16_t)0x5555U) /*!< FWDGT_CTL bits write access enable value */ +#define FWDGT_WRITEACCESS_DISABLE ((uint16_t)0x0000U) /*!< FWDGT_CTL bits write access disable value */ +#define FWDGT_KEY_RELOAD ((uint16_t)0xAAAAU) /*!< FWDGT_CTL bits fwdgt counter reload value */ +#define FWDGT_KEY_ENABLE ((uint16_t)0xCCCCU) /*!< FWDGT_CTL bits fwdgt counter enable value */ + +/* FWDGT timeout value */ +#define FWDGT_PSC_TIMEOUT ((uint32_t)0x000FFFFFU) /*!< FWDGT_PSC register write operation state flag timeout */ +#define FWDGT_RLD_TIMEOUT ((uint32_t)0x000FFFFFU) /*!< FWDGT_RLD register write operation state flag timeout */ + +/* FWDGT flag definitions */ +#define FWDGT_FLAG_PUD FWDGT_STAT_PUD /*!< FWDGT prescaler divider value update flag */ +#define FWDGT_FLAG_RUD FWDGT_STAT_RUD /*!< FWDGT counter reload value update flag */ + +/* write value to FWDGT_RLD_RLD bit field */ +#define RLD_RLD(regval) (BITS(0,11) & ((uint32_t)(regval) << 0)) + +/* function declarations */ +/* enable write access to FWDGT_PSC and FWDGT_RLD */ +void fwdgt_write_enable(void); +/* disable write access to FWDGT_PSC and FWDGT_RLD */ +void fwdgt_write_disable(void); +/* start the free watchdog timer counter */ +void fwdgt_enable(void); + +/* configure the free watchdog timer counter prescaler value */ +ErrStatus fwdgt_prescaler_value_config(uint16_t prescaler_value); +/* configure the free watchdog timer counter reload value */ +ErrStatus fwdgt_reload_value_config(uint16_t reload_value); +/* reload the counter of FWDGT */ +void fwdgt_counter_reload(void); +/* configure counter reload value, and prescaler divider value */ +ErrStatus fwdgt_config(uint16_t reload_value, uint8_t prescaler_div); + +/* get flag state of FWDGT */ +FlagStatus fwdgt_flag_get(uint16_t flag); + +#endif /* GD32F5XX_FWDGT_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_gpio.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_gpio.h new file mode 100644 index 0000000..fb11b98 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_gpio.h @@ -0,0 +1,406 @@ +/*! + \file gd32f5xx_gpio.h + \brief definitions for the GPIO + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_GPIO_H +#define GD32F5XX_GPIO_H + +#include "gd32f5xx.h" + +/* GPIOx(x=A,B,C,D,E,F,G,H,I) definitions */ +#define GPIOA (GPIO_BASE + 0x00000000U) /*!< GPIOA base address */ +#define GPIOB (GPIO_BASE + 0x00000400U) /*!< GPIOB base address */ +#define GPIOC (GPIO_BASE + 0x00000800U) /*!< GPIOC base address */ +#define GPIOD (GPIO_BASE + 0x00000C00U) /*!< GPIOD base address */ +#define GPIOE (GPIO_BASE + 0x00001000U) /*!< GPIOE base address */ +#define GPIOF (GPIO_BASE + 0x00001400U) /*!< GPIOF base address */ +#define GPIOG (GPIO_BASE + 0x00001800U) /*!< GPIOG base address */ +#define GPIOH (GPIO_BASE + 0x00001C00U) /*!< GPIOH base address */ +#define GPIOI (GPIO_BASE + 0x00002000U) /*!< GPIOI base address */ + +/* registers definitions */ +#define GPIO_CTL(gpiox) REG32((gpiox) + 0x00U) /*!< GPIO port control register */ +#define GPIO_OMODE(gpiox) REG32((gpiox) + 0x04U) /*!< GPIO port output mode register */ +#define GPIO_OSPD(gpiox) REG32((gpiox) + 0x08U) /*!< GPIO port output speed register */ +#define GPIO_PUD(gpiox) REG32((gpiox) + 0x0CU) /*!< GPIO port pull-up/pull-down register */ +#define GPIO_ISTAT(gpiox) REG32((gpiox) + 0x10U) /*!< GPIO port input status register */ +#define GPIO_OCTL(gpiox) REG32((gpiox) + 0x14U) /*!< GPIO port output control register */ +#define GPIO_BOP(gpiox) REG32((gpiox) + 0x18U) /*!< GPIO port bit operate register */ +#define GPIO_LOCK(gpiox) REG32((gpiox) + 0x1CU) /*!< GPIO port configuration lock register */ +#define GPIO_AFSEL0(gpiox) REG32((gpiox) + 0x20U) /*!< GPIO alternate function selected register 0 */ +#define GPIO_AFSEL1(gpiox) REG32((gpiox) + 0x24U) /*!< GPIO alternate function selected register 1 */ +#define GPIO_BC(gpiox) REG32((gpiox) + 0x28U) /*!< GPIO bit clear register */ +#define GPIO_TG(gpiox) REG32((gpiox) + 0x2CU) /*!< GPIO port bit toggle register */ + +/* bits definitions */ +/* GPIO_CTL */ +#define GPIO_CTL_CTL0 BITS(0,1) /*!< pin 0 configuration bits */ +#define GPIO_CTL_CTL1 BITS(2,3) /*!< pin 1 configuration bits */ +#define GPIO_CTL_CTL2 BITS(4,5) /*!< pin 2 configuration bits */ +#define GPIO_CTL_CTL3 BITS(6,7) /*!< pin 3 configuration bits */ +#define GPIO_CTL_CTL4 BITS(8,9) /*!< pin 4 configuration bits */ +#define GPIO_CTL_CTL5 BITS(10,11) /*!< pin 5 configuration bits */ +#define GPIO_CTL_CTL6 BITS(12,13) /*!< pin 6 configuration bits */ +#define GPIO_CTL_CTL7 BITS(14,15) /*!< pin 7 configuration bits */ +#define GPIO_CTL_CTL8 BITS(16,17) /*!< pin 8 configuration bits */ +#define GPIO_CTL_CTL9 BITS(18,19) /*!< pin 9 configuration bits */ +#define GPIO_CTL_CTL10 BITS(20,21) /*!< pin 10 configuration bits */ +#define GPIO_CTL_CTL11 BITS(22,23) /*!< pin 11 configuration bits */ +#define GPIO_CTL_CTL12 BITS(24,25) /*!< pin 12 configuration bits */ +#define GPIO_CTL_CTL13 BITS(26,27) /*!< pin 13 configuration bits */ +#define GPIO_CTL_CTL14 BITS(28,29) /*!< pin 14 configuration bits */ +#define GPIO_CTL_CTL15 BITS(30,31) /*!< pin 15 configuration bits */ + +/* GPIO_OMODE */ +#define GPIO_OMODE_OM0 BIT(0) /*!< pin 0 output mode bit */ +#define GPIO_OMODE_OM1 BIT(1) /*!< pin 1 output mode bit */ +#define GPIO_OMODE_OM2 BIT(2) /*!< pin 2 output mode bit */ +#define GPIO_OMODE_OM3 BIT(3) /*!< pin 3 output mode bit */ +#define GPIO_OMODE_OM4 BIT(4) /*!< pin 4 output mode bit */ +#define GPIO_OMODE_OM5 BIT(5) /*!< pin 5 output mode bit */ +#define GPIO_OMODE_OM6 BIT(6) /*!< pin 6 output mode bit */ +#define GPIO_OMODE_OM7 BIT(7) /*!< pin 7 output mode bit */ +#define GPIO_OMODE_OM8 BIT(8) /*!< pin 8 output mode bit */ +#define GPIO_OMODE_OM9 BIT(9) /*!< pin 9 output mode bit */ +#define GPIO_OMODE_OM10 BIT(10) /*!< pin 10 output mode bit */ +#define GPIO_OMODE_OM11 BIT(11) /*!< pin 11 output mode bit */ +#define GPIO_OMODE_OM12 BIT(12) /*!< pin 12 output mode bit */ +#define GPIO_OMODE_OM13 BIT(13) /*!< pin 13 output mode bit */ +#define GPIO_OMODE_OM14 BIT(14) /*!< pin 14 output mode bit */ +#define GPIO_OMODE_OM15 BIT(15) /*!< pin 15 output mode bit */ + +/* GPIO_OSPD */ +#define GPIO_OSPD_OSPD0 BITS(0,1) /*!< pin 0 output max speed bits */ +#define GPIO_OSPD_OSPD1 BITS(2,3) /*!< pin 1 output max speed bits */ +#define GPIO_OSPD_OSPD2 BITS(4,5) /*!< pin 2 output max speed bits */ +#define GPIO_OSPD_OSPD3 BITS(6,7) /*!< pin 3 output max speed bits */ +#define GPIO_OSPD_OSPD4 BITS(8,9) /*!< pin 4 output max speed bits */ +#define GPIO_OSPD_OSPD5 BITS(10,11) /*!< pin 5 output max speed bits */ +#define GPIO_OSPD_OSPD6 BITS(12,13) /*!< pin 6 output max speed bits */ +#define GPIO_OSPD_OSPD7 BITS(14,15) /*!< pin 7 output max speed bits */ +#define GPIO_OSPD_OSPD8 BITS(16,17) /*!< pin 8 output max speed bits */ +#define GPIO_OSPD_OSPD9 BITS(18,19) /*!< pin 9 output max speed bits */ +#define GPIO_OSPD_OSPD10 BITS(20,21) /*!< pin 10 output max speed bits */ +#define GPIO_OSPD_OSPD11 BITS(22,23) /*!< pin 11 output max speed bits */ +#define GPIO_OSPD_OSPD12 BITS(24,25) /*!< pin 12 output max speed bits */ +#define GPIO_OSPD_OSPD13 BITS(26,27) /*!< pin 13 output max speed bits */ +#define GPIO_OSPD_OSPD14 BITS(28,29) /*!< pin 14 output max speed bits */ +#define GPIO_OSPD_OSPD15 BITS(30,31) /*!< pin 15 output max speed bits */ + +/* GPIO_PUD */ +#define GPIO_PUD_PUD0 BITS(0,1) /*!< pin 0 pull-up or pull-down bits */ +#define GPIO_PUD_PUD1 BITS(2,3) /*!< pin 1 pull-up or pull-down bits */ +#define GPIO_PUD_PUD2 BITS(4,5) /*!< pin 2 pull-up or pull-down bits */ +#define GPIO_PUD_PUD3 BITS(6,7) /*!< pin 3 pull-up or pull-down bits */ +#define GPIO_PUD_PUD4 BITS(8,9) /*!< pin 4 pull-up or pull-down bits */ +#define GPIO_PUD_PUD5 BITS(10,11) /*!< pin 5 pull-up or pull-down bits */ +#define GPIO_PUD_PUD6 BITS(12,13) /*!< pin 6 pull-up or pull-down bits */ +#define GPIO_PUD_PUD7 BITS(14,15) /*!< pin 7 pull-up or pull-down bits */ +#define GPIO_PUD_PUD8 BITS(16,17) /*!< pin 8 pull-up or pull-down bits */ +#define GPIO_PUD_PUD9 BITS(18,19) /*!< pin 9 pull-up or pull-down bits */ +#define GPIO_PUD_PUD10 BITS(20,21) /*!< pin 10 pull-up or pull-down bits */ +#define GPIO_PUD_PUD11 BITS(22,23) /*!< pin 11 pull-up or pull-down bits */ +#define GPIO_PUD_PUD12 BITS(24,25) /*!< pin 12 pull-up or pull-down bits */ +#define GPIO_PUD_PUD13 BITS(26,27) /*!< pin 13 pull-up or pull-down bits */ +#define GPIO_PUD_PUD14 BITS(28,29) /*!< pin 14 pull-up or pull-down bits */ +#define GPIO_PUD_PUD15 BITS(30,31) /*!< pin 15 pull-up or pull-down bits */ + +/* GPIO_ISTAT */ +#define GPIO_ISTAT_ISTAT0 BIT(0) /*!< pin 0 input status */ +#define GPIO_ISTAT_ISTAT1 BIT(1) /*!< pin 1 input status */ +#define GPIO_ISTAT_ISTAT2 BIT(2) /*!< pin 2 input status */ +#define GPIO_ISTAT_ISTAT3 BIT(3) /*!< pin 3 input status */ +#define GPIO_ISTAT_ISTAT4 BIT(4) /*!< pin 4 input status */ +#define GPIO_ISTAT_ISTAT5 BIT(5) /*!< pin 5 input status */ +#define GPIO_ISTAT_ISTAT6 BIT(6) /*!< pin 6 input status */ +#define GPIO_ISTAT_ISTAT7 BIT(7) /*!< pin 7 input status */ +#define GPIO_ISTAT_ISTAT8 BIT(8) /*!< pin 8 input status */ +#define GPIO_ISTAT_ISTAT9 BIT(9) /*!< pin 9 input status */ +#define GPIO_ISTAT_ISTAT10 BIT(10) /*!< pin 10 input status */ +#define GPIO_ISTAT_ISTAT11 BIT(11) /*!< pin 11 input status */ +#define GPIO_ISTAT_ISTAT12 BIT(12) /*!< pin 12 input status */ +#define GPIO_ISTAT_ISTAT13 BIT(13) /*!< pin 13 input status */ +#define GPIO_ISTAT_ISTAT14 BIT(14) /*!< pin 14 input status */ +#define GPIO_ISTAT_ISTAT15 BIT(15) /*!< pin 15 input status */ + +/* GPIO_OCTL */ +#define GPIO_OCTL_OCTL0 BIT(0) /*!< pin 0 output control bit */ +#define GPIO_OCTL_OCTL1 BIT(1) /*!< pin 1 output control bit */ +#define GPIO_OCTL_OCTL2 BIT(2) /*!< pin 2 output control bit */ +#define GPIO_OCTL_OCTL3 BIT(3) /*!< pin 3 output control bit */ +#define GPIO_OCTL_OCTL4 BIT(4) /*!< pin 4 output control bit */ +#define GPIO_OCTL_OCTL5 BIT(5) /*!< pin 5 output control bit */ +#define GPIO_OCTL_OCTL6 BIT(6) /*!< pin 6 output control bit */ +#define GPIO_OCTL_OCTL7 BIT(7) /*!< pin 7 output control bit */ +#define GPIO_OCTL_OCTL8 BIT(8) /*!< pin 8 output control bit */ +#define GPIO_OCTL_OCTL9 BIT(9) /*!< pin 9 output control bit */ +#define GPIO_OCTL_OCTL10 BIT(10) /*!< pin 10 output control bit */ +#define GPIO_OCTL_OCTL11 BIT(11) /*!< pin 11 output control bit */ +#define GPIO_OCTL_OCTL12 BIT(12) /*!< pin 12 output control bit */ +#define GPIO_OCTL_OCTL13 BIT(13) /*!< pin 13 output control bit */ +#define GPIO_OCTL_OCTL14 BIT(14) /*!< pin 14 output control bit */ +#define GPIO_OCTL_OCTL15 BIT(15) /*!< pin 15 output control bit */ + +/* GPIO_BOP */ +#define GPIO_BOP_BOP0 BIT(0) /*!< pin 0 set bit */ +#define GPIO_BOP_BOP1 BIT(1) /*!< pin 1 set bit */ +#define GPIO_BOP_BOP2 BIT(2) /*!< pin 2 set bit */ +#define GPIO_BOP_BOP3 BIT(3) /*!< pin 3 set bit */ +#define GPIO_BOP_BOP4 BIT(4) /*!< pin 4 set bit */ +#define GPIO_BOP_BOP5 BIT(5) /*!< pin 5 set bit */ +#define GPIO_BOP_BOP6 BIT(6) /*!< pin 6 set bit */ +#define GPIO_BOP_BOP7 BIT(7) /*!< pin 7 set bit */ +#define GPIO_BOP_BOP8 BIT(8) /*!< pin 8 set bit */ +#define GPIO_BOP_BOP9 BIT(9) /*!< pin 9 set bit */ +#define GPIO_BOP_BOP10 BIT(10) /*!< pin 10 set bit */ +#define GPIO_BOP_BOP11 BIT(11) /*!< pin 11 set bit */ +#define GPIO_BOP_BOP12 BIT(12) /*!< pin 12 set bit */ +#define GPIO_BOP_BOP13 BIT(13) /*!< pin 13 set bit */ +#define GPIO_BOP_BOP14 BIT(14) /*!< pin 14 set bit */ +#define GPIO_BOP_BOP15 BIT(15) /*!< pin 15 set bit */ +#define GPIO_BOP_CR0 BIT(16) /*!< pin 0 clear bit */ +#define GPIO_BOP_CR1 BIT(17) /*!< pin 1 clear bit */ +#define GPIO_BOP_CR2 BIT(18) /*!< pin 2 clear bit */ +#define GPIO_BOP_CR3 BIT(19) /*!< pin 3 clear bit */ +#define GPIO_BOP_CR4 BIT(20) /*!< pin 4 clear bit */ +#define GPIO_BOP_CR5 BIT(21) /*!< pin 5 clear bit */ +#define GPIO_BOP_CR6 BIT(22) /*!< pin 6 clear bit */ +#define GPIO_BOP_CR7 BIT(23) /*!< pin 7 clear bit */ +#define GPIO_BOP_CR8 BIT(24) /*!< pin 8 clear bit */ +#define GPIO_BOP_CR9 BIT(25) /*!< pin 9 clear bit */ +#define GPIO_BOP_CR10 BIT(26) /*!< pin 10 clear bit */ +#define GPIO_BOP_CR11 BIT(27) /*!< pin 11 clear bit */ +#define GPIO_BOP_CR12 BIT(28) /*!< pin 12 clear bit */ +#define GPIO_BOP_CR13 BIT(29) /*!< pin 13 clear bit */ +#define GPIO_BOP_CR14 BIT(30) /*!< pin 14 clear bit */ +#define GPIO_BOP_CR15 BIT(31) /*!< pin 15 clear bit */ + +/* GPIO_LOCK */ +#define GPIO_LOCK_LK0 BIT(0) /*!< pin 0 lock bit */ +#define GPIO_LOCK_LK1 BIT(1) /*!< pin 1 lock bit */ +#define GPIO_LOCK_LK2 BIT(2) /*!< pin 2 lock bit */ +#define GPIO_LOCK_LK3 BIT(3) /*!< pin 3 lock bit */ +#define GPIO_LOCK_LK4 BIT(4) /*!< pin 4 lock bit */ +#define GPIO_LOCK_LK5 BIT(5) /*!< pin 5 lock bit */ +#define GPIO_LOCK_LK6 BIT(6) /*!< pin 6 lock bit */ +#define GPIO_LOCK_LK7 BIT(7) /*!< pin 7 lock bit */ +#define GPIO_LOCK_LK8 BIT(8) /*!< pin 8 lock bit */ +#define GPIO_LOCK_LK9 BIT(9) /*!< pin 9 lock bit */ +#define GPIO_LOCK_LK10 BIT(10) /*!< pin 10 lock bit */ +#define GPIO_LOCK_LK11 BIT(11) /*!< pin 11 lock bit */ +#define GPIO_LOCK_LK12 BIT(12) /*!< pin 12 lock bit */ +#define GPIO_LOCK_LK13 BIT(13) /*!< pin 13 lock bit */ +#define GPIO_LOCK_LK14 BIT(14) /*!< pin 14 lock bit */ +#define GPIO_LOCK_LK15 BIT(15) /*!< pin 15 lock bit */ +#define GPIO_LOCK_LKK BIT(16) /*!< pin lock sequence key */ + +/* GPIO_AFSEL0 */ +#define GPIO_AFSEL0_SEL0 BITS(0,3) /*!< pin 0 alternate function selected */ +#define GPIO_AFSEL0_SEL1 BITS(4,7) /*!< pin 1 alternate function selected */ +#define GPIO_AFSEL0_SEL2 BITS(8,11) /*!< pin 2 alternate function selected */ +#define GPIO_AFSEL0_SEL3 BITS(12,15) /*!< pin 3 alternate function selected */ +#define GPIO_AFSEL0_SEL4 BITS(16,19) /*!< pin 4 alternate function selected */ +#define GPIO_AFSEL0_SEL5 BITS(20,23) /*!< pin 5 alternate function selected */ +#define GPIO_AFSEL0_SEL6 BITS(24,27) /*!< pin 6 alternate function selected */ +#define GPIO_AFSEL0_SEL7 BITS(28,31) /*!< pin 7 alternate function selected */ + +/* GPIO_AFSEL1 */ +#define GPIO_AFSEL1_SEL8 BITS(0,3) /*!< pin 8 alternate function selected */ +#define GPIO_AFSEL1_SEL9 BITS(4,7) /*!< pin 9 alternate function selected */ +#define GPIO_AFSEL1_SEL10 BITS(8,11) /*!< pin 10 alternate function selected */ +#define GPIO_AFSEL1_SEL11 BITS(12,15) /*!< pin 11 alternate function selected */ +#define GPIO_AFSEL1_SEL12 BITS(16,19) /*!< pin 12 alternate function selected */ +#define GPIO_AFSEL1_SEL13 BITS(20,23) /*!< pin 13 alternate function selected */ +#define GPIO_AFSEL1_SEL14 BITS(24,27) /*!< pin 14 alternate function selected */ +#define GPIO_AFSEL1_SEL15 BITS(28,31) /*!< pin 15 alternate function selected */ + +/* GPIO_BC */ +#define GPIO_BC_CR0 BIT(0) /*!< pin 0 clear bit */ +#define GPIO_BC_CR1 BIT(1) /*!< pin 1 clear bit */ +#define GPIO_BC_CR2 BIT(2) /*!< pin 2 clear bit */ +#define GPIO_BC_CR3 BIT(3) /*!< pin 3 clear bit */ +#define GPIO_BC_CR4 BIT(4) /*!< pin 4 clear bit */ +#define GPIO_BC_CR5 BIT(5) /*!< pin 5 clear bit */ +#define GPIO_BC_CR6 BIT(6) /*!< pin 6 clear bit */ +#define GPIO_BC_CR7 BIT(7) /*!< pin 7 clear bit */ +#define GPIO_BC_CR8 BIT(8) /*!< pin 8 clear bit */ +#define GPIO_BC_CR9 BIT(9) /*!< pin 9 clear bit */ +#define GPIO_BC_CR10 BIT(10) /*!< pin 10 clear bit */ +#define GPIO_BC_CR11 BIT(11) /*!< pin 11 clear bit */ +#define GPIO_BC_CR12 BIT(12) /*!< pin 12 clear bit */ +#define GPIO_BC_CR13 BIT(13) /*!< pin 13 clear bit */ +#define GPIO_BC_CR14 BIT(14) /*!< pin 14 clear bit */ +#define GPIO_BC_CR15 BIT(15) /*!< pin 15 clear bit */ + +/* GPIO_TG */ +#define GPIO_TG_TG0 BIT(0) /*!< pin 0 toggle bit */ +#define GPIO_TG_TG1 BIT(1) /*!< pin 1 toggle bit */ +#define GPIO_TG_TG2 BIT(2) /*!< pin 2 toggle bit */ +#define GPIO_TG_TG3 BIT(3) /*!< pin 3 toggle bit */ +#define GPIO_TG_TG4 BIT(4) /*!< pin 4 toggle bit */ +#define GPIO_TG_TG5 BIT(5) /*!< pin 5 toggle bit */ +#define GPIO_TG_TG6 BIT(6) /*!< pin 6 toggle bit */ +#define GPIO_TG_TG7 BIT(7) /*!< pin 7 toggle bit */ +#define GPIO_TG_TG8 BIT(8) /*!< pin 8 toggle bit */ +#define GPIO_TG_TG9 BIT(9) /*!< pin 9 toggle bit */ +#define GPIO_TG_TG10 BIT(10) /*!< pin 10 toggle bit */ +#define GPIO_TG_TG11 BIT(11) /*!< pin 11 toggle bit */ +#define GPIO_TG_TG12 BIT(12) /*!< pin 12 toggle bit */ +#define GPIO_TG_TG13 BIT(13) /*!< pin 13 toggle bit */ +#define GPIO_TG_TG14 BIT(14) /*!< pin 14 toggle bit */ +#define GPIO_TG_TG15 BIT(15) /*!< pin 15 toggle bit */ + +/* constants definitions */ +typedef FlagStatus bit_status; + +/* output mode definitions */ +#define CTL_CLTR(regval) (BITS(0,1) & ((uint32_t)(regval) << 0)) +#define GPIO_MODE_INPUT CTL_CLTR(0) /*!< input mode */ +#define GPIO_MODE_OUTPUT CTL_CLTR(1) /*!< output mode */ +#define GPIO_MODE_AF CTL_CLTR(2) /*!< alternate function mode */ +#define GPIO_MODE_ANALOG CTL_CLTR(3) /*!< analog mode */ + +/* pull-up/ pull-down definitions */ +#define PUD_PUPD(regval) (BITS(0,1) & ((uint32_t)(regval) << 0)) +#define GPIO_PUPD_NONE PUD_PUPD(0) /*!< floating mode, no pull-up and pull-down resistors */ +#define GPIO_PUPD_PULLUP PUD_PUPD(1) /*!< with pull-up resistor */ +#define GPIO_PUPD_PULLDOWN PUD_PUPD(2) /*!< with pull-down resistor */ + +/* GPIO pin definitions */ +#define GPIO_PIN_0 BIT(0) /*!< GPIO pin 0 */ +#define GPIO_PIN_1 BIT(1) /*!< GPIO pin 1 */ +#define GPIO_PIN_2 BIT(2) /*!< GPIO pin 2 */ +#define GPIO_PIN_3 BIT(3) /*!< GPIO pin 3 */ +#define GPIO_PIN_4 BIT(4) /*!< GPIO pin 4 */ +#define GPIO_PIN_5 BIT(5) /*!< GPIO pin 5 */ +#define GPIO_PIN_6 BIT(6) /*!< GPIO pin 6 */ +#define GPIO_PIN_7 BIT(7) /*!< GPIO pin 7 */ +#define GPIO_PIN_8 BIT(8) /*!< GPIO pin 8 */ +#define GPIO_PIN_9 BIT(9) /*!< GPIO pin 9 */ +#define GPIO_PIN_10 BIT(10) /*!< GPIO pin 10 */ +#define GPIO_PIN_11 BIT(11) /*!< GPIO pin 11 */ +#define GPIO_PIN_12 BIT(12) /*!< GPIO pin 12 */ +#define GPIO_PIN_13 BIT(13) /*!< GPIO pin 13 */ +#define GPIO_PIN_14 BIT(14) /*!< GPIO pin 14 */ +#define GPIO_PIN_15 BIT(15) /*!< GPIO pin 15 */ +#define GPIO_PIN_ALL BITS(0,15) /*!< GPIO pin all */ + +/* GPIO mode configuration values */ +#define GPIO_MODE_SET(n, mode) ((uint32_t)((uint32_t)(mode) << (2U * (n)))) +#define GPIO_MODE_MASK(n) (0x3U << (2U * (n))) + +/* GPIO pull-up/ pull-down values */ +#define GPIO_PUPD_SET(n, pupd) ((uint32_t)((uint32_t)(pupd) << (2U * (n)))) +#define GPIO_PUPD_MASK(n) (0x3U << (2U * (n))) + +/* GPIO output speed values */ +#define GPIO_OSPEED_SET(n, speed) ((uint32_t)((uint32_t)(speed) << (2U * (n)))) +#define GPIO_OSPEED_MASK(n) (0x3U << (2U * (n))) + +/* GPIO output type */ +#define GPIO_OTYPE_PP ((uint8_t)(0x00U)) /*!< push pull mode */ +#define GPIO_OTYPE_OD ((uint8_t)(0x01U)) /*!< open drain mode */ + +/* GPIO output max speed level */ +#define OSPD_OSPD(regval) (BITS(0,1) & ((uint32_t)(regval) << 0)) +#define GPIO_OSPEED_LEVEL0 OSPD_OSPD(0) /*!< output max speed level 0 */ +#define GPIO_OSPEED_LEVEL1 OSPD_OSPD(1) /*!< output max speed level 1 */ +#define GPIO_OSPEED_LEVEL2 OSPD_OSPD(2) /*!< output max speed level 2 */ +#define GPIO_OSPEED_LEVEL3 OSPD_OSPD(3) /*!< output max speed level 3 */ + +/* GPIO output max speed value */ +#define GPIO_OSPEED_2MHZ GPIO_OSPEED_LEVEL0 /*!< output max speed 2MHz */ +#define GPIO_OSPEED_10MHZ GPIO_OSPEED_LEVEL1 /*!< output max speed 10MHz */ +#define GPIO_OSPEED_50MHZ GPIO_OSPEED_LEVEL2 /*!< output max speed 50MHz */ +#define GPIO_OSPEED_MAX GPIO_OSPEED_LEVEL3 /*!< GPIO very high output speed, max speed more than 50MHz */ + +/* GPIO alternate function values */ +#define GPIO_AFR_SET(n, af) ((uint32_t)((uint32_t)(af) << (4U * (n)))) +#define GPIO_AFR_MASK(n) (0xFU << (4U * (n))) + +/* GPIO alternate function */ +#define AF(regval) (BITS(0,3) & ((uint32_t)(regval) << 0)) +#define GPIO_AF_0 AF(0) /*!< alternate function 0 selected */ +#define GPIO_AF_1 AF(1) /*!< alternate function 1 selected */ +#define GPIO_AF_2 AF(2) /*!< alternate function 2 selected */ +#define GPIO_AF_3 AF(3) /*!< alternate function 3 selected */ +#define GPIO_AF_4 AF(4) /*!< alternate function 4 selected */ +#define GPIO_AF_5 AF(5) /*!< alternate function 5 selected */ +#define GPIO_AF_6 AF(6) /*!< alternate function 6 selected */ +#define GPIO_AF_7 AF(7) /*!< alternate function 7 selected */ +#define GPIO_AF_8 AF(8) /*!< alternate function 8 selected */ +#define GPIO_AF_9 AF(9) /*!< alternate function 9 selected */ +#define GPIO_AF_10 AF(10) /*!< alternate function 10 selected */ +#define GPIO_AF_11 AF(11) /*!< alternate function 11 selected */ +#define GPIO_AF_12 AF(12) /*!< alternate function 12 selected */ +#define GPIO_AF_13 AF(13) /*!< alternate function 13 selected */ +#define GPIO_AF_14 AF(14) /*!< alternate function 14 selected */ +#define GPIO_AF_15 AF(15) /*!< alternate function 15 selected */ + +/* function declarations */ +/* reset GPIO port */ +void gpio_deinit(uint32_t gpio_periph); +/* set GPIO mode */ +void gpio_mode_set(uint32_t gpio_periph, uint32_t mode, uint32_t pull_up_down, uint32_t pin); +/* set GPIO output type and speed */ +void gpio_output_options_set(uint32_t gpio_periph, uint8_t otype, uint32_t speed, uint32_t pin); + +/* set GPIO pin bit */ +void gpio_bit_set(uint32_t gpio_periph, uint32_t pin); +/* reset GPIO pin bit */ +void gpio_bit_reset(uint32_t gpio_periph, uint32_t pin); +/* write data to the specified GPIO pin */ +void gpio_bit_write(uint32_t gpio_periph, uint32_t pin, bit_status bit_value); +/* write data to the specified GPIO port */ +void gpio_port_write(uint32_t gpio_periph, uint16_t data); + +/* get GPIO pin input status */ +FlagStatus gpio_input_bit_get(uint32_t gpio_periph, uint32_t pin); +/* get GPIO port input status */ +uint16_t gpio_input_port_get(uint32_t gpio_periph); +/* get GPIO pin output status */ +FlagStatus gpio_output_bit_get(uint32_t gpio_periph, uint32_t pin); +/* get GPIO port output status */ +uint16_t gpio_output_port_get(uint32_t gpio_periph); + +/* set GPIO alternate function */ +void gpio_af_set(uint32_t gpio_periph, uint32_t alt_func_num, uint32_t pin); +/* lock GPIO pin bit */ +void gpio_pin_lock(uint32_t gpio_periph, uint32_t pin); + +/* toggle GPIO pin status */ +void gpio_bit_toggle(uint32_t gpio_periph, uint32_t pin); +/* toggle GPIO port status */ +void gpio_port_toggle(uint32_t gpio_periph); + +#endif /* GD32F5XX_GPIO_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_hau.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_hau.h new file mode 100644 index 0000000..dacd29a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_hau.h @@ -0,0 +1,223 @@ +/*! + \file gd32f5xx_hau.h + \brief definitions for the HAU + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_HAU_H +#define GD32F5XX_HAU_H + +#include "gd32f5xx.h" + +/* HAU definitions */ +#define HAU HAU_BASE /*!< HAU base address */ + +/* registers definitions */ +#define HAU_CTL REG32(HAU + 0x00000000U) /*!< control register */ +#define HAU_DI REG32(HAU + 0x00000004U) /*!< data input register */ +#define HAU_CFG REG32(HAU + 0x00000008U) /*!< configuration register */ +#define HAU_DO0 REG32(HAU + 0x0000000CU) /*!< data output register 0 */ +#define HAU_DO1 REG32(HAU + 0x00000010U) /*!< data output register 1 */ +#define HAU_DO2 REG32(HAU + 0x00000014U) /*!< data output register 2 */ +#define HAU_DO3 REG32(HAU + 0x00000018U) /*!< data output register 3 */ +#define HAU_DO4 REG32(HAU + 0x0000001CU) /*!< data output register 4 */ +#define HAU_DO5 REG32(HAU + 0x00000324U) /*!< data output register 5 */ +#define HAU_DO6 REG32(HAU + 0x00000328U) /*!< data output register 6 */ +#define HAU_DO7 REG32(HAU + 0x0000032CU) /*!< data output register 7 */ +#define HAU_INTEN REG32(HAU + 0x00000020U) /*!< interrupt enable register */ +#define HAU_STAT REG32(HAU + 0x00000024U) /*!< status and interrupt flag register */ +#define HAU_CTXS(regval) REG32(HAU + 0x000000F8U + 0x04U * (regval)) /*!< context switch register, regval<=53 */ + +/* bits definitions */ +/* HAU_CTL */ +#define HAU_CTL_START BIT(2) /*!< set to 1 to reset the HAU processor core, so that it is ready to start the digest calculation */ +#define HAU_CTL_DMAE BIT(3) /*!< DMA enable */ +#define HAU_CTL_DATAM BITS(4,5) /*!< data type mode */ +#define HAU_CTL_HMS BIT(6) /*!< HAU mode selection */ +#define HAU_CTL_ALGM_0 BIT(7) /*!< algorithm selection bit 0 */ +#define HAU_CTL_NWIF BITS(8,11) /*!< number of words in the input FIFO */ +#define HAU_CTL_DINE BIT(12) /*!< DI register not empty */ +#define HAU_CTL_MDS BIT(13) /*!< multiple DMA selection */ +#define HAU_CTL_KLM BIT(16) /*!< key length mode */ +#define HAU_CTL_ALGM_1 BIT(18) /*!< algorithm selection bit 1 */ + +/* HAU_DI */ +#define HAU_DI_DI BITS(0,31) /*!< message data input */ + +/* HAU_CFG */ +#define HAU_CFG_VBL BITS(0,4) /*!< valid bits length in the last word */ +#define HAU_CFG_CALEN BIT(8) /*!< digest calculation enable */ + +/* HAU_DOx x=0..7 */ +#define HAU_DOX_DOX BITS(0,31) /*!< message digest result of hash algorithm */ + +/* HAU_INTEN */ +#define HAU_INTEN_DIIE BIT(0) /*!< data input interrupt enable */ +#define HAU_INTEN_CCIE BIT(1) /*!< calculation completion interrupt enable */ + +/* HAU_STAT */ +#define HAU_STAT_DIF BIT(0) /*!< data input interrupt flag */ +#define HAU_STAT_CCF BIT(1) /*!< digest calculation completion interrupt flag */ +#define HAU_STAT_DMAS BIT(2) /*!< DMA status */ +#define HAU_STAT_BUSY BIT(3) /*!< busy bit */ + +/* constants definitions */ +/* structure for initialization of the hau */ +typedef struct +{ + uint32_t algo; /*!< algorithm selection */ + uint32_t mode; /*!< HAU mode selection */ + uint32_t datatype; /*!< data type mode */ + uint32_t keytype; /*!< key length mode */ +}hau_init_parameter_struct; + +/* structure for message digest result of the hau */ +typedef struct +{ + uint32_t out[8]; /*!< message digest result 0-7 */ +}hau_digest_parameter_struct; + +/* structure for context switch */ +typedef struct +{ + uint32_t hau_ctl_bak; /*!< backup of HAU_CTL register */ + uint32_t hau_cfg_bak; /*!< backup of HAU_CFG register */ + uint32_t hau_inten_bak; /*!< backup of HAU_INTEN register */ + uint32_t hau_ctxs_bak[54];/*!< backup of HAU_CTXSx registers */ +}hau_context_parameter_struct; + +/* hau_ctl register value */ +#define HAU_ALGO_SHA1 ((uint32_t)0x00000000U) /*!< HAU function is SHA1 */ +#define HAU_ALGO_SHA224 HAU_CTL_ALGM_1 /*!< HAU function is SHA224 */ +#define HAU_ALGO_SHA256 (HAU_CTL_ALGM_1 | HAU_CTL_ALGM_0) /*!< HAU function is SHA256 */ +#define HAU_ALGO_MD5 HAU_CTL_ALGM_0 /*!< HAU function is MD5 */ + +#define HAU_MODE_HASH ((uint32_t)0x00000000U) /*!< HAU mode is HASH */ +#define HAU_MODE_HMAC HAU_CTL_HMS /*!< HAU mode is HMAC */ + +#define CTL_DATAM_1(regval) (BITS(4,5) & ((uint32_t)(regval) << 4U)) /*!< write value to HAU_CTL_DATAM bit field */ +#define HAU_SWAPPING_32BIT CTL_DATAM_1(0) /*!< no swapping */ +#define HAU_SWAPPING_16BIT CTL_DATAM_1(1) /*!< half-word swapping */ +#define HAU_SWAPPING_8BIT CTL_DATAM_1(2) /*!< bytes swapping */ +#define HAU_SWAPPING_1BIT CTL_DATAM_1(3) /*!< bit swapping */ + +#define HAU_KEY_SHORTER_64 ((uint32_t)0x00000000U) /*!< HMAC key is <= 64 bytes */ +#define HAU_KEY_LONGGER_64 HAU_CTL_KLM /*!< HMAC key is > 64 bytes */ + +#define GET_CTL_NWIF(regval) GET_BITS((regval),8,11) /*!< get value of HAU_CTL_NWIF bit field */ + +#define SINGLE_DMA_AUTO_DIGEST ((uint32_t)0x00000000U) /*!< message padding and message digest calculation at the end of a DMA transfer */ +#define MULTIPLE_DMA_NO_DIGEST HAU_CTL_MDS /*!< multiple DMA transfers needed and CALEN bit is not automatically set at the end of a DMA transfer */ + +/* hau_cfg register value */ +#define CFG_VBL(regval) (BITS(0,4) & ((regval) << 0U)) /*!< write value to HAU_CFG_VBL bit field */ + +/* hau_inten register value */ +#define HAU_INT_DATA_INPUT HAU_INTEN_DIIE /*!< a new block can be entered into the IN buffer */ +#define HAU_INT_CALCULATION_COMPLETE HAU_INTEN_CCIE /*!< calculation complete */ + +#define HAU_FLAG_DATA_INPUT HAU_STAT_DIF /*!< there is enough space (16 bytes) in the input FIFO */ +#define HAU_FLAG_CALCULATION_COMPLETE HAU_STAT_CCF /*!< digest calculation is completed */ +#define HAU_FLAG_DMA HAU_STAT_DMAS /*!< DMA is enabled (DMAE =1) or a transfer is processing */ +#define HAU_FLAG_BUSY HAU_STAT_BUSY /*!< data block is in process */ +#define HAU_FLAG_INFIFO_NO_EMPTY HAU_CTL_DINE /*!< the input FIFO is not empty */ + +#define HAU_INT_FLAG_DATA_INPUT HAU_STAT_DIF /*!< there is enough space (16 bytes) in the input FIFO */ +#define HAU_INT_FLAG_CALCULATION_COMPLETE HAU_STAT_CCF /*!< digest calculation is completed */ + +/* function declarations */ +/* initialization functions */ +/* reset the HAU peripheral */ +void hau_deinit(void); +/* initialize the HAU peripheral parameters */ +void hau_init(hau_init_parameter_struct* initpara); +/* initialize the structure hau_initpara */ +void hau_init_struct_para_init(hau_init_parameter_struct* initpara); +/* reset the HAU processor core */ +void hau_reset(void); +/* configure the number of valid bits in last word of the message */ +void hau_last_word_validbits_num_config(uint32_t valid_num); +/* write data to the IN FIFO */ +void hau_data_write(uint32_t data); +/* return the number of words already written into the IN FIFO */ +uint32_t hau_infifo_words_num_get(void); +/* read the message digest result */ +void hau_digest_read(hau_digest_parameter_struct* digestpara); +/* enable digest calculation */ +void hau_digest_calculation_enable(void); +/* configure single or multiple DMA is used, and digest calculation at the end of a DMA transfer or not */ +void hau_multiple_single_dma_config(uint32_t multi_single); +/* enable the HAU DMA interface */ +void hau_dma_enable(void); +/* disable the HAU DMA interface */ +void hau_dma_disable(void); + +/* context swapping functions */ +/* initialize the struct context */ +void hau_context_struct_para_init(hau_context_parameter_struct* context); +/* save the HAU peripheral context */ +void hau_context_save(hau_context_parameter_struct* context_save); +/* restore the HAU peripheral context */ +void hau_context_restore(hau_context_parameter_struct* context_restore); + +/* calculate digest in HASH mode */ +/* calculate digest using SHA1 in HASH mode */ +ErrStatus hau_hash_sha_1(uint8_t *input, uint32_t in_length, uint8_t output[]); +/* calculate digest using SHA1 in HMAC mode */ +ErrStatus hau_hmac_sha_1(uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t output[]); +/* calculate digest using SHA224 in HASH mode */ +ErrStatus hau_hash_sha_224(uint8_t *input, uint32_t in_length, uint8_t output[]); +/* calculate digest using SHA224 in HMAC mode */ +ErrStatus hau_hmac_sha_224(uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t output[]); +/* calculate digest using SHA256 in HASH mode */ +ErrStatus hau_hash_sha_256(uint8_t *input, uint32_t in_length, uint8_t output[]); +/* calculate digest using SHA256 in HMAC mode */ +ErrStatus hau_hmac_sha_256(uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t output[]); +/* calculate digest using MD5 in HASH mode */ +ErrStatus hau_hash_md5(uint8_t *input, uint32_t in_length, uint8_t output[]); +/* calculate digest using MD5 in HMAC mode */ +ErrStatus hau_hmac_md5(uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t output[]); + +/* interrupt & flag functions */ +/* get the HAU flag status */ +FlagStatus hau_flag_get(uint32_t flag); +/* clear the HAU flag status */ +void hau_flag_clear(uint32_t flag); +/* enable the HAU interrupts */ +void hau_interrupt_enable(uint32_t interrupt); +/* disable the HAU interrupts */ +void hau_interrupt_disable(uint32_t interrupt); +/* get the HAU interrupt flag status */ +FlagStatus hau_interrupt_flag_get(uint32_t int_flag); +/* clear the HAU interrupt flag status */ +void hau_interrupt_flag_clear(uint32_t int_flag); + +#endif /* GD32F5XX_HAU_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_i2c.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_i2c.h new file mode 100644 index 0000000..98e19f2 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_i2c.h @@ -0,0 +1,416 @@ +/*! + \file gd32f5xx_i2c.h + \brief definitions for the I2C0-2 + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_I2C_SIMPLE_H +#define GD32F5XX_I2C_SIMPLE_H + +#include "gd32f5xx.h" + +/* I2Cx(x=0,1,2) definitions */ +#define I2C0 I2C_BASE /*!< I2C0 base address */ +#define I2C1 (I2C_BASE + 0x00000400U) /*!< I2C1 base address */ +#define I2C2 (I2C_BASE + 0x00000800U) /*!< I2C2 base address */ + +/* registers definitions */ +#define I2C_CTL0(i2cx) REG32((i2cx) + 0x00000000U) /*!< I2C control register 0 */ +#define I2C_CTL1(i2cx) REG32((i2cx) + 0x00000004U) /*!< I2C control register 1 */ +#define I2C_SADDR0(i2cx) REG32((i2cx) + 0x00000008U) /*!< I2C slave address register 0 */ +#define I2C_SADDR1(i2cx) REG32((i2cx) + 0x0000000CU) /*!< I2C slave address register 1 */ +#define I2C_DATA(i2cx) REG32((i2cx) + 0x00000010U) /*!< I2C transfer buffer register */ +#define I2C_STAT0(i2cx) REG32((i2cx) + 0x00000014U) /*!< I2C transfer status register 0 */ +#define I2C_STAT1(i2cx) REG32((i2cx) + 0x00000018U) /*!< I2C transfer status register */ +#define I2C_CKCFG(i2cx) REG32((i2cx) + 0x0000001CU) /*!< I2C clock configure register */ +#define I2C_RT(i2cx) REG32((i2cx) + 0x00000020U) /*!< I2C rise time register */ +#define I2C_FCTL(i2cx) REG32((i2cx) + 0x00000024U) /*!< I2C filter control register */ +#define I2C_SAMCS(i2cx) REG32((i2cx) + 0x00000080U) /*!< I2C SAM control and status register */ + +/* bits definitions */ +/* I2Cx_CTL0 */ +#define I2C_CTL0_I2CEN BIT(0) /*!< peripheral enable */ +#define I2C_CTL0_SMBEN BIT(1) /*!< SMBus mode */ +#define I2C_CTL0_SMBSEL BIT(3) /*!< SMBus type */ +#define I2C_CTL0_ARPEN BIT(4) /*!< ARP enable */ +#define I2C_CTL0_PECEN BIT(5) /*!< PEC enable */ +#define I2C_CTL0_GCEN BIT(6) /*!< general call enable */ +#define I2C_CTL0_SS BIT(7) /*!< clock stretching disable (slave mode) */ +#define I2C_CTL0_START BIT(8) /*!< start generation */ +#define I2C_CTL0_STOP BIT(9) /*!< stop generation */ +#define I2C_CTL0_ACKEN BIT(10) /*!< acknowledge enable */ +#define I2C_CTL0_POAP BIT(11) /*!< acknowledge/PEC position (for data reception) */ +#define I2C_CTL0_PECTRANS BIT(12) /*!< packet error checking */ +#define I2C_CTL0_SALT BIT(13) /*!< SMBus alert */ +#define I2C_CTL0_SRESET BIT(15) /*!< software reset */ + +/* I2Cx_CTL1 */ +#define I2C_CTL1_I2CCLK BITS(0,5) /*!< I2CCLK[5:0] bits (peripheral clock frequency) */ +#define I2C_CTL1_ERRIE BIT(8) /*!< error interrupt enable */ +#define I2C_CTL1_EVIE BIT(9) /*!< event interrupt enable */ +#define I2C_CTL1_BUFIE BIT(10) /*!< buffer interrupt enable */ +#define I2C_CTL1_DMAON BIT(11) /*!< DMA requests enable */ +#define I2C_CTL1_DMALST BIT(12) /*!< DMA last transfer */ +#define I2C_CTL1_CFGRBNE BIT(15) /*!< RBNE clear condition control */ + +/* I2Cx_SADDR0 */ +#define I2C_SADDR0_ADDRESS0 BIT(0) /*!< bit 0 of a 10-bit address */ +#define I2C_SADDR0_ADDRESS BITS(1,7) /*!< 7-bit address or bits 7:1 of a 10-bit address */ +#define I2C_SADDR0_ADDRESS_H BITS(8,9) /*!< highest two bits of a 10-bit address */ +#define I2C_SADDR0_ADDFORMAT BIT(15) /*!< address mode for the I2C slave */ + +/* I2Cx_SADDR1 */ +#define I2C_SADDR1_DUADEN BIT(0) /*!< aual-address mode switch */ +#define I2C_SADDR1_ADDRESS2 BITS(1,7) /*!< second I2C address for the slave in dual-address mode */ + +/* I2Cx_DATA */ +#define I2C_DATA_TRB BITS(0,7) /*!< 8-bit data register */ + +/* I2Cx_STAT0 */ +#define I2C_STAT0_SBSEND BIT(0) /*!< start bit (master mode) */ +#define I2C_STAT0_ADDSEND BIT(1) /*!< address sent (master mode)/matched (slave mode) */ +#define I2C_STAT0_BTC BIT(2) /*!< byte transfer finished */ +#define I2C_STAT0_ADD10SEND BIT(3) /*!< 10-bit header sent (master mode) */ +#define I2C_STAT0_STPDET BIT(4) /*!< stop detection (slave mode) */ +#define I2C_STAT0_RBNE BIT(6) /*!< data register not empty (receivers) */ +#define I2C_STAT0_TBE BIT(7) /*!< data register empty (transmitters) */ +#define I2C_STAT0_BERR BIT(8) /*!< bus error */ +#define I2C_STAT0_LOSTARB BIT(9) /*!< arbitration lost (master mode) */ +#define I2C_STAT0_AERR BIT(10) /*!< acknowledge failure */ +#define I2C_STAT0_OUERR BIT(11) /*!< overrun/underrun */ +#define I2C_STAT0_PECERR BIT(12) /*!< PEC error in reception */ +#define I2C_STAT0_SMBTO BIT(14) /*!< timeout signal in SMBus mode */ +#define I2C_STAT0_SMBALT BIT(15) /*!< SMBus alert status */ + +/* I2Cx_STAT1 */ +#define I2C_STAT1_MASTER BIT(0) /*!< master/slave */ +#define I2C_STAT1_I2CBSY BIT(1) /*!< bus busy */ +#define I2C_STAT1_TR BIT(2) /*!< transmitter/receiver */ +#define I2C_STAT1_RXGC BIT(4) /*!< general call address (slave mode) */ +#define I2C_STAT1_DEFSMB BIT(5) /*!< SMBus device default address (slave mode) */ +#define I2C_STAT1_HSTSMB BIT(6) /*!< SMBus host header (slave mode) */ +#define I2C_STAT1_DUMODF BIT(7) /*!< dual flag (slave mode) */ +#define I2C_STAT1_PECV BITS(8,15) /*!< packet error checking value */ + +/* I2Cx_CKCFG */ +#define I2C_CKCFG_CLKC BITS(0,11) /*!< clock control register in fast/standard mode (master mode) */ +#define I2C_CKCFG_DTCY BIT(14) /*!< fast mode duty cycle */ +#define I2C_CKCFG_FAST BIT(15) /*!< I2C speed selection in master mode */ + +/* I2Cx_RT */ +#define I2C_RT_RISETIME BITS(0,5) /*!< maximum rise time in fast/standard mode (Master mode) */ + +/* I2Cx_FCTL */ +#define I2C_FCTL_DF BITS(0,3) /*!< digital noise filter */ +#define I2C_FCTL_AFD BIT(4) /*!< analog noise filter disable */ + +/* I2Cx_SAMCS */ +#define I2C_SAMCS_SAMEN BIT(0) /*!< SAM_V interface enable */ +#define I2C_SAMCS_STOEN BIT(1) /*!< SAM_V interface timeout detect enable */ +#define I2C_SAMCS_TFFIE BIT(4) /*!< txframe fall interrupt enable */ +#define I2C_SAMCS_TFRIE BIT(5) /*!< txframe rise interrupt enable */ +#define I2C_SAMCS_RFFIE BIT(6) /*!< rxframe fall interrupt enable */ +#define I2C_SAMCS_RFRIE BIT(7) /*!< rxframe rise interrupt enable */ +#define I2C_SAMCS_TXF BIT(8) /*!< level of txframe signal */ +#define I2C_SAMCS_RXF BIT(9) /*!< level of rxframe signal */ +#define I2C_SAMCS_TFF BIT(12) /*!< txframe fall flag */ +#define I2C_SAMCS_TFR BIT(13) /*!< txframe rise flag */ +#define I2C_SAMCS_RFF BIT(14) /*!< rxframe fall flag */ +#define I2C_SAMCS_RFR BIT(15) /*!< rxframe rise flag */ + +/* constants definitions */ +/* define the I2C bit position and its register index offset */ +#define I2C_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)) +#define I2C_REG_VAL(i2cx, offset) (REG32((i2cx) + (((uint32_t)(offset) & 0x0000FFFFU) >> 6))) +#define I2C_BIT_POS(val) ((uint32_t)(val) & 0x0000001FU) +#define I2C_REGIDX_BIT2(regidx, bitpos, regidx2, bitpos2) (((uint32_t)(regidx2) << 22) | (uint32_t)((bitpos2) << 16)\ + | (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))) +#define I2C_REG_VAL2(i2cx, offset) (REG32((i2cx) + ((uint32_t)(offset) >> 22))) +#define I2C_BIT_POS2(val) (((uint32_t)(val) & 0x001F0000U) >> 16) + +/* register offset */ +#define I2C_CTL1_REG_OFFSET ((uint32_t)0x00000004U) /*!< CTL1 register offset */ +#define I2C_STAT0_REG_OFFSET ((uint32_t)0x00000014U) /*!< STAT0 register offset */ +#define I2C_STAT1_REG_OFFSET ((uint32_t)0x00000018U) /*!< STAT1 register offset */ +#define I2C_SAMCS_REG_OFFSET ((uint32_t)0x00000080U) /*!< SAMCS register offset */ + +/* I2C flags */ +typedef enum { + /* flags in STAT0 register */ + I2C_FLAG_SBSEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 0U), /*!< start condition sent out in master mode */ + I2C_FLAG_ADDSEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 1U), /*!< address is sent in master mode or received and matches in slave mode */ + I2C_FLAG_BTC = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 2U), /*!< byte transmission finishes */ + I2C_FLAG_ADD10SEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 3U), /*!< header of 10-bit address is sent in master mode */ + I2C_FLAG_STPDET = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 4U), /*!< stop condition detected in slave mode */ + I2C_FLAG_RBNE = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 6U), /*!< I2C_DATA is not empty during receiving */ + I2C_FLAG_TBE = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 7U), /*!< I2C_DATA is empty during transmitting */ + I2C_FLAG_BERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 8U), /*!< a bus error occurs indication a unexpected start or stop condition on I2C bus */ + I2C_FLAG_LOSTARB = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 9U), /*!< arbitration lost in master mode */ + I2C_FLAG_AERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 10U), /*!< acknowledge error */ + I2C_FLAG_OUERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 11U), /*!< over-run or under-run situation occurs in slave mode */ + I2C_FLAG_PECERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 12U), /*!< PEC error when receiving data */ + I2C_FLAG_SMBTO = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 14U), /*!< timeout signal in SMBus mode */ + I2C_FLAG_SMBALT = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 15U), /*!< SMBus alert status */ + /* flags in STAT1 register */ + I2C_FLAG_MASTER = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 0U), /*!< a flag indicating whether I2C block is in master or slave mode */ + I2C_FLAG_I2CBSY = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 1U), /*!< busy flag */ + I2C_FLAG_TR = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 2U), /*!< whether the I2C is a transmitter or a receiver */ + I2C_FLAG_RXGC = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 4U), /*!< general call address (00h) received */ + I2C_FLAG_DEFSMB = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 5U), /*!< default address of SMBus device */ + I2C_FLAG_HSTSMB = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 6U), /*!< SMBus host header detected in slave mode */ + I2C_FLAG_DUMOD = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 7U), /*!< dual flag in slave mode indicating which address is matched in dual-address mode */ + /* flags in SAMCS register */ + I2C_FLAG_TFF = I2C_REGIDX_BIT(I2C_SAMCS_REG_OFFSET, 12U), /*!< txframe fall flag */ + I2C_FLAG_TFR = I2C_REGIDX_BIT(I2C_SAMCS_REG_OFFSET, 13U), /*!< txframe rise flag */ + I2C_FLAG_RFF = I2C_REGIDX_BIT(I2C_SAMCS_REG_OFFSET, 14U), /*!< rxframe fall flag */ + I2C_FLAG_RFR = I2C_REGIDX_BIT(I2C_SAMCS_REG_OFFSET, 15U) /*!< rxframe rise flag */ +} i2c_flag_enum; + +/* I2C interrupt flags */ +typedef enum { + /* interrupt flags in CTL1 register */ + I2C_INT_FLAG_SBSEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 0U), /*!< start condition sent out in master mode interrupt flag */ + I2C_INT_FLAG_ADDSEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 1U), /*!< address is sent in master mode or received and matches in slave mode interrupt flag */ + I2C_INT_FLAG_BTC = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 2U), /*!< byte transmission finishes interrupt flag */ + I2C_INT_FLAG_ADD10SEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 3U), /*!< header of 10-bit address is sent in master mode interrupt flag */ + I2C_INT_FLAG_STPDET = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 4U), /*!< stop condition detected in slave mode interrupt flag */ + I2C_INT_FLAG_RBNE = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 6U), /*!< I2C_DATA is not Empty during receiving interrupt flag */ + I2C_INT_FLAG_TBE = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 7U), /*!< I2C_DATA is empty during transmitting interrupt flag */ + I2C_INT_FLAG_BERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 8U), /*!< a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag */ + I2C_INT_FLAG_LOSTARB = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 9U), /*!< arbitration lost in master mode interrupt flag */ + I2C_INT_FLAG_AERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 10U), /*!< acknowledge error interrupt flag */ + I2C_INT_FLAG_OUERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 11U), /*!< over-run or under-run situation occurs in slave mode interrupt flag */ + I2C_INT_FLAG_PECERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 12U), /*!< PEC error when receiving data interrupt flag */ + I2C_INT_FLAG_SMBTO = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 14U), /*!< timeout signal in SMBus mode interrupt flag */ + I2C_INT_FLAG_SMBALT = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 15U), /*!< SMBus alert status interrupt flag */ + /* interrupt flags in SAMCS register */ + I2C_INT_FLAG_TFF = I2C_REGIDX_BIT2(I2C_SAMCS_REG_OFFSET, 4U, I2C_SAMCS_REG_OFFSET, 12U), /*!< txframe fall interrupt flag */ + I2C_INT_FLAG_TFR = I2C_REGIDX_BIT2(I2C_SAMCS_REG_OFFSET, 5U, I2C_SAMCS_REG_OFFSET, 13U), /*!< txframe rise interrupt flag */ + I2C_INT_FLAG_RFF = I2C_REGIDX_BIT2(I2C_SAMCS_REG_OFFSET, 6U, I2C_SAMCS_REG_OFFSET, 14U), /*!< rxframe fall interrupt flag */ + I2C_INT_FLAG_RFR = I2C_REGIDX_BIT2(I2C_SAMCS_REG_OFFSET, 7U, I2C_SAMCS_REG_OFFSET, 15U) /*!< rxframe rise interrupt flag */ +} i2c_interrupt_flag_enum; + +/* I2C interrupt */ +typedef enum { + /* interrupt in CTL1 register */ + I2C_INT_ERR = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 8U), /*!< error interrupt */ + I2C_INT_EV = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 9U), /*!< event interrupt */ + I2C_INT_BUF = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 10U), /*!< buffer interrupt */ + /* interrupt in SAMCS register */ + I2C_INT_TFF = I2C_REGIDX_BIT(I2C_SAMCS_REG_OFFSET, 4U), /*!< txframe fall interrupt */ + I2C_INT_TFR = I2C_REGIDX_BIT(I2C_SAMCS_REG_OFFSET, 5U), /*!< txframe rise interrupt */ + I2C_INT_RFF = I2C_REGIDX_BIT(I2C_SAMCS_REG_OFFSET, 6U), /*!< rxframe fall interrupt */ + I2C_INT_RFR = I2C_REGIDX_BIT(I2C_SAMCS_REG_OFFSET, 7U) /*!< rxframe rise interrupt */ +} i2c_interrupt_enum; + +/* the digital noise filter can filter spikes's length */ +typedef enum { + I2C_DF_DISABLE = 0, /*!< disable digital noise filter */ + I2C_DF_1PCLK, /*!< enable digital noise filter and the maximum filtered spiker's length 1 PCLK1 */ + I2C_DF_2PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 2 PCLK1 */ + I2C_DF_3PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 3 PCLK1 */ + I2C_DF_4PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 4 PCLK1 */ + I2C_DF_5PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 5 PCLK1 */ + I2C_DF_6PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 6 PCLK1 */ + I2C_DF_7PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 7 PCLK1 */ + I2C_DF_8PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 8 PCLK1 */ + I2C_DF_9PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 9 PCLK1 */ + I2C_DF_10PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 10 PCLK1 */ + I2C_DF_11PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 11 PCLK1 */ + I2C_DF_12PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 12 PCLK1 */ + I2C_DF_13PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 13 PCLK1 */ + I2C_DF_14PCLKS, /*!< enable digital noise filter and the maximum filtered spiker's length 14 PCLK1 */ + I2C_DF_15PCLKS /*!< enable digital noise filter and the maximum filtered spiker's length 15 PCLK1 */ +} i2c_digital_filter_enum; + +/* SMBus/I2C mode switch and SMBus type selection */ +#define I2C_I2CMODE_ENABLE ((uint32_t)0x00000000U) /*!< I2C mode */ +#define I2C_SMBUSMODE_ENABLE I2C_CTL0_SMBEN /*!< SMBus mode */ + +/* SMBus/I2C mode switch and SMBus type selection */ +#define I2C_SMBUS_DEVICE ((uint32_t)0x00000000U) /*!< SMBus mode device type */ +#define I2C_SMBUS_HOST I2C_CTL0_SMBSEL /*!< SMBus mode host type */ + +/* I2C transfer direction */ +#define I2C_RECEIVER ((uint32_t)0x00000001U) /*!< receiver */ +#define I2C_TRANSMITTER ((uint32_t)0xFFFFFFFEU) /*!< transmitter */ + +/* whether or not to send an ACK */ +#define I2C_ACK_DISABLE ((uint32_t)0x00000000U) /*!< ACK will be not sent */ +#define I2C_ACK_ENABLE I2C_CTL0_ACKEN /*!< ACK will be sent */ + +/* I2C POAP position*/ +#define I2C_ACKPOS_CURRENT ((uint32_t)0x00000000U) /*!< ACKEN bit decides whether or not to send ACK or not for the current byte */ +#define I2C_ACKPOS_NEXT I2C_CTL0_POAP /*!< ACKEN bit decides whether or not to send ACK for the next byte */ + +/* whether or not to stretch SCL low */ +#define I2C_SCLSTRETCH_ENABLE ((uint32_t)0x00000000U) /*!< enable SCL stretching */ +#define I2C_SCLSTRETCH_DISABLE I2C_CTL0_SS /*!< disable SCL stretching */ + +/* whether or not to response to a general call */ +#define I2C_GCEN_ENABLE I2C_CTL0_GCEN /*!< slave will response to a general call */ +#define I2C_GCEN_DISABLE ((uint32_t)0x00000000U) /*!< slave will not response to a general call */ + +/* software reset I2C */ +#define I2C_SRESET_RESET ((uint32_t)0x00000000U) /*!< I2C is not under reset */ +#define I2C_SRESET_SET I2C_CTL0_SRESET /*!< I2C is under reset */ + +/* I2C DMA mode configure */ +/* DMA mode switch */ +#define I2C_DMA_OFF ((uint32_t)0x00000000U) /*!< disable DMA mode */ +#define I2C_DMA_ON I2C_CTL1_DMAON /*!< enable DMA mode */ + +/* flag indicating DMA last transfer */ +#define I2C_DMALST_OFF ((uint32_t)0x00000000U) /*!< next DMA EOT is not the last transfer */ +#define I2C_DMALST_ON I2C_CTL1_DMALST /*!< next DMA EOT is the last transfer */ + +/* RBNE clear condition control */ +#define I2C_CFGRBNE_OFF ((uint32_t)0x00000000U) /*!< RBNE can be cleared when RXDATA is read and BTC is cleared */ +#define I2C_CFGRBNE_ON I2C_CTL1_CFGRBNE /*!< RBNE can be cleared when RXDATA is read */ + +/* I2C PEC configure */ +/* PEC enable */ +#define I2C_PEC_DISABLE ((uint32_t)0x00000000U) /*!< PEC calculation off */ +#define I2C_PEC_ENABLE I2C_CTL0_PECEN /*!< PEC calculation on */ + +/* PEC transfer */ +#define I2C_PECTRANS_DISABLE ((uint32_t)0x00000000U) /*!< not transfer PEC value */ +#define I2C_PECTRANS_ENABLE I2C_CTL0_PECTRANS /*!< transfer PEC value */ + +/* I2C SMBus configure */ +/* issue or not alert through SMBA pin */ +#define I2C_SALTSEND_DISABLE ((uint32_t)0x00000000U) /*!< not issue alert through SMBA */ +#define I2C_SALTSEND_ENABLE I2C_CTL0_SALT /*!< issue alert through SMBA pin */ + +/* ARP protocol in SMBus switch */ +#define I2C_ARP_DISABLE ((uint32_t)0x00000000U) /*!< disable ARP */ +#define I2C_ARP_ENABLE I2C_CTL0_ARPEN /*!< enable ARP */ + +/* transmit I2C data */ +#define DATA_TRANS(regval) (BITS(0,7) & ((uint32_t)(regval) << 0)) + +/* receive I2C data */ +#define DATA_RECV(regval) GET_BITS((uint32_t)(regval), 0, 7) + +/* I2C duty cycle in fast mode */ +#define I2C_DTCY_2 ((uint32_t)0x00000000U) /*!< T_low/T_high = 2 in fast mode */ +#define I2C_DTCY_16_9 I2C_CKCFG_DTCY /*!< T_low/T_high = 16/9 in fast mode */ + +/* address mode for the I2C slave */ +#define I2C_ADDFORMAT_7BITS ((uint32_t)0x00000000U) /*!< address format is 7 bits */ +#define I2C_ADDFORMAT_10BITS I2C_SADDR0_ADDFORMAT /*!< address format is 10 bits */ + +/* function declarations */ +/* initialization functions */ +/* reset I2C */ +void i2c_deinit(uint32_t i2c_periph); +/* configure I2C clock */ +void i2c_clock_config(uint32_t i2c_periph, uint32_t clkspeed, uint32_t dutycyc); +/* configure I2C address */ +void i2c_mode_addr_config(uint32_t i2c_periph, uint32_t mode, uint32_t addformat, uint32_t addr); + +/* application function declarations */ +/* select SMBus type */ +void i2c_smbus_type_config(uint32_t i2c_periph, uint32_t type); +/* whether or not to send an ACK */ +void i2c_ack_config(uint32_t i2c_periph, uint32_t ack); +/* configure I2C POAP position */ +void i2c_ackpos_config(uint32_t i2c_periph, uint32_t pos); +/* master sends slave address */ +void i2c_master_addressing(uint32_t i2c_periph, uint32_t addr, uint32_t trandirection); +/* enable dual-address mode */ +void i2c_dualaddr_enable(uint32_t i2c_periph, uint32_t addr); +/* disable dual-address mode */ +void i2c_dualaddr_disable(uint32_t i2c_periph); +/* enable I2C */ +void i2c_enable(uint32_t i2c_periph); +/* disable I2C */ +void i2c_disable(uint32_t i2c_periph); +/* generate a START condition on I2C bus */ +void i2c_start_on_bus(uint32_t i2c_periph); +/* generate a STOP condition on I2C bus */ +void i2c_stop_on_bus(uint32_t i2c_periph); +/* I2C transmit data function */ +void i2c_data_transmit(uint32_t i2c_periph, uint8_t data); +/* I2C receive data function */ +uint8_t i2c_data_receive(uint32_t i2c_periph); +/* configure I2C DMA mode */ +void i2c_dma_config(uint32_t i2c_periph, uint32_t dmastate); +/* configure whether next DMA EOT is DMA last transfer or not */ +void i2c_dma_last_transfer_config(uint32_t i2c_periph, uint32_t dmalast); +/* configure RBNE clear condition */ +void i2c_rbne_clear_config(uint32_t i2c_periph, uint32_t rbnecondition); +/* whether to stretch SCL low when data is not ready in slave mode */ +void i2c_stretch_scl_low_config(uint32_t i2c_periph, uint32_t stretchpara); +/* whether or not to response to a general call */ +void i2c_slave_response_to_gcall_config(uint32_t i2c_periph, uint32_t gcallpara); +/* configure software reset of I2C */ +void i2c_software_reset_config(uint32_t i2c_periph, uint32_t sreset); +/* configure I2C PEC calculation */ +void i2c_pec_config(uint32_t i2c_periph, uint32_t pecstate); +/* configure whether to transfer PEC value */ +void i2c_pec_transfer_config(uint32_t i2c_periph, uint32_t pecpara); +/* get packet error checking value */ +uint8_t i2c_pec_value_get(uint32_t i2c_periph); +/* configure I2C alert through SMBA pin */ +void i2c_smbus_alert_config(uint32_t i2c_periph, uint32_t smbuspara); +/* configure I2C ARP protocol in SMBus */ +void i2c_smbus_arp_config(uint32_t i2c_periph, uint32_t arpstate); +/* disable analog noise filter */ +void i2c_analog_noise_filter_disable(uint32_t i2c_periph); +/* enable analog noise filter */ +void i2c_analog_noise_filter_enable(uint32_t i2c_periph); +/* configure digital noise filter */ +void i2c_digital_noise_filter_config(uint32_t i2c_periph, i2c_digital_filter_enum dfilterpara); +/* enable SAM_V interface */ +void i2c_sam_enable(uint32_t i2c_periph); +/* disable SAM_V interface */ +void i2c_sam_disable(uint32_t i2c_periph); +/* enable SAM_V interface timeout detect */ +void i2c_sam_timeout_enable(uint32_t i2c_periph); +/* disable SAM_V interface timeout detect */ +void i2c_sam_timeout_disable(uint32_t i2c_periph); + +/* interrupt & flag functions */ +/* get I2C flag status */ +FlagStatus i2c_flag_get(uint32_t i2c_periph, i2c_flag_enum flag); +/* clear I2C flag status */ +void i2c_flag_clear(uint32_t i2c_periph, i2c_flag_enum flag); +/* enable I2C interrupt */ +void i2c_interrupt_enable(uint32_t i2c_periph, i2c_interrupt_enum interrupt); +/* disable I2C interrupt */ +void i2c_interrupt_disable(uint32_t i2c_periph, i2c_interrupt_enum interrupt); +/* get I2C interrupt flag status */ +FlagStatus i2c_interrupt_flag_get(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag); +/* clear I2C interrupt flag status */ +void i2c_interrupt_flag_clear(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag); + +#endif /* GD32F5XX_I2C_SIMPLE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_i2c_add.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_i2c_add.h new file mode 100644 index 0000000..7b7cf41 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_i2c_add.h @@ -0,0 +1,410 @@ +/*! + \file gd32f5xx_i2c.h + \brief definitions for the I2C3-5 + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_I2C_ADD_H +#define GD32F5XX_I2C_ADD_H + +#include "gd32f5xx.h" + +/* I2Cx(x=3,4,5) definitions */ +#define I2C0 I2C_BASE /*!< I2C0 base address */ + +#define I2C3 (I2C_BASE + 0x00002C00U) /*!< I2C3 base address */ +#define I2C4 (I2C_BASE + 0x00003000U) /*!< I2C4 base address */ +#define I2C5 (I2C_BASE + 0x00003400U) /*!< I2C5 base address */ + +/* registers definitions */ +/* registers of I2Cx(x=3,4,5) */ +#define I2C_ADD_CTL0(i2cx) REG32((i2cx) + 0x00000000U) /*!< I2C control register 0 */ +#define I2C_ADD_CTL1(i2cx) REG32((i2cx) + 0x00000004U) /*!< I2C control register 1 */ +#define I2C_ADD_SADDR0(i2cx) REG32((i2cx) + 0x00000008U) /*!< I2C slave address register 0*/ +#define I2C_ADD_SADDR1(i2cx) REG32((i2cx) + 0x0000000CU) /*!< I2C slave address register 1*/ +#define I2C_ADD_TIMING(i2cx) REG32((i2cx) + 0x00000010U) /*!< I2C timing register */ +#define I2C_ADD_TIMEOUT(i2cx) REG32((i2cx) + 0x00000014U) /*!< I2C timeout register */ +#define I2C_ADD_STAT(i2cx) REG32((i2cx) + 0x00000018U) /*!< I2C status register */ +#define I2C_ADD_STATC(i2cx) REG32((i2cx) + 0x0000001CU) /*!< I2C status clear register */ +#define I2C_ADD_PEC(i2cx) REG32((i2cx) + 0x00000020U) /*!< I2C PEC register */ +#define I2C_ADD_RDATA(i2cx) REG32((i2cx) + 0x00000024U) /*!< I2C receive data register */ +#define I2C_ADD_TDATA(i2cx) REG32((i2cx) + 0x00000028U) /*!< I2C transmit data register */ +#define I2C_ADD_CTL2(i2cx) REG32((i2cx) + 0x00000090U) /*!< I2C control register 2 */ + +/* bits definitions */ +/* I2Cx_CTL0 */ +#define I2C_ADD_CTL0_I2CEN BIT(0) /*!< I2C peripheral enable */ +#define I2C_ADD_CTL0_TIE BIT(1) /*!< transmit interrupt enable */ +#define I2C_ADD_CTL0_RBNEIE BIT(2) /*!< receive interrupt enable */ +#define I2C_ADD_CTL0_ADDMIE BIT(3) /*!< address match interrupt enable in slave mode */ +#define I2C_ADD_CTL0_NACKIE BIT(4) /*!< not acknowledge received interrupt enable */ +#define I2C_ADD_CTL0_STPDETIE BIT(5) /*!< stop detection interrupt enable */ +#define I2C_ADD_CTL0_TCIE BIT(6) /*!< transfer complete interrupt enable */ +#define I2C_ADD_CTL0_ERRIE BIT(7) /*!< error interrupt enable */ +#define I2C_ADD_CTL0_DNF BITS(8,11) /*!< digital noise filter */ +#define I2C_ADD_CTL0_ANOFF BIT(12) /*!< analog noise filter */ +#define I2C_ADD_CTL0_DENT BIT(14) /*!< DMA enable for transmission */ +#define I2C_ADD_CTL0_DENR BIT(15) /*!< DMA enable for reception */ +#define I2C_ADD_CTL0_SBCTL BIT(16) /*!< slave byte control */ +#define I2C_ADD_CTL0_SS BIT(17) /*!< whether to stretch SCL low when data is not ready in slave mode */ +#define I2C_ADD_CTL0_WUEN BIT(18) /*!< wakeup from deep-sleep mode enable */ +#define I2C_ADD_CTL0_GCEN BIT(19) /*!< whether or not to response to a general call (0x00) */ +#define I2C_ADD_CTL0_SMBHAEN BIT(20) /*!< SMBus host address enable */ +#define I2C_ADD_CTL0_SMBDAEN BIT(21) /*!< SMBus device default address enable */ +#define I2C_ADD_CTL0_SMBALTEN BIT(22) /*!< SMBus alert enable */ +#define I2C_ADD_CTL0_PECEN BIT(23) /*!< PEC calculation switch */ + +/* I2Cx_CTL1 */ +#define I2C_ADD_CTL1_SADDRESS BITS(0,9) /*!< received slave address */ +#define I2C_ADD_CTL1_TRDIR BIT(10) /*!< transfer direction in master mode */ +#define I2C_ADD_CTL1_ADD10EN BIT(11) /*!< 10-bit addressing mode enable in master mode */ +#define I2C_ADD_CTL1_HEAD10R BIT(12) /*!< 10-bit address header executes read direction only in master receive mode */ +#define I2C_ADD_CTL1_START BIT(13) /*!< generate a START condition on I2C bus */ +#define I2C_ADD_CTL1_STOP BIT(14) /*!< generate a STOP condition on I2C bus */ +#define I2C_ADD_CTL1_NACKEN BIT(15) /*!< generate NACK in slave mode */ +#define I2C_ADD_CTL1_BYTENUM BITS(16,23) /*!< number of bytes to be transferred */ +#define I2C_ADD_CTL1_RELOAD BIT(24) /*!< reload mode enable */ +#define I2C_ADD_CTL1_AUTOEND BIT(25) /*!< automatic end mode in master mode */ +#define I2C_ADD_CTL1_PECTRANS BIT(26) /*!< PEC transfer */ + +/* I2Cx_SADDR0 */ +#define I2C_ADD_SADDR0_ADDRESS0 BIT(0) /*!< bit 0 of a 10-bit address */ +#define I2C_ADD_SADDR0_ADDRESS BITS(1,7) /*!< 7-bit address or bits 7:1 of a 10-bit address */ +#define I2C_ADD_SADDR0_ADDRESS_H BITS(8,9) /*!< highest two bits of a 10-bit address */ +#define I2C_ADD_SADDR0_ADDFORMAT BIT(10) /*!< address mode for the I2C slave */ +#define I2C_ADD_SADDR0_ADDRESSEN BIT(15) /*!< I2C address enable */ + +/* I2Cx_SADDR1 */ +#define I2C_ADD_SADDR1_ADDRESS2 BITS(1,7) /*!< second I2C address for the slave */ +#define I2C_ADD_SADDR1_ADDMSK2 BITS(8,10) /*!< ADDRESS2[7:1] mask */ +#define I2C_ADD_SADDR1_ADDRESS2EN BIT(15) /*!< second I2C address enable */ + +/* I2Cx_TIMING */ +#define I2C_ADD_TIMING_SCLL BITS(0,7) /*!< SCL low period */ +#define I2C_ADD_TIMING_SCLH BITS(8,15) /*!< SCL high period */ +#define I2C_ADD_TIMING_SDADELY BITS(16,19) /*!< data hold time */ +#define I2C_ADD_TIMING_SCLDELY BITS(20,23) /*!< data setup time */ +#define I2C_ADD_TIMING_PSC BITS(28,31) /*!< timing prescaler */ + +/* I2Cx_TIMEOUT */ +#define I2C_ADD_TIMEOUT_BUSTOA BITS(0,11) /*!< bus timeout A */ +#define I2C_ADD_TIMEOUT_TOIDLE BIT(12) /*!< idle clock timeout detection */ +#define I2C_ADD_TIMEOUT_TOEN BIT(15) /*!< clock timeout detection enable */ +#define I2C_ADD_TIMEOUT_BUSTOB BITS(16,27) /*!< bus timeout B */ +#define I2C_ADD_TIMEOUT_EXTOEN BIT(31) /*!< extended clock timeout detection enable */ + +/* I2Cx_STAT */ +#define I2C_ADD_STAT_TBE BIT(0) /*!< I2C_ADD_TDATA is empty during transmitting */ +#define I2C_ADD_STAT_TI BIT(1) /*!< transmit interrupt */ +#define I2C_ADD_STAT_RBNE BIT(2) /*!< I2C_ADD_RDATA is not empty during receiving */ +#define I2C_ADD_STAT_ADDSEND BIT(3) /*!< address received matches in slave mode */ +#define I2C_ADD_STAT_NACK BIT(4) /*!< not acknowledge flag */ +#define I2C_ADD_STAT_STPDET BIT(5) /*!< STOP condition detected in slave mode */ +#define I2C_ADD_STAT_TC BIT(6) /*!< transfer complete in master mode */ +#define I2C_ADD_STAT_TCR BIT(7) /*!< transfer complete reload */ +#define I2C_ADD_STAT_BERR BIT(8) /*!< bus error */ +#define I2C_ADD_STAT_LOSTARB BIT(9) /*!< arbitration lost */ +#define I2C_ADD_STAT_OUERR BIT(10) /*!< overrun/underrun error in slave mode */ +#define I2C_ADD_STAT_PECERR BIT(11) /*!< PEC error */ +#define I2C_ADD_STAT_TIMEOUT BIT(12) /*!< timeout flag */ +#define I2C_ADD_STAT_SMBALT BIT(13) /*!< SMBus Alert */ +#define I2C_ADD_STAT_I2CBSY BIT(15) /*!< busy flag */ +#define I2C_ADD_STAT_TR BIT(16) /*!< whether the I2C is a transmitter or a receiver in slave mode */ +#define I2C_ADD_STAT_READDR BITS(17,23) /*!< received match address in slave mode */ + +/* I2Cx_STATC */ +#define I2C_ADD_STATC_ADDSENDC BIT(3) /*!< ADDSEND flag clear */ +#define I2C_ADD_STATC_NACKC BIT(4) /*!< not acknowledge flag clear */ +#define I2C_ADD_STATC_STPDETC BIT(5) /*!< STPDET flag clear */ +#define I2C_ADD_STATC_BERRC BIT(8) /*!< bus error flag clear */ +#define I2C_ADD_STATC_LOSTARBC BIT(9) /*!< arbitration Lost flag clear */ +#define I2C_ADD_STATC_OUERRC BIT(10) /*!< overrun/underrun flag clear */ +#define I2C_ADD_STATC_PECERRC BIT(11) /*!< PEC error flag clear */ +#define I2C_ADD_STATC_TIMEOUTC BIT(12) /*!< TIMEOUT flag clear */ +#define I2C_ADD_STATC_SMBALTC BIT(13) /*!< SMBus Alert flag clear */ + +/* I2Cx_PEC */ +#define I2C_ADD_PEC_PECV BITS(0,7) /*!< Packet Error Checking Value that calculated by hardware when PEC is enabled */ + +/* I2Cx_RDATA */ +#define I2C_ADD_RDATA_RDATA BITS(0,7) /*!< receive data value */ + +/* I2Cx_TDATA */ +#define I2C_ADD_TDATA_TDATA BITS(0,7) /*!< transmit data value */ + +/* I2Cx_CTL2 */ +#define I2C_ADD_CTL2_ADDM BITS(9,15) /*!< address bits compare select */ + +/* constants definitions */ +/* define the I2C bit position and its register index offset */ +#define I2C_ADD_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)) +#define I2C_ADD_REG_VAL(i2cx, offset) (REG32((i2cx) + (((uint32_t)(offset) & 0x0000FFFFU) >> 6))) +#define I2C_ADD_BIT_POS(val) ((uint32_t)(val) & 0x0000001FU) +#define I2C_ADD_REGIDX_BIT2(regidx, bitpos, regidx2, bitpos2) (((uint32_t)(regidx2) << 22) | (uint32_t)((bitpos2) << 16)\ + | (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))) +#define I2C_ADD_REG_VAL2(i2cx, offset) (REG32((i2cx) + ((uint32_t)(offset) >> 22))) +#define I2C_ADD_BIT_POS2(val) (((uint32_t)(val) & 0x001F0000U) >> 16) + +/* register offset */ +#define I2C_ADD_CTL0_REG_OFFSET ((uint32_t)0x00000000U) /*!< CTL0 register offset */ +#define I2C_ADD_STAT_REG_OFFSET ((uint32_t)0x00000018U) /*!< STAT register offset */ + +/* I2C interrupt flags */ +typedef enum { + I2C_ADD_INT_FLAG_TI = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 1U, I2C_ADD_STAT_REG_OFFSET, 1U), /*!< transmit interrupt flag */ + I2C_ADD_INT_FLAG_RBNE = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 2U, I2C_ADD_STAT_REG_OFFSET, 2U), /*!< I2C_ADD_RDATA is not empty during receiving interrupt flag */ + I2C_ADD_INT_FLAG_ADDSEND = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 3U, I2C_ADD_STAT_REG_OFFSET, 3U), /*!< address received matches in slave mode interrupt flag */ + I2C_ADD_INT_FLAG_NACK = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 4U, I2C_ADD_STAT_REG_OFFSET, 4U), /*!< not acknowledge interrupt flag */ + I2C_ADD_INT_FLAG_STPDET = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 5U, I2C_ADD_STAT_REG_OFFSET, 5U), /*!< stop condition detected in slave mode interrupt flag */ + I2C_ADD_INT_FLAG_TC = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 6U, I2C_ADD_STAT_REG_OFFSET, 6U), /*!< transfer complete in master mode interrupt flag */ + I2C_ADD_INT_FLAG_TCR = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 6U, I2C_ADD_STAT_REG_OFFSET, 7U), /*!< transfer complete reload interrupt flag */ + I2C_ADD_INT_FLAG_BERR = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 7U, I2C_ADD_STAT_REG_OFFSET, 8U), /*!< bus error interrupt flag */ + I2C_ADD_INT_FLAG_LOSTARB = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 7U, I2C_ADD_STAT_REG_OFFSET, 9U), /*!< arbitration lost interrupt flag */ + I2C_ADD_INT_FLAG_OUERR = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 7U, I2C_ADD_STAT_REG_OFFSET, 10U), /*!< overrun/underrun error in slave mode interrupt flag */ + I2C_ADD_INT_FLAG_PECERR = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 7U, I2C_ADD_STAT_REG_OFFSET, 11U), /*!< PEC error interrupt flag */ + I2C_ADD_INT_FLAG_TIMEOUT = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 7U, I2C_ADD_STAT_REG_OFFSET, 12U), /*!< timeout interrupt flag */ + I2C_ADD_INT_FLAG_SMBALT = I2C_ADD_REGIDX_BIT2(I2C_ADD_CTL0_REG_OFFSET, 7U, I2C_ADD_STAT_REG_OFFSET, 13U) /*!< SMBus Alert interrupt flag */ +} i2c_add_interrupt_flag_enum; + +/* I2C DMA constants definitions */ +#define I2C_ADD_DMA_TRANSMIT ((uint32_t)0x00000000U) /*!< I2C transmit data use DMA */ +#define I2C_ADD_DMA_RECEIVE ((uint32_t)0x00000001U) /*!< I2C receive data use DMA */ + +/* I2C interrupt enable or disable */ +#define I2C_ADD_INT_ERR I2C_ADD_CTL0_ERRIE /*!< error interrupt enable */ +#define I2C_ADD_INT_TC I2C_ADD_CTL0_TCIE /*!< transfer complete interrupt enable */ +#define I2C_ADD_INT_STPDET I2C_ADD_CTL0_STPDETIE /*!< stop detection interrupt enable */ +#define I2C_ADD_INT_NACK I2C_ADD_CTL0_NACKIE /*!< not acknowledge received interrupt enable */ +#define I2C_ADD_INT_ADDM I2C_ADD_CTL0_ADDMIE /*!< address match interrupt enable */ +#define I2C_ADD_INT_RBNE I2C_ADD_CTL0_RBNEIE /*!< receive interrupt enable */ +#define I2C_ADD_INT_TI I2C_ADD_CTL0_TIE /*!< transmit interrupt enable */ + +/* I2C transfer direction in master mode */ +#define I2C_ADD_MASTER_TRANSMIT ((uint32_t)0x00000000U) /*!< I2C master transmit */ +#define I2C_ADD_MASTER_RECEIVE I2C_ADD_CTL1_TRDIR /*!< I2C master receive */ + +/* address mode for the I2C slave */ +#define I2C_ADD_ADDFORMAT_7BITS ((uint32_t)0x00000000U) /*!< address:7 bits */ +#define I2C_ADD_ADDFORMAT_10BITS I2C_ADD_SADDR0_ADDFORMAT /*!< address:10 bits */ + +/* the length of filter spikes */ +#define FILTER_DISABLE ((uint32_t)0x00000000U) /*!< digital filter is disabled */ +#define FILTER_LENGTH_1 ((uint32_t)0x00000001U) /*!< digital filter is enabled and filter spikes with a length of up to 1 tI2CCLK */ +#define FILTER_LENGTH_2 ((uint32_t)0x00000002U) /*!< digital filter is enabled and filter spikes with a length of up to 2 tI2CCLK */ +#define FILTER_LENGTH_3 ((uint32_t)0x00000003U) /*!< digital filter is enabled and filter spikes with a length of up to 3 tI2CCLK */ +#define FILTER_LENGTH_4 ((uint32_t)0x00000004U) /*!< digital filter is enabled and filter spikes with a length of up to 4 tI2CCLK */ +#define FILTER_LENGTH_5 ((uint32_t)0x00000005U) /*!< digital filter is enabled and filter spikes with a length of up to 5 tI2CCLK */ +#define FILTER_LENGTH_6 ((uint32_t)0x00000006U) /*!< digital filter is enabled and filter spikes with a length of up to 6 tI2CCLK */ +#define FILTER_LENGTH_7 ((uint32_t)0x00000007U) /*!< digital filter is enabled and filter spikes with a length of up to 7 tI2CCLK */ +#define FILTER_LENGTH_8 ((uint32_t)0x00000008U) /*!< digital filter is enabled and filter spikes with a length of up to 8 tI2CCLK */ +#define FILTER_LENGTH_9 ((uint32_t)0x00000009U) /*!< digital filter is enabled and filter spikes with a length of up to 9 tI2CCLK */ +#define FILTER_LENGTH_10 ((uint32_t)0x0000000AU) /*!< digital filter is enabled and filter spikes with a length of up to 10 tI2CCLK */ +#define FILTER_LENGTH_11 ((uint32_t)0x0000000BU) /*!< digital filter is enabled and filter spikes with a length of up to 11 tI2CCLK */ +#define FILTER_LENGTH_12 ((uint32_t)0x0000000CU) /*!< digital filter is enabled and filter spikes with a length of up to 12 tI2CCLK */ +#define FILTER_LENGTH_13 ((uint32_t)0x0000000DU) /*!< digital filter is enabled and filter spikes with a length of up to 13 tI2CCLK */ +#define FILTER_LENGTH_14 ((uint32_t)0x0000000EU) /*!< digital filter is enabled and filter spikes with a length of up to 14 tI2CCLK */ +#define FILTER_LENGTH_15 ((uint32_t)0x0000000FU) /*!< digital filter is enabled and filter spikes with a length of up to 15 tI2CCLK */ + +/* defines which bits of register ADDRESS[7:1] are compared with an incoming address byte */ +#define ADDRESS_BIT1_COMPARE ((uint32_t)0x00000200U) /*!< address bit1 needs compare */ +#define ADDRESS_BIT2_COMPARE ((uint32_t)0x00000400U) /*!< address bit2 needs compare */ +#define ADDRESS_BIT3_COMPARE ((uint32_t)0x00000800U) /*!< address bit3 needs compare */ +#define ADDRESS_BIT4_COMPARE ((uint32_t)0x00001000U) /*!< address bit4 needs compare */ +#define ADDRESS_BIT5_COMPARE ((uint32_t)0x00002000U) /*!< address bit5 needs compare */ +#define ADDRESS_BIT6_COMPARE ((uint32_t)0x00004000U) /*!< address bit6 needs compare */ +#define ADDRESS_BIT7_COMPARE ((uint32_t)0x00008000U) /*!< address bit7 needs compare */ + +/* defines which bits of ADDRESS2[7:1] are compared with an incoming address byte, and which bits are masked (don??t care) */ +#define ADDRESS2_NO_MASK ((uint32_t)0x00000000U) /*!< no mask, all the bits must be compared */ +#define ADDRESS2_MASK_BIT1 ((uint32_t)0x00000001U) /*!< ADDRESS2[1] is masked, only ADDRESS2[7:2] are compared */ +#define ADDRESS2_MASK_BIT1_2 ((uint32_t)0x00000002U) /*!< ADDRESS2[2:1] is masked, only ADDRESS2[7:3] are compared */ +#define ADDRESS2_MASK_BIT1_3 ((uint32_t)0x00000003U) /*!< ADDRESS2[3:1] is masked, only ADDRESS2[7:4] are compared */ +#define ADDRESS2_MASK_BIT1_4 ((uint32_t)0x00000004U) /*!< ADDRESS2[4:1] is masked, only ADDRESS2[7:5] are compared */ +#define ADDRESS2_MASK_BIT1_5 ((uint32_t)0x00000005U) /*!< ADDRESS2[5:1] is masked, only ADDRESS2[7:6] are compared */ +#define ADDRESS2_MASK_BIT1_6 ((uint32_t)0x00000006U) /*!< ADDRESS2[6:1] is masked, only ADDRESS2[7] are compared */ +#define ADDRESS2_MASK_ALL ((uint32_t)0x00000007U) /*!< all the ADDRESS2[7:1] bits are masked */ + +/* idle clock timeout detection */ +#define BUSTOA_DETECT_SCL_LOW ((uint32_t)0x00000000U) /*!< BUSTOA is used to detect SCL low timeout */ +#define BUSTOA_DETECT_IDLE I2C_ADD_TIMEOUT_TOIDLE /*!< BUSTOA is used to detect both SCL and SDA high timeout when the bus is idle */ + +/* I2C flag definitions */ +#define I2C_ADD_FLAG_TBE I2C_ADD_STAT_TBE /*!< I2C_ADD_TDATA is empty during transmitting */ +#define I2C_ADD_FLAG_TI I2C_ADD_STAT_TI /*!< transmit interrupt */ +#define I2C_ADD_FLAG_RBNE I2C_ADD_STAT_RBNE /*!< I2C_ADD_RDATA is not empty during receiving */ +#define I2C_ADD_FLAG_ADDSEND I2C_ADD_STAT_ADDSEND /*!< address received matches in slave mode */ +#define I2C_ADD_FLAG_NACK I2C_ADD_STAT_NACK /*!< not acknowledge flag */ +#define I2C_ADD_FLAG_STPDET I2C_ADD_STAT_STPDET /*!< STOP condition detected in slave mode */ +#define I2C_ADD_FLAG_TC I2C_ADD_STAT_TC /*!< transfer complete in master mode */ +#define I2C_ADD_FLAG_TCR I2C_ADD_STAT_TCR /*!< transfer complete reload */ +#define I2C_ADD_FLAG_BERR I2C_ADD_STAT_BERR /*!< bus error */ +#define I2C_ADD_FLAG_LOSTARB I2C_ADD_STAT_LOSTARB /*!< arbitration lost */ +#define I2C_ADD_FLAG_OUERR I2C_ADD_STAT_OUERR /*!< overrun/underrun error in slave mode */ +#define I2C_ADD_FLAG_PECERR I2C_ADD_STAT_PECERR /*!< PEC error */ +#define I2C_ADD_FLAG_TIMEOUT I2C_ADD_STAT_TIMEOUT /*!< timeout flag */ +#define I2C_ADD_FLAG_SMBALT I2C_ADD_STAT_SMBALT /*!< SMBus Alert */ +#define I2C_ADD_FLAG_I2CBSY I2C_ADD_STAT_I2CBSY /*!< busy flag */ +#define I2C_ADD_FLAG_TR I2C_ADD_STAT_TR /*!< whether the I2C is a transmitter or a receiver in slave mode */ + +/* function declarations */ +/* initialization functions */ +/* reset I2C */ +void i2c_add_deinit(uint32_t i2c_add_periph); +/* configure the timing parameters */ +void i2c_add_timing_config(uint32_t i2c_add_periph, uint32_t psc, uint32_t scl_dely, uint32_t sda_dely); +/* configure digital noise filter */ +void i2c_add_digital_noise_filter_config(uint32_t i2c_add_periph, uint32_t filter_length); +/* enable analog noise filter */ +void i2c_add_analog_noise_filter_enable(uint32_t i2c_add_periph); +/* disable analog noise filter */ +void i2c_add_analog_noise_filter_disable(uint32_t i2c_add_periph); +/* configure the SCL high and low period of clock in master mode */ +void i2c_add_master_clock_config(uint32_t i2c_add_periph, uint32_t sclh, uint32_t scll); +/* configure i2c slave address and transfer direction in master mode */ +void i2c_add_master_addressing(uint32_t i2c_add_periph, uint32_t address, uint32_t trans_direction); + +/* application function declarations */ +/* 10-bit address header executes read direction only in master receive mode */ +void i2c_add_address10_header_enable(uint32_t i2c_add_periph); +/* 10-bit address header executes complete sequence in master receive mode */ +void i2c_add_address10_header_disable(uint32_t i2c_add_periph); +/* enable 10-bit addressing mode in master mode */ +void i2c_add_address10_enable(uint32_t i2c_add_periph); +/* disable 10-bit addressing mode in master mode */ +void i2c_add_address10_disable(uint32_t i2c_add_periph); +/* enable I2C automatic end mode in master mode */ +void i2c_add_automatic_end_enable(uint32_t i2c_add_periph); +/* disable I2C automatic end mode in master mode */ +void i2c_add_automatic_end_disable(uint32_t i2c_add_periph); +/* enable the response to a general call */ +void i2c_add_slave_response_to_gcall_enable(uint32_t i2c_add_periph); +/* disable the response to a general call */ +void i2c_add_slave_response_to_gcall_disable(uint32_t i2c_add_periph); +/* enable to stretch SCL low when data is not ready in slave mode */ +void i2c_add_stretch_scl_low_enable(uint32_t i2c_add_periph); +/* disable to stretch SCL low when data is not ready in slave mode */ +void i2c_add_stretch_scl_low_disable(uint32_t i2c_add_periph); +/* configure i2c slave address */ +void i2c_add_address_config(uint32_t i2c_add_periph, uint32_t address, uint32_t addr_format); +/* define which bits of ADDRESS[7:1] need to compare with the incoming address byte */ +void i2c_add_address_bit_compare_config(uint32_t i2c_add_periph, uint32_t compare_bits); +/* disable i2c address in slave mode */ +void i2c_add_address_disable(uint32_t i2c_add_periph); +/* configure i2c second slave address */ +void i2c_add_second_address_config(uint32_t i2c_add_periph, uint32_t address, uint32_t addr_mask); +/* disable i2c second address in slave mode */ +void i2c_add_second_address_disable(uint32_t i2c_add_periph); +/* get received match address in slave mode */ +uint32_t i2c_add_recevied_address_get(uint32_t i2c_add_periph); +/* enable slave byte control */ +void i2c_add_slave_byte_control_enable(uint32_t i2c_add_periph); +/* disable slave byte control */ +void i2c_add_slave_byte_control_disable(uint32_t i2c_add_periph); +/* generate a NACK in slave mode */ +void i2c_add_nack_enable(uint32_t i2c_add_periph); +/* generate an ACK in slave mode */ +void i2c_add_nack_disable(uint32_t i2c_add_periph); +/* enable wakeup from deep-sleep mode */ +void i2c_add_wakeup_from_deepsleep_enable(uint32_t i2c_add_periph); +/* disable wakeup from deep-sleep mode */ +void i2c_add_wakeup_from_deepsleep_disable(uint32_t i2c_add_periph); +/* enable I2C */ +void i2c_add_enable(uint32_t i2c_add_periph); +/* disable I2C */ +void i2c_add_disable(uint32_t i2c_add_periph); +/* generate a START condition on I2C bus */ +void i2c_add_start_on_bus(uint32_t i2c_add_periph); +/* generate a STOP condition on I2C bus */ +void i2c_add_stop_on_bus(uint32_t i2c_add_periph); +/* I2C transmit data */ +void i2c_add_data_transmit(uint32_t i2c_add_periph, uint32_t data); +/* I2C receive data */ +uint32_t i2c_add_data_receive(uint32_t i2c_add_periph); +/* enable I2C reload mode */ +void i2c_add_reload_enable(uint32_t i2c_add_periph); +/* disable I2C reload mode */ +void i2c_add_reload_disable(uint32_t i2c_add_periph); +/* configure number of bytes to be transferred */ +void i2c_add_transfer_byte_number_config(uint32_t i2c_add_periph, uint32_t byte_number); +/* enable I2C DMA for transmission or reception */ +void i2c_add_dma_enable(uint32_t i2c_add_periph, uint8_t dma); +/* disable I2C DMA for transmission or reception */ +void i2c_add_dma_disable(uint32_t i2c_add_periph, uint8_t dma); +/* I2C transfers PEC value */ +void i2c_add_pec_transfer(uint32_t i2c_add_periph); +/* enable I2C PEC calculation */ +void i2c_add_pec_enable(uint32_t i2c_add_periph); +/* disable I2C PEC calculation */ +void i2c_add_pec_disable(uint32_t i2c_add_periph); +/* get packet error checking value */ +uint32_t i2c_add_pec_value_get(uint32_t i2c_add_periph); +/* enable SMBus alert */ +void i2c_add_smbus_alert_enable(uint32_t i2c_add_periph); +/* disable SMBus alert */ +void i2c_add_smbus_alert_disable(uint32_t i2c_add_periph); +/* enable SMBus device default address */ +void i2c_add_smbus_default_addr_enable(uint32_t i2c_add_periph); +/* disable SMBus device default address */ +void i2c_add_smbus_default_addr_disable(uint32_t i2c_add_periph); +/* enable SMBus host address */ +void i2c_add_smbus_host_addr_enable(uint32_t i2c_add_periph); +/* disable SMBus host address */ +void i2c_add_smbus_host_addr_disable(uint32_t i2c_add_periph); +/* enable extended clock timeout detection */ +void i2c_add_extented_clock_timeout_enable(uint32_t i2c_add_periph); +/* disable extended clock timeout detection */ +void i2c_add_extented_clock_timeout_disable(uint32_t i2c_add_periph); +/* enable clock timeout detection */ +void i2c_add_clock_timeout_enable(uint32_t i2c_add_periph); +/* disable clock timeout detection */ +void i2c_add_clock_timeout_disable(uint32_t i2c_add_periph); +/* configure bus timeout B */ +void i2c_add_bus_timeout_b_config(uint32_t i2c_add_periph, uint32_t timeout); +/* configure bus timeout A */ +void i2c_add_bus_timeout_a_config(uint32_t i2c_add_periph, uint32_t timeout); +/* configure idle clock timeout detection */ +void i2c_add_idle_clock_timeout_config(uint32_t i2c_add_periph, uint32_t timeout); + +/* interrupt & flag functions */ +/* get I2C flag status */ +FlagStatus i2c_add_flag_get(uint32_t i2c_add_periph, uint32_t flag); +/* clear I2C flag status */ +void i2c_add_flag_clear(uint32_t i2c_add_periph, uint32_t flag); +/* enable I2C interrupt */ +void i2c_add_interrupt_enable(uint32_t i2c_add_periph, uint32_t interrupt); +/* disable I2C interrupt */ +void i2c_add_interrupt_disable(uint32_t i2c_add_periph, uint32_t interrupt); +/* get I2C interrupt flag status */ +FlagStatus i2c_add_interrupt_flag_get(uint32_t i2c_add_periph, i2c_add_interrupt_flag_enum int_flag); +/* clear I2C interrupt flag status */ +void i2c_add_interrupt_flag_clear(uint32_t i2c_add_periph, i2c_add_interrupt_flag_enum int_flag); + +#endif /* GD32F5XX_I2C_ADD_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_ipa.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_ipa.h new file mode 100644 index 0000000..dfb2653 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_ipa.h @@ -0,0 +1,378 @@ +/*! + \file gd32f5xx_ipa.h + \brief definitions for the IPA + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_IPA_H +#define GD32F5XX_IPA_H + +#include "gd32f5xx.h" + +/* IPA definitions */ +#define IPA IPA_BASE /*!< IPA base address */ + +/* bits definitions */ +/* registers definitions */ +#define IPA_CTL REG32(IPA + 0x00000000U) /*!< IPA control register */ +#define IPA_INTF REG32(IPA + 0x00000004U) /*!< IPA interrupt flag register */ +#define IPA_INTC REG32(IPA + 0x00000008U) /*!< IPA interrupt flag clear register */ +#define IPA_FMADDR REG32(IPA + 0x0000000CU) /*!< IPA foreground memory base address register */ +#define IPA_FLOFF REG32(IPA + 0x00000010U) /*!< IPA foreground line offset register */ +#define IPA_BMADDR REG32(IPA + 0x00000014U) /*!< IPA background memory base address register */ +#define IPA_BLOFF REG32(IPA + 0x00000018U) /*!< IPA background line offset register */ +#define IPA_FPCTL REG32(IPA + 0x0000001CU) /*!< IPA foreground pixel control register */ +#define IPA_FPV REG32(IPA + 0x00000020U) /*!< IPA foreground pixel value register */ +#define IPA_BPCTL REG32(IPA + 0x00000024U) /*!< IPA background pixel control register */ +#define IPA_BPV REG32(IPA + 0x00000028U) /*!< IPA background pixel value register */ +#define IPA_FLMADDR REG32(IPA + 0x0000002CU) /*!< IPA foreground LUT memory base address register */ +#define IPA_BLMADDR REG32(IPA + 0x00000030U) /*!< IPA background LUT memory base address register */ +#define IPA_DPCTL REG32(IPA + 0x00000034U) /*!< IPA destination pixel control register */ +#define IPA_DPV REG32(IPA + 0x00000038U) /*!< IPA destination pixel value register */ +#define IPA_DMADDR REG32(IPA + 0x0000003CU) /*!< IPA destination memory base address register */ +#define IPA_DLOFF REG32(IPA + 0x00000040U) /*!< IPA destination line offset register */ +#define IPA_IMS REG32(IPA + 0x00000044U) /*!< IPA image size register */ +#define IPA_LM REG32(IPA + 0x00000048U) /*!< IPA line mark register */ +#define IPA_ITCTL REG32(IPA + 0x0000004CU) /*!< IPA inter-timer control register */ + +/* IPA_CTL */ +#define IPA_CTL_TEN BIT(0) /*!< transfer enable */ +#define IPA_CTL_THU BIT(1) /*!< transfer hang up */ +#define IPA_CTL_TST BIT(2) /*!< transfer stop */ +#define IPA_CTL_TAEIE BIT(8) /*!< enable bit for transfer access error interrupt */ +#define IPA_CTL_FTFIE BIT(9) /*!< enable bit for full transfer finish interrup */ +#define IPA_CTL_TLMIE BIT(10) /*!< enable bit for transfer line mark interrupt */ +#define IPA_CTL_LACIE BIT(11) /*!< enable bit for LUT access conflict interrupt */ +#define IPA_CTL_LLFIE BIT(12) /*!< enable bit for LUT loading finish interrupt */ +#define IPA_CTL_WCFIE BIT(13) /*!< enable bit for wrong configuration interrupt */ +#define IPA_CTL_PFCM BITS(16,17) /*!< pixel format convert mode */ + +/* IPA_INTF */ +#define IPA_INTF_TAEIF BIT(0) /*!< transfer access error interrupt flag */ +#define IPA_INTF_FTFIF BIT(1) /*!< full transfer finish interrupt flag */ +#define IPA_INTF_TLMIF BIT(2) /*!< transfer line mark interrupt flag */ +#define IPA_INTF_LACIF BIT(3) /*!< LUT access conflict interrupt flag */ +#define IPA_INTF_LLFIF BIT(4) /*!< LUT loading finish interrupt flag */ +#define IPA_INTF_WCFIF BIT(5) /*!< wrong configuration interrupt flag */ + +/* IPA_INTC */ +#define IPA_INTC_TAEIFC BIT(0) /*!< clear bit for transfer access error interrupt flag */ +#define IPA_INTC_FTFIFC BIT(1) /*!< clear bit for full transfer finish interrupt flag */ +#define IPA_INTC_TLMIFC BIT(2) /*!< clear bit for transfer line mark interrupt flag */ +#define IPA_INTC_LACIFC BIT(3) /*!< clear bit for LUT access conflict interrupt flag */ +#define IPA_INTC_LLFIFC BIT(4) /*!< clear bit for LUT loading finish interrupt flag */ +#define IPA_INTC_WCFIFC BIT(5) /*!< clear bit for wrong configuration interrupt flag */ + +/* IPA_FMADDR */ +#define IPA_FMADDR_FMADDR BITS(0,31) /*!< foreground memory base address */ + +/* IPA_FLOFF */ +#define IPA_FLOFF_FLOFF BITS(0,13) /*!< foreground line offset */ + +/* IPA_BMADDR */ +#define IPA_BMADDR_BMADDR BITS(0,31) /*!< background memory base address */ + +/* IPA_BLOFF */ +#define IPA_BLOFF_BLOFF BITS(0,13) /*!< background line offset */ + +/* IPA_FPCTL */ +#define IPA_FPCTL_FPF BITS(0,3) /*!< foreground pixel format */ +#define IPA_FPCTL_FLPF BIT(4) /*!< foreground LUT pixel format */ +#define IPA_FPCTL_FLLEN BIT(5) /*!< foreground LUT loading enable */ +#define IPA_FPCTL_FCNP BITS(8,15) /*!< foreground LUT number of pixel */ +#define IPA_FPCTL_FAVCA BITS(16,17) /*!< foreground alpha value calculation algorithm */ +#define IPA_FPCTL_FPDAV BITS(24,31) /*!< foreground pre- defined alpha value */ + +/* IPA_FPV */ +#define IPA_FPV_FPDBV BITS(0,7) /*!< foreground pre-defined red value */ +#define IPA_FPV_FPDGV BITS(8,15) /*!< foreground pre-defined green value */ +#define IPA_FPV_FPDRV BITS(16,23) /*!< foreground pre-defined red value */ + +/* IPA_BPCTL */ +#define IPA_BPCTL_BPF BITS(0,3) /*!< background pixel format */ +#define IPA_BPCTL_BLPF BIT(4) /*!< background LUT pixel format */ +#define IPA_BPCTL_BLLEN BIT(5) /*!< background LUT loading enable */ +#define IPA_BPCTL_BCNP BITS(8,15) /*!< background LUT number of pixel */ +#define IPA_BPCTL_BAVCA BITS(16,17) /*!< background alpha value calculation algorithm */ +#define IPA_BPCTL_BPDAV BITS(24,31) /*!< background pre- defined alpha value */ + +/* IPA_BPV */ +#define IPA_BPV_BPDBV BITS(0,7) /*!< background pre-defined blue value */ +#define IPA_BPV_BPDGV BITS(8,15) /*!< background pre-defined green value */ +#define IPA_BPV_BPDRV BITS(16,23) /*!< background pre-defined red value */ + +/* IPA_FLMADDR */ +#define IPA_FLMADDR_FLMADDR BITS(0,31) /*!< foreground LUT memory base address */ + +/* IPA_BLMADDR */ +#define IPA_BLMADDR_BLMADDR BITS(0,31) /*!< background LUT memory base address */ + +/* IPA_DPCTL */ +#define IPA_DPCTL_DPF BITS(0,2) /*!< destination pixel control register */ + +/* IPA_DPV */ +/* destination pixel format ARGB8888 */ +#define IPA_DPV_DPDBV_0 BITS(0,7) /*!< destination pre-defined blue value */ +#define IPA_DPV_DPDGV_0 BITS(8,15) /*!< destination pre-defined green value */ +#define IPA_DPV_DPDRV_0 BITS(16,23) /*!< destination pre-defined red value */ +#define IPA_DPV_DPDAV_0 BITS(24,31) /*!< destination pre-defined alpha value */ + +/* destination pixel format RGB8888 */ +#define IPA_DPV_DPDBV_1 BITS(0,7) /*!< destination pre-defined blue value */ +#define IPA_DPV_DPDGV_1 BITS(8,15) /*!< destination pre-defined green value */ +#define IPA_DPV_DPDRV_1 BITS(16,23) /*!< destination pre-defined red value */ + +/* destination pixel format RGB565 */ +#define IPA_DPV_DPDBV_2 BITS(0,4) /*!< destination pre-defined blue value */ +#define IPA_DPV_DPDGV_2 BITS(5,10) /*!< destination pre-defined green value */ +#define IPA_DPV_DPDRV_2 BITS(11,15) /*!< destination pre-defined red value */ + +/* destination pixel format ARGB1555 */ +#define IPA_DPV_DPDBV_3 BITS(0,4) /*!< destination pre-defined blue value */ +#define IPA_DPV_DPDGV_3 BITS(5,9) /*!< destination pre-defined green value */ +#define IPA_DPV_DPDRV_3 BITS(10,14) /*!< destination pre-defined red value */ +#define IPA_DPV_DPDAV_3 BIT(15) /*!< destination pre-defined alpha value */ + +/* destination pixel format ARGB4444 */ +#define IPA_DPV_DPDBV_4 BITS(0,3) /*!< destination pre-defined blue value */ +#define IPA_DPV_DPDGV_4 BITS(4,7) /*!< destination pre-defined green value */ +#define IPA_DPV_DPDRV_4 BITS(8,11) /*!< destination pre-defined red value */ +#define IPA_DPV_DPDAV_4 BITS(12,15) /*!< destination pre-defined alpha value */ + +/* IPA_DMADDR */ +#define IPA_DMADDR_DMADDR BITS(0,31) /*!< destination memory base address */ + +/* IPA_DLOFF */ +#define IPA_DLOFF_DLOFF BITS(0,13) /*!< destination line offset */ + +/* IPA_IMS */ +#define IPA_IMS_HEIGHT BITS(0,15) /*!< height of the image to be processed */ +#define IPA_IMS_WIDTH BITS(16,29) /*!< width of the image to be processed */ + +/* IPA_LM */ +#define IPA_LM_LM BITS(0,15) /*!< line mark */ + +/* IPA_ITCTL */ +#define IPA_ITCTL_ITEN BIT(0) /*!< inter-timer enable */ +#define IPA_ITCTL_NCCI BITS(8,15) /*!< number of clock cycles interval */ + + +/* constants definitions */ +/* IPA foreground parameter struct definitions */ +typedef struct { + uint32_t foreground_memaddr; /*!< foreground memory base address */ + uint32_t foreground_lineoff; /*!< foreground line offset */ + uint32_t foreground_prealpha; /*!< foreground pre-defined alpha value */ + uint32_t foreground_alpha_algorithm; /*!< foreground alpha value calculation algorithm */ + uint32_t foreground_pf; /*!< foreground pixel format */ + uint32_t foreground_prered; /*!< foreground pre-defined red value */ + uint32_t foreground_pregreen; /*!< foreground pre-defined green value */ + uint32_t foreground_preblue; /*!< foreground pre-defined blue value */ +} ipa_foreground_parameter_struct; + +/* IPA background parameter struct definitions */ +typedef struct { + uint32_t background_memaddr; /*!< background memory base address */ + uint32_t background_lineoff; /*!< background line offset */ + uint32_t background_prealpha; /*!< background pre-defined alpha value */ + uint32_t background_alpha_algorithm; /*!< background alpha value calculation algorithm */ + uint32_t background_pf; /*!< background pixel format */ + uint32_t background_prered; /*!< background pre-defined red value */ + uint32_t background_pregreen; /*!< background pre-defined green value */ + uint32_t background_preblue; /*!< background pre-defined blue value */ +} ipa_background_parameter_struct; + +/* IPA destination parameter struct definitions */ +typedef struct { + uint32_t destination_memaddr; /*!< destination memory base address */ + uint32_t destination_lineoff; /*!< destination line offset */ + uint32_t destination_prealpha; /*!< destination pre-defined alpha value */ + uint32_t destination_pf; /*!< destination pixel format */ + uint32_t destination_prered; /*!< destination pre-defined red value */ + uint32_t destination_pregreen; /*!< destination pre-defined green value */ + uint32_t destination_preblue; /*!< destination pre-defined blue value */ + uint32_t image_width; /*!< width of the image to be processed */ + uint32_t image_height; /*!< height of the image to be processed */ +} ipa_destination_parameter_struct; + +/* destination pixel format */ +typedef enum { + IPA_DPF_ARGB8888, /*!< destination pixel format ARGB8888 */ + IPA_DPF_RGB888, /*!< destination pixel format RGB888 */ + IPA_DPF_RGB565, /*!< destination pixel format RGB565 */ + IPA_DPF_ARGB1555, /*!< destination pixel format ARGB1555 */ + IPA_DPF_ARGB4444 /*!< destination pixel format ARGB4444 */ +} ipa_dpf_enum; + +/* LUT pixel format */ +#define IPA_LUT_PF_ARGB8888 ((uint8_t)0x00U) /*!< LUT pixel format ARGB8888 */ +#define IPA_LUT_PF_RGB888 ((uint8_t)0x01U) /*!< LUT pixel format RGB888 */ + +/* Inter-timer */ +#define IPA_INTER_TIMER_DISABLE ((uint8_t)0x00U) /*!< inter-timer disable */ +#define IPA_INTER_TIMER_ENABLE ((uint8_t)0x01U) /*!< inter-timer enable */ + +/* IPA pixel format convert mode */ +#define CTL_PFCM(regval) (BITS(16,17) & ((uint32_t)(regval) << 16)) +#define IPA_FGTODE CTL_PFCM(0) /*!< foreground memory to destination memory without pixel format convert */ +#define IPA_FGTODE_PF_CONVERT CTL_PFCM(1) /*!< foreground memory to destination memory with pixel format convert */ +#define IPA_FGBGTODE CTL_PFCM(2) /*!< blending foreground and background memory to destination memory */ +#define IPA_FILL_UP_DE CTL_PFCM(3) /*!< fill up destination memory with specific color */ + +/* foreground alpha value calculation algorithm */ +#define FPCTL_FAVCA(regval) (BITS(16,17) & ((uint32_t)(regval) << 16)) +#define IPA_FG_ALPHA_MODE_0 FPCTL_FAVCA(0) /*!< no effect */ +#define IPA_FG_ALPHA_MODE_1 FPCTL_FAVCA(1) /*!< FPDAV[7:0] is selected as the foreground alpha value */ +#define IPA_FG_ALPHA_MODE_2 FPCTL_FAVCA(2) /*!< FPDAV[7:0] multiplied by read alpha value */ + +/* background alpha value calculation algorithm */ +#define BPCTL_BAVCA(regval) (BITS(16,17) & ((uint32_t)(regval) << 16)) +#define IPA_BG_ALPHA_MODE_0 BPCTL_BAVCA(0) /*!< no effect */ +#define IPA_BG_ALPHA_MODE_1 BPCTL_BAVCA(1) /*!< BPDAV[7:0] is selected as the background alpha value */ +#define IPA_BG_ALPHA_MODE_2 BPCTL_BAVCA(2) /*!< BPDAV[7:0] multiplied by read alpha value */ + +/* foreground pixel format */ +#define FPCTL_PPF(regval) (BITS(0,3) & ((uint32_t)(regval))) +#define FOREGROUND_PPF_ARGB8888 FPCTL_PPF(0) /*!< foreground pixel format ARGB8888 */ +#define FOREGROUND_PPF_RGB888 FPCTL_PPF(1) /*!< foreground pixel format RGB888 */ +#define FOREGROUND_PPF_RGB565 FPCTL_PPF(2) /*!< foreground pixel format RGB565 */ +#define FOREGROUND_PPF_ARG1555 FPCTL_PPF(3) /*!< foreground pixel format ARGB1555 */ +#define FOREGROUND_PPF_ARGB4444 FPCTL_PPF(4) /*!< foreground pixel format ARGB4444 */ +#define FOREGROUND_PPF_L8 FPCTL_PPF(5) /*!< foreground pixel format L8 */ +#define FOREGROUND_PPF_AL44 FPCTL_PPF(6) /*!< foreground pixel format AL44 */ +#define FOREGROUND_PPF_AL88 FPCTL_PPF(7) /*!< foreground pixel format AL88 */ +#define FOREGROUND_PPF_L4 FPCTL_PPF(8) /*!< foreground pixel format L4 */ +#define FOREGROUND_PPF_A8 FPCTL_PPF(9) /*!< foreground pixel format A8 */ +#define FOREGROUND_PPF_A4 FPCTL_PPF(10) /*!< foreground pixel format A4 */ + +/* background pixel format */ +#define BPCTL_PPF(regval) (BITS(0,3) & ((uint32_t)(regval))) +#define BACKGROUND_PPF_ARGB8888 BPCTL_PPF(0) /*!< background pixel format ARGB8888 */ +#define BACKGROUND_PPF_RGB888 BPCTL_PPF(1) /*!< background pixel format RGB888 */ +#define BACKGROUND_PPF_RGB565 BPCTL_PPF(2) /*!< background pixel format RGB565 */ +#define BACKGROUND_PPF_ARG1555 BPCTL_PPF(3) /*!< background pixel format ARGB1555 */ +#define BACKGROUND_PPF_ARGB4444 BPCTL_PPF(4) /*!< background pixel format ARGB4444 */ +#define BACKGROUND_PPF_L8 BPCTL_PPF(5) /*!< background pixel format L8 */ +#define BACKGROUND_PPF_AL44 BPCTL_PPF(6) /*!< background pixel format AL44 */ +#define BACKGROUND_PPF_AL88 BPCTL_PPF(7) /*!< background pixel format AL88 */ +#define BACKGROUND_PPF_L4 BPCTL_PPF(8) /*!< background pixel format L4 */ +#define BACKGROUND_PPF_A8 BPCTL_PPF(9) /*!< background pixel format A8 */ +#define BACKGROUND_PPF_A4 BPCTL_PPF(10) /*!< background pixel format A4 */ + +/* IPA flags */ +#define IPA_FLAG_TAE IPA_INTF_TAEIF /*!< transfer access error interrupt flag */ +#define IPA_FLAG_FTF IPA_INTF_FTFIF /*!< full transfer finish interrupt flag */ +#define IPA_FLAG_TLM IPA_INTF_TLMIF /*!< transfer line mark interrupt flag */ +#define IPA_FLAG_LAC IPA_INTF_LACIF /*!< LUT access conflict interrupt flag */ +#define IPA_FLAG_LLF IPA_INTF_LLFIF /*!< LUT loading finish interrupt flag */ +#define IPA_FLAG_WCF IPA_INTF_WCFIF /*!< wrong configuration interrupt flag */ + +/* IPA interrupt enable or disable */ +#define IPA_INT_TAE IPA_CTL_TAEIE /*!< transfer access error interrupt */ +#define IPA_INT_FTF IPA_CTL_FTFIE /*!< full transfer finish interrupt */ +#define IPA_INT_TLM IPA_CTL_TLMIE /*!< transfer line mark interrupt */ +#define IPA_INT_LAC IPA_CTL_LACIE /*!< LUT access conflict interrupt */ +#define IPA_INT_LLF IPA_CTL_LLFIE /*!< LUT loading finish interrupt */ +#define IPA_INT_WCF IPA_CTL_WCFIE /*!< wrong configuration interrupt */ + +/* IPA interrupt flags */ +#define IPA_INT_FLAG_TAE IPA_INTF_TAEIF /*!< transfer access error interrupt flag */ +#define IPA_INT_FLAG_FTF IPA_INTF_FTFIF /*!< full transfer finish interrupt flag */ +#define IPA_INT_FLAG_TLM IPA_INTF_TLMIF /*!< transfer line mark interrupt flag */ +#define IPA_INT_FLAG_LAC IPA_INTF_LACIF /*!< LUT access conflict interrupt flag */ +#define IPA_INT_FLAG_LLF IPA_INTF_LLFIF /*!< LUT loading finish interrupt flag */ +#define IPA_INT_FLAG_WCF IPA_INTF_WCFIF /*!< wrong configuration interrupt flag */ + +/* function declarations */ +/* functions enable or disable, pixel format convert mode set */ +/* deinitialize IPA */ +void ipa_deinit(void); +/* enable IPA transfer */ +void ipa_transfer_enable(void); +/* enable IPA transfer hang up */ +void ipa_transfer_hangup_enable(void); +/* disable IPA transfer hang up */ +void ipa_transfer_hangup_disable(void); +/* enable IPA transfer stop */ +void ipa_transfer_stop_enable(void); +/* disable IPA transfer stop */ +void ipa_transfer_stop_disable(void); +/* enable IPA foreground LUT loading */ +void ipa_foreground_lut_loading_enable(void); +/* enable IPA background LUT loading */ +void ipa_background_lut_loading_enable(void); +/* set pixel format convert mode, the function is invalid when the IPA transfer is enabled */ +void ipa_pixel_format_convert_mode_set(uint32_t pfcm); + +/* structure initialization, foreground, background, destination and LUT initialization */ +/* initialize the structure of IPA foreground parameter struct with the default values, it is + suggested that call this function after an ipa_foreground_parameter_struct structure is defined */ +void ipa_foreground_struct_para_init(ipa_foreground_parameter_struct *foreground_struct); +/* initialize foreground parameters */ +void ipa_foreground_init(ipa_foreground_parameter_struct *foreground_struct); +/* initialize the structure of IPA background parameter struct with the default values, it is + suggested that call this function after an ipa_background_parameter_struct structure is defined */ +void ipa_background_struct_para_init(ipa_background_parameter_struct *background_struct); +/* initialize background parameters */ +void ipa_background_init(ipa_background_parameter_struct *background_struct); +/* initialize the structure of IPA destination parameter struct with the default values, it is + suggested that call this function after an ipa_destination_parameter_struct structure is defined */ +void ipa_destination_struct_para_init(ipa_destination_parameter_struct *destination_struct); +/* initialize destination parameters */ +void ipa_destination_init(ipa_destination_parameter_struct *destination_struct); +/* initialize IPA foreground LUT parameters */ +void ipa_foreground_lut_init(uint8_t fg_lut_num, uint8_t fg_lut_pf, uint32_t fg_lut_addr); +/* initialize IPA background LUT parameters */ +void ipa_background_lut_init(uint8_t bg_lut_num, uint8_t bg_lut_pf, uint32_t bg_lut_addr); + +/* configuration functions */ +/* configure IPA line mark */ +void ipa_line_mark_config(uint16_t line_num); +/* inter-timer enable or disable */ +void ipa_inter_timer_config(uint8_t timer_cfg); +/* configure the number of clock cycles interval */ +void ipa_interval_clock_num_config(uint8_t clk_num); + +/* flag and interrupt functions */ +/* get IPA flag status in IPA_INTF register */ +FlagStatus ipa_flag_get(uint32_t flag); +/* clear IPA flag in IPA_INTF register */ +void ipa_flag_clear(uint32_t flag); +/* enable IPA interrupt */ +void ipa_interrupt_enable(uint32_t int_flag); +/* disable IPA interrupt */ +void ipa_interrupt_disable(uint32_t int_flag); +/* get IPA interrupt flag */ +FlagStatus ipa_interrupt_flag_get(uint32_t int_flag); +/* clear IPA interrupt flag */ +void ipa_interrupt_flag_clear(uint32_t int_flag); + +#endif /* GD32F5XX_IPA_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_iref.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_iref.h new file mode 100644 index 0000000..48b449a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_iref.h @@ -0,0 +1,184 @@ +/*! + \file gd32f5xx_iref.h + \brief definitions for the IREF + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_IREF_H +#define GD32F5XX_IREF_H + +#include "gd32f5xx.h" + +/* IREF definitions */ +#define IREF IREF_BASE /*!< IREF base address */ + +/* registers definitions */ +#define IREF_CTL REG32(IREF + 0x300U) /*!< IREF control register */ + +/* bits definitions */ +/* IREF_CTL */ +#define IREF_CTL_CSDT BITS(0,5) /*!< current step data */ +#define IREF_CTL_SCMOD BIT(7) /*!< sink current mode */ +#define IREF_CTL_CPT BITS(8,12) /*!< current precision trim */ +#define IREF_CTL_SSEL BIT(14) /*!< step selection */ +#define IREF_CTL_CREN BIT(15) /*!< current reference enable */ + +/* constants definitions */ +/* IREF current precision trim */ +#define CTL_CPT(regval) (BITS(8,12) & ((uint32_t)(regval) << 8)) +#define IREF_CUR_PRECISION_TRIM_0 CTL_CPT(0) /*!< IREF current precision trim 0 */ +#define IREF_CUR_PRECISION_TRIM_1 CTL_CPT(1) /*!< IREF current precision trim 1 */ +#define IREF_CUR_PRECISION_TRIM_2 CTL_CPT(2) /*!< IREF current precision trim 2 */ +#define IREF_CUR_PRECISION_TRIM_3 CTL_CPT(3) /*!< IREF current precision trim 3 */ +#define IREF_CUR_PRECISION_TRIM_4 CTL_CPT(4) /*!< IREF current precision trim 4 */ +#define IREF_CUR_PRECISION_TRIM_5 CTL_CPT(5) /*!< IREF current precision trim 5 */ +#define IREF_CUR_PRECISION_TRIM_6 CTL_CPT(6) /*!< IREF current precision trim 6 */ +#define IREF_CUR_PRECISION_TRIM_7 CTL_CPT(7) /*!< IREF current precision trim 7 */ +#define IREF_CUR_PRECISION_TRIM_8 CTL_CPT(8) /*!< IREF current precision trim 8 */ +#define IREF_CUR_PRECISION_TRIM_9 CTL_CPT(9) /*!< IREF current precision trim 9 */ +#define IREF_CUR_PRECISION_TRIM_10 CTL_CPT(10) /*!< IREF current precision trim 10 */ +#define IREF_CUR_PRECISION_TRIM_11 CTL_CPT(11) /*!< IREF current precision trim 11 */ +#define IREF_CUR_PRECISION_TRIM_12 CTL_CPT(12) /*!< IREF current precision trim 12 */ +#define IREF_CUR_PRECISION_TRIM_13 CTL_CPT(13) /*!< IREF current precision trim 13 */ +#define IREF_CUR_PRECISION_TRIM_14 CTL_CPT(14) /*!< IREF current precision trim 14 */ +#define IREF_CUR_PRECISION_TRIM_15 CTL_CPT(15) /*!< IREF current precision trim 15 */ +#define IREF_CUR_PRECISION_TRIM_16 CTL_CPT(16) /*!< IREF current precision trim 16 */ +#define IREF_CUR_PRECISION_TRIM_17 CTL_CPT(17) /*!< IREF current precision trim 17 */ +#define IREF_CUR_PRECISION_TRIM_18 CTL_CPT(18) /*!< IREF current precision trim 18 */ +#define IREF_CUR_PRECISION_TRIM_19 CTL_CPT(19) /*!< IREF current precision trim 19 */ +#define IREF_CUR_PRECISION_TRIM_20 CTL_CPT(20) /*!< IREF current precision trim 20 */ +#define IREF_CUR_PRECISION_TRIM_21 CTL_CPT(21) /*!< IREF current precision trim 21 */ +#define IREF_CUR_PRECISION_TRIM_22 CTL_CPT(22) /*!< IREF current precision trim 22 */ +#define IREF_CUR_PRECISION_TRIM_23 CTL_CPT(23) /*!< IREF current precision trim 23 */ +#define IREF_CUR_PRECISION_TRIM_24 CTL_CPT(24) /*!< IREF current precision trim 24 */ +#define IREF_CUR_PRECISION_TRIM_25 CTL_CPT(25) /*!< IREF current precision trim 25 */ +#define IREF_CUR_PRECISION_TRIM_26 CTL_CPT(26) /*!< IREF current precision trim 26 */ +#define IREF_CUR_PRECISION_TRIM_27 CTL_CPT(27) /*!< IREF current precision trim 27 */ +#define IREF_CUR_PRECISION_TRIM_28 CTL_CPT(28) /*!< IREF current precision trim 28 */ +#define IREF_CUR_PRECISION_TRIM_29 CTL_CPT(29) /*!< IREF current precision trim 29 */ +#define IREF_CUR_PRECISION_TRIM_30 CTL_CPT(30) /*!< IREF current precision trim 30 */ +#define IREF_CUR_PRECISION_TRIM_31 CTL_CPT(31) /*!< IREF current precision trim 31 */ + +/* IREF current step */ +#define CTL_CSDT(regval) (BITS(0,5) & ((uint32_t)(regval) << 0)) +#define IREF_CUR_STEP_DATA_0 CTL_CSDT(0) /*!< IREF current step data 0 */ +#define IREF_CUR_STEP_DATA_1 CTL_CSDT(1) /*!< IREF current step data 1 */ +#define IREF_CUR_STEP_DATA_2 CTL_CSDT(2) /*!< IREF current step data 2 */ +#define IREF_CUR_STEP_DATA_3 CTL_CSDT(3) /*!< IREF current step data 3 */ +#define IREF_CUR_STEP_DATA_4 CTL_CSDT(4) /*!< IREF current step data 4 */ +#define IREF_CUR_STEP_DATA_5 CTL_CSDT(5) /*!< IREF current step data 5 */ +#define IREF_CUR_STEP_DATA_6 CTL_CSDT(6) /*!< IREF current step data 6 */ +#define IREF_CUR_STEP_DATA_7 CTL_CSDT(7) /*!< IREF current step data 7 */ +#define IREF_CUR_STEP_DATA_8 CTL_CSDT(8) /*!< IREF current step data 8 */ +#define IREF_CUR_STEP_DATA_9 CTL_CSDT(9) /*!< IREF current step data 9 */ +#define IREF_CUR_STEP_DATA_10 CTL_CSDT(10) /*!< IREF current step data 10 */ +#define IREF_CUR_STEP_DATA_11 CTL_CSDT(11) /*!< IREF current step data 11 */ +#define IREF_CUR_STEP_DATA_12 CTL_CSDT(12) /*!< IREF current step data 12 */ +#define IREF_CUR_STEP_DATA_13 CTL_CSDT(13) /*!< IREF current step data 13 */ +#define IREF_CUR_STEP_DATA_14 CTL_CSDT(14) /*!< IREF current step data 14 */ +#define IREF_CUR_STEP_DATA_15 CTL_CSDT(15) /*!< IREF current step data 15 */ +#define IREF_CUR_STEP_DATA_16 CTL_CSDT(16) /*!< IREF current step data 16 */ +#define IREF_CUR_STEP_DATA_17 CTL_CSDT(17) /*!< IREF current step data 17 */ +#define IREF_CUR_STEP_DATA_18 CTL_CSDT(18) /*!< IREF current step data 18 */ +#define IREF_CUR_STEP_DATA_19 CTL_CSDT(19) /*!< IREF current step data 19 */ +#define IREF_CUR_STEP_DATA_20 CTL_CSDT(20) /*!< IREF current step data 20 */ +#define IREF_CUR_STEP_DATA_21 CTL_CSDT(21) /*!< IREF current step data 21 */ +#define IREF_CUR_STEP_DATA_22 CTL_CSDT(22) /*!< IREF current step data 22 */ +#define IREF_CUR_STEP_DATA_23 CTL_CSDT(23) /*!< IREF current step data 23 */ +#define IREF_CUR_STEP_DATA_24 CTL_CSDT(24) /*!< IREF current step data 24 */ +#define IREF_CUR_STEP_DATA_25 CTL_CSDT(25) /*!< IREF current step data 25 */ +#define IREF_CUR_STEP_DATA_26 CTL_CSDT(26) /*!< IREF current step data 26 */ +#define IREF_CUR_STEP_DATA_27 CTL_CSDT(27) /*!< IREF current step data 27 */ +#define IREF_CUR_STEP_DATA_28 CTL_CSDT(28) /*!< IREF current step data 28 */ +#define IREF_CUR_STEP_DATA_29 CTL_CSDT(29) /*!< IREF current step data 29 */ +#define IREF_CUR_STEP_DATA_30 CTL_CSDT(30) /*!< IREF current step data 30 */ +#define IREF_CUR_STEP_DATA_31 CTL_CSDT(31) /*!< IREF current step data 31 */ +#define IREF_CUR_STEP_DATA_32 CTL_CSDT(32) /*!< IREF current step data 32 */ +#define IREF_CUR_STEP_DATA_33 CTL_CSDT(33) /*!< IREF current step data 33 */ +#define IREF_CUR_STEP_DATA_34 CTL_CSDT(34) /*!< IREF current step data 34 */ +#define IREF_CUR_STEP_DATA_35 CTL_CSDT(35) /*!< IREF current step data 35 */ +#define IREF_CUR_STEP_DATA_36 CTL_CSDT(36) /*!< IREF current step data 36 */ +#define IREF_CUR_STEP_DATA_37 CTL_CSDT(37) /*!< IREF current step data 37 */ +#define IREF_CUR_STEP_DATA_38 CTL_CSDT(38) /*!< IREF current step data 38 */ +#define IREF_CUR_STEP_DATA_39 CTL_CSDT(39) /*!< IREF current step data 39 */ +#define IREF_CUR_STEP_DATA_40 CTL_CSDT(40) /*!< IREF current step data 40 */ +#define IREF_CUR_STEP_DATA_41 CTL_CSDT(41) /*!< IREF current step data 41 */ +#define IREF_CUR_STEP_DATA_42 CTL_CSDT(42) /*!< IREF current step data 42 */ +#define IREF_CUR_STEP_DATA_43 CTL_CSDT(43) /*!< IREF current step data 43 */ +#define IREF_CUR_STEP_DATA_44 CTL_CSDT(44) /*!< IREF current step data 44 */ +#define IREF_CUR_STEP_DATA_45 CTL_CSDT(45) /*!< IREF current step data 45 */ +#define IREF_CUR_STEP_DATA_46 CTL_CSDT(46) /*!< IREF current step data 46 */ +#define IREF_CUR_STEP_DATA_47 CTL_CSDT(47) /*!< IREF current step data 47 */ +#define IREF_CUR_STEP_DATA_48 CTL_CSDT(48) /*!< IREF current step data 48 */ +#define IREF_CUR_STEP_DATA_49 CTL_CSDT(49) /*!< IREF current step data 49 */ +#define IREF_CUR_STEP_DATA_50 CTL_CSDT(50) /*!< IREF current step data 50 */ +#define IREF_CUR_STEP_DATA_51 CTL_CSDT(51) /*!< IREF current step data 51 */ +#define IREF_CUR_STEP_DATA_52 CTL_CSDT(52) /*!< IREF current step data 52 */ +#define IREF_CUR_STEP_DATA_53 CTL_CSDT(53) /*!< IREF current step data 53 */ +#define IREF_CUR_STEP_DATA_54 CTL_CSDT(54) /*!< IREF current step data 54 */ +#define IREF_CUR_STEP_DATA_55 CTL_CSDT(55) /*!< IREF current step data 54 */ +#define IREF_CUR_STEP_DATA_56 CTL_CSDT(56) /*!< IREF current step data 54 */ +#define IREF_CUR_STEP_DATA_57 CTL_CSDT(57) /*!< IREF current step data 57 */ +#define IREF_CUR_STEP_DATA_58 CTL_CSDT(58) /*!< IREF current step data 58 */ +#define IREF_CUR_STEP_DATA_59 CTL_CSDT(59) /*!< IREF current step data 59 */ +#define IREF_CUR_STEP_DATA_60 CTL_CSDT(60) /*!< IREF current step data 60 */ +#define IREF_CUR_STEP_DATA_61 CTL_CSDT(61) /*!< IREF current step data 61 */ +#define IREF_CUR_STEP_DATA_62 CTL_CSDT(62) /*!< IREF current step data 62 */ +#define IREF_CUR_STEP_DATA_63 CTL_CSDT(63) /*!< IREF current step data 63 */ + +/* IREF mode selection */ +#define IREF_STEP(regval) (BIT(14) & ((uint32_t)(regval) << 14)) +#define IREF_MODE_LOW_POWER IREF_STEP(0) /*!< low power, 1uA step */ +#define IREF_MODE_HIGH_CURRENT IREF_STEP(1) /*!< high current, 8uA step */ + +/* IREF sink current mode*/ +#define IREF_CURRENT(regval) (BIT(7) & ((uint32_t)(regval) << 7)) +#define IREF_SOURCE_CURRENT IREF_CURRENT(0) /*!< IREF source current */ +#define IREF_SINK_CURRENT IREF_CURRENT(1) /*!< IREF sink current */ + +/* function declarations */ +/* deinitialize IREF */ +void iref_deinit(void); +/* enable IREF */ +void iref_enable(void); +/* disable IREF */ +void iref_disable(void); + +/* set IREF mode*/ +void iref_mode_set(uint32_t step); +/* set IREF current precision trim value */ +void iref_precision_trim_value_set(uint32_t precisiontrim); +/* set IREF sink current mode*/ +void iref_sink_set(uint32_t sinkmode); +/* set IREF step data*/ +void iref_step_data_config(uint32_t stepdata); + +#endif /* GD32F5XX_IREF_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_misc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_misc.h new file mode 100644 index 0000000..e4357ae --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_misc.h @@ -0,0 +1,91 @@ +/*! + \file gd32f5xx_misc.h + \brief definitions for the MISC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_MISC_H +#define GD32F5XX_MISC_H + +#include "gd32f5xx.h" + +/* constants definitions */ +/* set the RAM and FLASH base address */ +#define NVIC_VECTTAB_RAM ((uint32_t)0x20000000) /*!< RAM base address */ +#define NVIC_VECTTAB_FLASH ((uint32_t)0x08000000) /*!< Flash base address */ + +/* set the NVIC vector table offset mask */ +#define NVIC_VECTTAB_OFFSET_MASK ((uint32_t)0x1FFFFF80) + +/* the register key mask, if you want to do the write operation, you should write 0x5FA to VECTKEY bits */ +#define NVIC_AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) + +/* priority group - define the pre-emption priority and the subpriority */ +#define NVIC_PRIGROUP_PRE0_SUB4 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority 4 bits for subpriority */ +#define NVIC_PRIGROUP_PRE1_SUB3 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority 3 bits for subpriority */ +#define NVIC_PRIGROUP_PRE2_SUB2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority 2 bits for subpriority */ +#define NVIC_PRIGROUP_PRE3_SUB1 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority 1 bits for subpriority */ +#define NVIC_PRIGROUP_PRE4_SUB0 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority 0 bits for subpriority */ + +/* choose the method to enter or exit the lowpower mode */ +#define SCB_SCR_SLEEPONEXIT ((uint8_t)0x02) /*!< choose the the system whether enter low power mode by exiting from ISR */ +#define SCB_SCR_SLEEPDEEP ((uint8_t)0x04) /*!< choose the the system enter the DEEPSLEEP mode or SLEEP mode */ +#define SCB_SCR_SEVONPEND ((uint8_t)0x10) /*!< choose the interrupt source that can wake up the lowpower mode */ + +#define SCB_LPM_SLEEP_EXIT_ISR SCB_SCR_SLEEPONEXIT +#define SCB_LPM_DEEPSLEEP SCB_SCR_SLEEPDEEP +#define SCB_LPM_WAKE_BY_ALL_INT SCB_SCR_SEVONPEND + +/* choose the systick clock source */ +#define SYSTICK_CLKSOURCE_HCLK_DIV8 ((uint32_t)0xFFFFFFFBU) /*!< systick clock source is from HCLK/8 */ +#define SYSTICK_CLKSOURCE_HCLK ((uint32_t)0x00000004U) /*!< systick clock source is from HCLK */ + +/* function declarations */ +/* set the priority group */ +void nvic_priority_group_set(uint32_t nvic_prigroup); + +/* enable NVIC interrupt request */ +void nvic_irq_enable(uint8_t nvic_irq, uint8_t nvic_irq_pre_priority, uint8_t nvic_irq_sub_priority); +/* disable NVIC interrupt request */ +void nvic_irq_disable(uint8_t nvic_irq); + +/* set the NVIC vector table base address */ +void nvic_vector_table_set(uint32_t nvic_vict_tab, uint32_t offset); + +/* set the state of the low power mode */ +void system_lowpower_set(uint8_t lowpower_mode); +/* reset the state of the low power mode */ +void system_lowpower_reset(uint8_t lowpower_mode); + +/* set the systick clock source */ +void systick_clksource_set(uint32_t systick_clksource); + +#endif /* GD32F5XX_MISC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_pkcau.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_pkcau.h new file mode 100644 index 0000000..ae7bc41 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_pkcau.h @@ -0,0 +1,290 @@ +/*! + \file gd32f5xx_pkcau.h + \brief definitions for the PKCAU + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_PKCAU_H +#define GD32F5XX_PKCAU_H + +#include "gd32f5xx.h" + +/* PKCAU definitions */ +#define PKCAU PKCAU_BASE /*!< PKCAU base address */ + +/* registers definitions */ +#define PKCAU_CTL REG32(PKCAU + 0x00000000U) /*!< PKCAU control register */ +#define PKCAU_STAT REG32(PKCAU + 0x00000004U) /*!< PKCAU status register */ +#define PKCAU_STATC REG32(PKCAU + 0x00000008U) /*!< PKCAU status clear register */ + +/* bits definitions */ +/* PKCAU_CTL */ +#define PKCAU_CTL_PKCAUEN BIT(0) /*!< PKCAU peripheral enable */ +#define PKCAU_CTL_START BIT(1) /*!< start operation */ +#define PKCAU_CTL_MODESEL BITS(8,13) /*!< operation mode selection */ +#define PKCAU_CTL_ENDIE BIT(17) /*!< end of operation interrupt enable */ +#define PKCAU_CTL_RAMERRIE BIT(19) /*!< RAM error interrupt enable */ +#define PKCAU_CTL_ADDRERRIE BIT(20) /*!< address error interrupt enable */ + +/* PKCAU_STAT */ +#define PKCAU_STAT_BUSY BIT(16) /*!< busy flag */ +#define PKCAU_STAT_ENDF BIT(17) /*!< end of PKCAU operation */ +#define PKCAU_STAT_RAMERR BIT(19) /*!< PKCAU RAM error */ +#define PKCAU_STAT_ADDRERR BIT(20) /*!< address error */ + +/* PKCAU_STATC */ +#define PKCAU_STATC_ENDFC BIT(17) /*!< end of PKCAU operation flag clear */ +#define PKCAU_STATC_RAMERRC BIT(19) /*!< PKCAU RAM error flag clear */ +#define PKCAU_STATC_ADDRERRC BIT(20) /*!< address error flag clear */ + +/* constants definitions */ +/* montgomery parameter structure */ +typedef struct{ + const uint8_t* modulus_n; /*!< modulus value n */ + uint32_t modulus_n_len; /*!< modulus length in byte */ +}pkcau_mont_parameter_struct; + +/* modular addition, modular subtraction, montgomery multiplication, modular inversion, modular reduction parameter structure */ +typedef struct{ + const uint8_t* oprd_a; /*!< operand A */ + uint32_t oprd_a_len; /*!< operand A length in byte */ + const uint8_t* oprd_b; /*!< operand B */ + uint32_t oprd_b_len; /*!< operand b length in byte */ + const uint8_t* modulus_n; /*!< modulus value n */ + uint32_t modulus_n_len; /*!< modulus length in byte */ +}pkcau_mod_parameter_struct; + +/* modular exponentiation parameter structure */ +typedef struct{ + const uint8_t* oprd_a; /*!< operand A */ + uint32_t oprd_a_len; /*!< operand A length in byte */ + const uint8_t* exp_e; /*!< exponent e */ + uint32_t e_len; /*!< exponent length in byte */ + const uint8_t* modulus_n; /*!< modulus n */ + uint32_t modulus_n_len; /*!< modulus length in byte */ + uint8_t* mont_para; /*!< montgomery parameter R2 mod n */ + uint32_t mont_para_len; /*!< montgomery parameter length in byte */ +}pkcau_mod_exp_parameter_struct; + +/* arithmetic addition, arithmetic subtraction, arithmetic multiplication and arithmetic comparison parameter structure */ +typedef struct{ + const uint8_t* oprd_a; /*!< operand A */ + uint32_t oprd_a_len; /*!< length of operand in byte */ + const uint8_t* oprd_b; /*!< operand B */ + uint32_t oprd_b_len; /*!< length of operand in byte */ +}pkcau_arithmetic_parameter_struct; + +/* CRT parameter structure */ +typedef struct{ + const uint8_t* oprd_a; /*!< operand A */ + uint32_t oprd_a_len; /*!< length of operand in byte */ + uint8_t* oprd_dp; /*!< operand dp */ + uint32_t oprd_dp_len; /*!< length of operand dp in byte */ + uint8_t* oprd_dq; /*!< operand dq */ + uint32_t oprd_dq_len; /*!< length of operand dq in byte */ + uint8_t* oprd_qinv; /*!< operand qinv */ + uint32_t oprd_qinv_len; /*!< length of operand qinv in byte */ + uint8_t* oprd_p; /*!< prime operand p */ + uint32_t oprd_p_len; /*!< length of operand p in byte */ + uint8_t* oprd_q; /*!< prime operand q */ + uint32_t oprd_q_len; /*!< length of operand q in byte */ +}pkcau_crt_parameter_struct; + +/* ECC curve parameter structure */ +typedef struct{ + uint8_t* modulus_p; /*!< curve modulus p */ + uint32_t modulus_p_len; /*!< curve modulus p length in byte */ + uint8_t* coff_a; /*!< curve coefficient a */ + uint32_t coff_a_len; /*!< curve coefficient a length in byte */ + uint8_t* coff_b; /*!< curve coefficient b */ + uint32_t coff_b_len; /*!< curve coefficient b length in byte */ + uint8_t* base_point_x; /*!< curve base point coordinate x */ + uint32_t base_point_x_len; /*!< curve base point coordinate x length in byte */ + uint8_t* base_point_y; /*!< curve base point coordinate y */ + uint32_t base_point_y_len; /*!< curve base point coordinate y length in byte */ + uint8_t* order_n; /*!< curve prime order n */ + uint32_t order_n_len; /*!< curve prime order n length in byte */ + uint32_t a_sign; /*!< curve coefficient a sign */ + + const uint8_t* multi_k; /*!< scalar multiplier k */ + uint32_t multi_k_len; /*!< scalar multiplier k length in byte */ + + const uint8_t* integer_k; /*!< integer k */ + uint32_t integer_k_len; /*!< integer k length in byte */ + const uint8_t* private_key_d; /*!< private key d */ + uint32_t private_key_d_len; /*!< private key d length in byte */ + uint8_t* mont_para; /*!< montgomery parameter R2 mod n */ + uint32_t mont_para_len; /*!< montgomery parameter R2 mod n length in byte */ +}pkcau_ec_group_parameter_struct; + +/* point structure */ +typedef struct{ + const uint8_t* point_x; /*!< point coordinate x */ + uint32_t point_x_len; /*!< point coordinate x length in byte > */ + const uint8_t* point_y; /*!< point coordinate y */ + uint32_t point_y_len; /*!< point coordinate y length in byte > */ +}pkcau_point_parameter_struct; + +/* signature structure */ +typedef struct{ + const uint8_t* sign_r; /*!< signature part r */ + uint32_t sign_r_len; /*!< signature part r lnegth in byte */ + const uint8_t* sign_s; /*!< signature part s */ + uint32_t sign_s_len; /*!< signature part s lnegth in byte */ +}pkcau_signature_parameter_struct; + +/* hash structure */ +typedef struct { + const uint8_t *hash_z; /*!< hash value z */ + uint32_t hash_z_len; /*!< hash value z length in byte */ +}pkcau_hash_parameter_struct; + + +/* ecdsa signature, ecc scalar multiplication output structure */ +typedef struct{ + uint32_t sign_extra; /*!< flag of extended ECDSA sign (extra outputs) */ + uint8_t* sign_r; /*!< pointer to signature part r */ + uint8_t* sign_s; /*!< pointer to signature part s */ + uint8_t* point_x; /*!< pointer to point kP coordinate x */ + uint8_t* point_y; /*!< pointer to point kP coordinate y */ +}pkcau_ecc_out_struct; + + +/* PKCAU operation code */ +#define CTL_MODE(regval) (BITS(8,13) & ((uint32_t)(regval) << 8)) +#define PKCAU_MODE_MOD_EXP CTL_MODE(0) /*!< montgomery parameter computation then modular exponentiation */ +#define PKCAU_MODE_MONT_PARAM CTL_MODE(1) /*!< montgomery parameter computation only */ +#define PKCAU_MODE_MOD_EXP_FAST CTL_MODE(2) /*!< modular exponentiation only */ +#define PKCAU_MODE_CRT_EXP CTL_MODE(7) /*!< RSA CRT exponentiation */ +#define PKCAU_MODE_MOD_INVERSION CTL_MODE(8) /*!< modular inversion */ +#define PKCAU_MODE_ARITHMETIC_ADD CTL_MODE(9) /*!< arithmetic addition */ +#define PKCAU_MODE_ARITHMETIC_SUB CTL_MODE(10) /*!< arithmetic subtraction */ +#define PKCAU_MODE_ARITHMETIC_MUL CTL_MODE(11) /*!< arithmetic multiplication */ +#define PKCAU_MODE_ARITHMETIC_COMP CTL_MODE(12) /*!< arithmetic comparison */ +#define PKCAU_MODE_MOD_REDUCTION CTL_MODE(13) /*!< modular reduction */ +#define PKCAU_MODE_MOD_ADD CTL_MODE(14) /*!< modular addition */ +#define PKCAU_MODE_MOD_SUB CTL_MODE(15) /*!< modular subtraction */ +#define PKCAU_MODE_MONT_MUL CTL_MODE(16) /*!< montgomery multiplication */ +#define PKCAU_MODE_ECC_SCALAR_MUL CTL_MODE(32) /*!< montgomery parameter computation then ECC scalar multiplication */ +#define PKCAU_MODE_ECC_SCALAR_MUL_FAST CTL_MODE(34) /*!< ECC scalar multiplication only */ +#define PKCAU_MODE_ECDSA_SIGN CTL_MODE(36) /*!< ECDSA sign */ +#define PKCAU_MODE_ECDSA_VERIFICATION CTL_MODE(38) /*!< ECDSA verification */ +#define PKCAU_MODE_POINT_CHECK CTL_MODE(40) /*!< point on elliptic curve Fp check */ + +/* PKCAU interrupt */ +#define PKCAU_INT_ADDRERR PKCAU_CTL_ADDRERRIE /*!< address error interrupt enable */ +#define PKCAU_INT_RAMERR PKCAU_CTL_RAMERRIE /*!< RAM error interrupt enable */ +#define PKCAU_INT_END PKCAU_CTL_ENDIE /*!< end of operation interrupt enable */ + +/* PKCAU flag definitions */ +#define PKCAU_FLAG_ADDRERR PKCAU_STAT_ADDRERR /*!< address error flag */ +#define PKCAU_FLAG_RAMERR PKCAU_STAT_RAMERR /*!< PKCAU RAM error flag */ +#define PKCAU_FLAG_END PKCAU_STAT_ENDF /*!< end of PKCAU operation flag */ +#define PKCAU_FLAG_BUSY PKCAU_STAT_BUSY /*!< busy flag */ + +/* PKCAU interrupt flag definitions */ +#define PKCAU_INT_FLAG_ADDRERR PKCAU_STAT_ADDRERR /*!< address error flag */ +#define PKCAU_INT_FLAG_RAMERR PKCAU_STAT_RAMERR /*!< PKCAU RAM error flag */ +#define PKCAU_INT_FLAG_ENDF PKCAU_STAT_ENDF /*!< end of PKCAU operation flag */ + +/* function declarations */ +/* initialization functions */ +/* reset pkcau */ +void pkcau_deinit(void); +/* initialize montgomery parameter structure with a default value */ +void pkcau_mont_struct_para_init(pkcau_mont_parameter_struct* init_para); +/* initialize modular parameter structure with a default value */ +void pkcau_mod_struct_para_init(pkcau_mod_parameter_struct* init_para); +/* initialize modular exponentiation parameter structure with a default value */ +void pkcau_mod_exp_struct_para_init(pkcau_mod_exp_parameter_struct* init_para); +/* initialize arithmetic parameter structure with a default value */ +void pkcau_arithmetic_struct_para_init(pkcau_arithmetic_parameter_struct* init_para); +/* initialize CRT parameter structure with a default value */ +void pkcau_crt_struct_para_init(pkcau_crt_parameter_struct* init_para); +/* initialize ECC curve parameter structure with a default value */ +void pkcau_ec_group_struct_para_init(pkcau_ec_group_parameter_struct* init_para); +/* initialize point parameter structure with a default value */ +void pkcau_point_struct_para_init(pkcau_point_parameter_struct* init_para); +/* initialize signature parameter structure with a default value */ +void pkcau_signature_struct_para_init(pkcau_signature_parameter_struct* init_para); +/* initialize hash parameter structure with a default value */ +void pkcau_hash_struct_para_init(pkcau_hash_parameter_struct* init_para); +/* initialize ecc output parameter structure with a default value */ +void pkcau_ecc_out_struct_para_init(pkcau_ecc_out_struct* init_para); + +/* application function declarations */ +/* enable PKCAU */ +void pkcau_enable(void); +/* disable PKCAU */ +void pkcau_disable(void); +/* start operation */ +void pkcau_start(void); +/* configure the PKCAU operation mode */ +void pkcau_mode_set(uint32_t mode); +/* execute montgomery parameter operation */ +void pkcau_mont_param_operation(pkcau_mont_parameter_struct* mont_para, uint8_t* results); +/* execute modular operation, include modular addition, modular subtraction and montgomery multiplication */ +void pkcau_mod_operation(pkcau_mod_parameter_struct* mod_para, uint32_t mode, uint8_t* results); +/* execute modular exponentiation operation */ +void pkcau_mod_exp_operation(pkcau_mod_exp_parameter_struct* mod_exp_para, uint32_t mode, uint8_t* results); +/* execute modular inversion operation */ +void pkcau_mod_inver_operation(pkcau_mod_parameter_struct* mod_inver_para, uint8_t* results); +/* execute modular reduction operation */ +void pkcau_mod_reduc_operation(pkcau_mod_parameter_struct* mod_reduc_para, uint8_t* results); +/* execute arithmetic addition operation */ +void pkcau_arithmetic_operation(pkcau_arithmetic_parameter_struct* arithmetic_para, uint32_t mode, uint8_t* results); +/* execute RSA CRT exponentiation operation */ +void pkcau_crt_exp_operation(pkcau_crt_parameter_struct* crt_para, uint8_t* results); +/* execute point check operation */ +uint8_t pkcau_point_check_operation(pkcau_point_parameter_struct* point_para, const pkcau_ec_group_parameter_struct* curve_group_para); +/* execute point multiplication operation */ +void pkcau_point_mul_operation(pkcau_point_parameter_struct* point_para, const pkcau_ec_group_parameter_struct* curve_group_para, uint32_t mode, pkcau_ecc_out_struct* result); +/* execute ECDSA sign operation */ +uint8_t pkcau_ecdsa_sign_operation(pkcau_hash_parameter_struct* hash_para, const pkcau_ec_group_parameter_struct* curve_group_para, pkcau_ecc_out_struct* result); +/* execute ECDSA verify operation */ +uint8_t pkcau_ecdsa_verification_operation(pkcau_point_parameter_struct* point_para, pkcau_hash_parameter_struct* hash_para, pkcau_signature_parameter_struct* signature_para, const pkcau_ec_group_parameter_struct* curve_group_para); + +/* interrupt & flag functions */ +/* get PKCAU flag status */ +FlagStatus pkcau_flag_get(uint32_t flag); +/* clear PKCAU flag status */ +void pkcau_flag_clear(uint32_t flag); +/* enable PKCAU interrupt */ +void pkcau_interrupt_enable(uint32_t interrupt); +/* disable PKCAU interrupt */ +void pkcau_interrupt_disable(uint32_t interrupt); +/* get PKCAU interrupt flag status */ +FlagStatus pkcau_interrupt_flag_get(uint32_t int_flag); +/* clear PKCAU interrupt flag status */ +void pkcau_interrupt_flag_clear(uint32_t int_flag); + +#endif /* GD32F5XX_PKCAU_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_pmu.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_pmu.h new file mode 100644 index 0000000..f6b3899 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_pmu.h @@ -0,0 +1,203 @@ +/*! + \file gd32f5xx_pmu.h + \brief definitions for the PMU + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_PMU_H +#define GD32F5XX_PMU_H + +#include "gd32f5xx.h" + +/* PMU definitions */ +#define PMU PMU_BASE /*!< PMU base address */ + +/* registers definitions */ +#define PMU_CTL REG32((PMU) + 0x00000000U) /*!< PMU control register */ +#define PMU_CS REG32((PMU) + 0x00000004U) /*!< PMU control and status register */ + +/* bits definitions */ +/* PMU_CTL */ +#define PMU_CTL_LDOLP BIT(0) /*!< LDO low power mode */ +#define PMU_CTL_STBMOD BIT(1) /*!< standby mode */ +#define PMU_CTL_WURST BIT(2) /*!< wakeup flag reset */ +#define PMU_CTL_STBRST BIT(3) /*!< standby flag reset */ +#define PMU_CTL_LVDEN BIT(4) /*!< low voltage detector enable */ +#define PMU_CTL_LVDT BITS(5,7) /*!< low voltage detector threshold */ +#define PMU_CTL_BKPWEN BIT(8) /*!< backup domain write enable */ +#define PMU_CTL_LDLP BIT(10) /*!< low-driver mode when use low power LDO */ +#define PMU_CTL_LDNP BIT(11) /*!< low-driver mode when use normal power LDO */ +#define PMU_CTL_LDOVS BITS(14,15) /*!< LDO output voltage select */ +#define PMU_CTL_HDEN BIT(16) /*!< high-driver mode enable */ +#define PMU_CTL_HDS BIT(17) /*!< high-driver mode switch */ +#define PMU_CTL_LDEN BITS(18,19) /*!< low-driver mode enable in deep-sleep mode */ + +/* PMU_CS */ +#define PMU_CS_WUF BIT(0) /*!< wakeup flag */ +#define PMU_CS_STBF BIT(1) /*!< standby flag */ +#define PMU_CS_LVDF BIT(2) /*!< low voltage detector status flag */ +#define PMU_CS_BLDORF BIT(3) /*!< backup SRAM LDO ready flag */ +#define PMU_CS_WUPEN BIT(8) /*!< wakeup pin enable */ +#define PMU_CS_BLDOON BIT(9) /*!< backup SRAM LDO on */ +#define PMU_CS_LDOVSRF BIT(14) /*!< LDO voltage select ready flag */ +#define PMU_CS_HDRF BIT(16) /*!< high-driver ready flag */ +#define PMU_CS_HDSRF BIT(17) /*!< high-driver switch ready flag */ +#define PMU_CS_LDRF BITS(18,19) /*!< low-driver mode ready flag */ + +/* constants definitions */ +/* PMU ldo definitions */ +#define PMU_LDO_NORMAL ((uint32_t)0x00000000U) /*!< LDO normal work when PMU enter deep-sleep mode */ +#define PMU_LDO_LOWPOWER PMU_CTL_LDOLP /*!< LDO work at low power status when PMU enter deep-sleep mode */ + +/* PMU low voltage detector threshold definitions */ +#define CTL_LVDT(regval) (BITS(5,7)&((uint32_t)(regval)<<5)) +#define PMU_LVDT_0 CTL_LVDT(0) /*!< voltage threshold is 2.1V */ +#define PMU_LVDT_1 CTL_LVDT(1) /*!< voltage threshold is 2.3V */ +#define PMU_LVDT_2 CTL_LVDT(2) /*!< voltage threshold is 2.4V */ +#define PMU_LVDT_3 CTL_LVDT(3) /*!< voltage threshold is 2.6V */ +#define PMU_LVDT_4 CTL_LVDT(4) /*!< voltage threshold is 2.7V */ +#define PMU_LVDT_5 CTL_LVDT(5) /*!< voltage threshold is 2.9V */ +#define PMU_LVDT_6 CTL_LVDT(6) /*!< voltage threshold is 3.0V */ +#define PMU_LVDT_7 CTL_LVDT(7) /*!< voltage threshold is 3.1V */ + +/* PMU low-driver mode when use low power LDO */ +#define CTL_LDLP(regval) (BIT(10)&((uint32_t)(regval)<<10)) +#define PMU_NORMALDR_LOWPWR CTL_LDLP(0) /*!< normal driver when use low power LDO */ +#define PMU_LOWDR_LOWPWR CTL_LDLP(1) /*!< low-driver mode enabled when LDEN is 11 and use low power LDO */ + +/* PMU low-driver mode when use normal power LDO */ +#define CTL_LDNP(regval) (BIT(11)&((uint32_t)(regval)<<11)) +#define PMU_NORMALDR_NORMALPWR CTL_LDNP(0) /*!< normal driver when use normal power LDO */ +#define PMU_LOWDR_NORMALPWR CTL_LDNP(1) /*!< low-driver mode enabled when LDEN is 11 and use normal power LDO */ + +/* PMU LDO output voltage select definitions */ +#define CTL_LDOVS(regval) (BITS(14,15)&((uint32_t)(regval)<<14)) +#define PMU_LDOVS_LOW CTL_LDOVS(1) /*!< LDO output voltage low mode */ +#define PMU_LDOVS_MID CTL_LDOVS(2) /*!< LDO output voltage mid mode */ +#define PMU_LDOVS_HIGH CTL_LDOVS(3) /*!< LDO output voltage high mode */ + + +/* PMU high-driver mode switch */ +#define CTL_HDS(regval) (BIT(17)&((uint32_t)(regval)<<17)) +#define PMU_HIGHDR_SWITCH_NONE CTL_HDS(0) /*!< no high-driver mode switch */ +#define PMU_HIGHDR_SWITCH_EN CTL_HDS(1) /*!< high-driver mode switch */ + +/* PMU low-driver mode enable in deep-sleep mode */ +#define CTL_LDEN(regval) (BITS(18,19)&((uint32_t)(regval)<<18)) +#define PMU_LOWDRIVER_DISABLE CTL_LDEN(0) /*!< low-driver mode disable in deep-sleep mode */ +#define PMU_LOWDRIVER_ENABLE CTL_LDEN(3) /*!< low-driver mode enable in deep-sleep mode */ + +/* PMU backup SRAM LDO on or off */ +#define CS_BLDOON(regval) (BIT(9)&((uint32_t)(regval)<<9)) +#define PMU_BLDOON_OFF CS_BLDOON(0) /*!< backup SRAM LDO off */ +#define PMU_BLDOON_ON CS_BLDOON(1) /*!< the backup SRAM LDO on */ + +/* PMU low power mode ready flag definitions */ +#define CS_LDRF(regval) (BITS(18,19)&((uint32_t)(regval)<<18)) +#define PMU_LDRF_NORMAL CS_LDRF(0) /*!< normal driver in deep-sleep mode */ +#define PMU_LDRF_LOWDRIVER CS_LDRF(3) /*!< low-driver mode in deep-sleep mode */ + +/* PMU flag definitions */ +#define PMU_FLAG_WAKEUP PMU_CS_WUF /*!< wakeup flag status */ +#define PMU_FLAG_STANDBY PMU_CS_STBF /*!< standby flag status */ +#define PMU_FLAG_LVD PMU_CS_LVDF /*!< lvd flag status */ +#define PMU_FLAG_BLDORF PMU_CS_BLDORF /*!< backup SRAM LDO ready flag */ +#define PMU_FLAG_LDOVSRF PMU_CS_LDOVSRF /*!< LDO voltage select ready flag */ +#define PMU_FLAG_HDRF PMU_CS_HDRF /*!< high-driver ready flag */ +#define PMU_FLAG_HDSRF PMU_CS_HDSRF /*!< high-driver switch ready flag */ +#define PMU_FLAG_LDRF PMU_CS_LDRF /*!< low-driver mode ready flag */ + +/* PMU flag reset definitions */ +#define PMU_FLAG_RESET_WAKEUP ((uint8_t)0x00U) /*!< wakeup flag reset */ +#define PMU_FLAG_RESET_STANDBY ((uint8_t)0x01U) /*!< standby flag reset */ + +/* PMU command constants definitions */ +#define WFI_CMD ((uint8_t)0x00U) /*!< use WFI command */ +#define WFE_CMD ((uint8_t)0x01U) /*!< use WFE command */ + +/* function declarations */ +/* reset PMU registers */ +void pmu_deinit(void); + +/* LVD functions */ +/* select low voltage detector threshold */ +void pmu_lvd_select(uint32_t lvdt_n); +/* disable PMU lvd */ +void pmu_lvd_disable(void); + +/* LDO functions */ +/* select LDO output voltage */ +void pmu_ldo_output_select(uint32_t ldo_output); + +/* functions of low-driver mode and high-driver mode */ +/* enable high-driver mode */ +void pmu_highdriver_mode_enable(void); +/* disable high-driver mode */ +void pmu_highdriver_mode_disable(void); +/* switch high-driver mode */ +void pmu_highdriver_switch_select(uint32_t highdr_switch); +/* enable low-driver mode in deep-sleep */ +void pmu_lowdriver_mode_enable(void); +/* disable low-driver mode in deep-sleep */ +void pmu_lowdriver_mode_disable(void); +/* in deep-sleep mode, driver mode when use low power LDO */ +void pmu_lowpower_driver_config(uint32_t mode); +/* in deep-sleep mode, driver mode when use normal power LDO */ +void pmu_normalpower_driver_config(uint32_t mode); + +/* set PMU mode */ +/* PMU work in sleep mode */ +void pmu_to_sleepmode(uint8_t sleepmodecmd); +/* PMU work in deepsleep mode */ +void pmu_to_deepsleepmode(uint32_t ldo, uint32_t lowdrive, uint8_t deepsleepmodecmd); +/* PMU work in standby mode */ +void pmu_to_standbymode(void); +/* enable PMU wakeup pin */ +void pmu_wakeup_pin_enable(void); +/* disable PMU wakeup pin */ +void pmu_wakeup_pin_disable(void); + +/* backup related functions */ +/* backup SRAM LDO on */ +void pmu_backup_ldo_config(uint32_t bkp_ldo); +/* enable write access to the registers in backup domain */ +void pmu_backup_write_enable(void); +/* disable write access to the registers in backup domain */ +void pmu_backup_write_disable(void); + +/* flag functions */ +/* get flag state */ +FlagStatus pmu_flag_get(uint32_t flag); +/* clear flag bit */ +void pmu_flag_clear(uint32_t flag); + +#endif /* GD32F5XX_PMU_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_rcu.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_rcu.h new file mode 100644 index 0000000..e50c05f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_rcu.h @@ -0,0 +1,1261 @@ +/*! + \file gd32f5xx_rcu.h + \brief definitions for the RCU + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_RCU_H +#define GD32F5XX_RCU_H + +#include "gd32f5xx.h" + +/* RCU definitions */ +#define RCU RCU_BASE + +/* registers definitions */ +#define RCU_CTL REG32(RCU + 0x00U) /*!< control register */ +#define RCU_PLL REG32(RCU + 0x04U) /*!< PLL register */ +#define RCU_CFG0 REG32(RCU + 0x08U) /*!< clock configuration register 0 */ +#define RCU_INT REG32(RCU + 0x0CU) /*!< clock interrupt register */ +#define RCU_AHB1RST REG32(RCU + 0x10U) /*!< AHB1 reset register */ +#define RCU_AHB2RST REG32(RCU + 0x14U) /*!< AHB2 reset register */ +#define RCU_AHB3RST REG32(RCU + 0x18U) /*!< AHB3 reset register */ +#define RCU_APB1RST REG32(RCU + 0x20U) /*!< APB1 reset register */ +#define RCU_APB2RST REG32(RCU + 0x24U) /*!< APB2 reset register */ +#define RCU_AHB1EN REG32(RCU + 0x30U) /*!< AHB1 enable register */ +#define RCU_AHB2EN REG32(RCU + 0x34U) /*!< AHB2 enable register */ +#define RCU_AHB3EN REG32(RCU + 0x38U) /*!< AHB3 enable register */ +#define RCU_APB1EN REG32(RCU + 0x40U) /*!< APB1 enable register */ +#define RCU_APB2EN REG32(RCU + 0x44U) /*!< APB2 enable register */ +#define RCU_AHB1SPEN REG32(RCU + 0x50U) /*!< AHB1 sleep mode enable register */ +#define RCU_AHB2SPEN REG32(RCU + 0x54U) /*!< AHB2 sleep mode enable register */ +#define RCU_AHB3SPEN REG32(RCU + 0x58U) /*!< AHB3 sleep mode enable register */ +#define RCU_APB1SPEN REG32(RCU + 0x60U) /*!< APB1 sleep mode enable register */ +#define RCU_APB2SPEN REG32(RCU + 0x64U) /*!< APB2 sleep mode enable register */ +#define RCU_BDCTL REG32(RCU + 0x70U) /*!< backup domain control register */ +#define RCU_RSTSCK REG32(RCU + 0x74U) /*!< reset source / clock register */ +#define RCU_PLLSSCTL REG32(RCU + 0x80U) /*!< PLL clock spread spectrum control register */ +#define RCU_PLLI2S REG32(RCU + 0x84U) /*!< PLLI2S register */ +#define RCU_PLLSAI REG32(RCU + 0x88U) /*!< PLLSAI register */ +#define RCU_CFG1 REG32(RCU + 0x8CU) /*!< clock configuration register 1 */ +#define RCU_CFG2 REG32(RCU + 0x94U) /*!< clock configuration register 2 */ +#define RCU_ADDCTL REG32(RCU + 0xC0U) /*!< additional clock control register */ +#define RCU_ADDINT REG32(RCU + 0xCCU) /*!< additional clock interrupt register */ +#define RCU_ADDAPB1RST REG32(RCU + 0xE0U) /*!< APB1 additional reset register */ +#define RCU_ADDAPB1EN REG32(RCU + 0xE4U) /*!< APB1 additional enable register */ +#define RCU_ADDAPB1SPEN REG32(RCU + 0xE8U) /*!< APB1 additional sleep mode enable register */ +#define RCU_VKEY REG32(RCU + 0x100U) /*!< voltage key register */ +#define RCU_DSV REG32(RCU + 0x134U) /*!< deep-sleep mode voltage register */ + +/* bits definitions */ +/* RCU_CTL */ +#define RCU_CTL_IRC16MEN BIT(0) /*!< internal high speed oscillator enable */ +#define RCU_CTL_IRC16MSTB BIT(1) /*!< IRC16M high speed internal oscillator stabilization flag */ +#define RCU_CTL_IRC16MADJ BITS(3,7) /*!< high speed internal oscillator clock trim adjust value */ +#define RCU_CTL_IRC16MCALIB BITS(8,15) /*!< high speed internal oscillator calibration value register */ +#define RCU_CTL_HXTALEN BIT(16) /*!< external high speed oscillator enable */ +#define RCU_CTL_HXTALSTB BIT(17) /*!< external crystal oscillator clock stabilization flag */ +#define RCU_CTL_HXTALBPS BIT(18) /*!< external crystal oscillator clock bypass mode enable */ +#define RCU_CTL_CKMEN BIT(19) /*!< HXTAL clock monitor enable */ +#define RCU_CTL_PLLEN BIT(24) /*!< PLL enable */ +#define RCU_CTL_PLLSTB BIT(25) /*!< PLL Clock Stabilization Flag */ +#define RCU_CTL_PLLI2SEN BIT(26) /*!< PLLI2S enable */ +#define RCU_CTL_PLLI2SSTB BIT(27) /*!< PLLI2S Clock Stabilization Flag */ +#define RCU_CTL_PLLSAIEN BIT(28) /*!< PLLSAI enable */ +#define RCU_CTL_PLLSAISTB BIT(29) /*!< PLLSAI Clock Stabilization Flag */ + +/* RCU_PLL */ +#define RCU_PLL_PLLPSC BITS(0,5) /*!< the PLL VCO source clock prescaler */ +#define RCU_PLL_PLLN BITS(6,14) /*!< the PLL VCO clock multi factor */ +#define RCU_PLL_PLLP BITS(16,17) /*!< the PLLP output frequency division factor from PLL VCO clock */ +#define RCU_PLL_PLLSEL BIT(22) /*!< PLL Clock Source Selection */ +#define RCU_PLL_PLLQ BITS(24,27) /*!< the PLL Q output frequency division factor from PLL VCO clock */ + +/* RCU_CFG0 */ +#define RCU_CFG0_SCS BITS(0,1) /*!< system clock switch */ +#define RCU_CFG0_SCSS BITS(2,3) /*!< system clock switch status */ +#define RCU_CFG0_AHBPSC BITS(4,7) /*!< AHB prescaler selection */ +#define RCU_CFG0_APB1PSC BITS(10,12) /*!< APB1 prescaler selection */ +#define RCU_CFG0_APB2PSC BITS(13,15) /*!< APB2 prescaler selection */ +#define RCU_CFG0_RTCDIV BITS(16,20) /*!< RTC clock divider factor */ +#define RCU_CFG0_CKOUT0SEL BITS(21,22) /*!< CKOUT0 Clock Source Selection */ +#define RCU_CFG0_I2SSEL BIT(23) /*!< I2S Clock Source Selection */ +#define RCU_CFG0_CKOUT0DIV BITS(24,26) /*!< the CK_OUT0 divider which the CK_OUT0 frequency can be reduced */ +#define RCU_CFG0_CKOUT1DIV BITS(27,29) /*!< the CK_OUT1 divider which the CK_OUT1 frequency can be reduced */ +#define RCU_CFG0_CKOUT1SEL BITS(30,31) /*!< CKOUT1 Clock Source Selection */ + +/* RCU_INT */ +#define RCU_INT_IRC32KSTBIF BIT(0) /*!< IRC32K stabilization interrupt flag */ +#define RCU_INT_LXTALSTBIF BIT(1) /*!< LXTAL stabilization interrupt flag */ +#define RCU_INT_IRC16MSTBIF BIT(2) /*!< IRC16M stabilization interrupt flag */ +#define RCU_INT_HXTALSTBIF BIT(3) /*!< HXTAL stabilization interrupt flag */ +#define RCU_INT_PLLSTBIF BIT(4) /*!< PLL stabilization interrupt flag */ +#define RCU_INT_PLLI2SSTBIF BIT(5) /*!< PLLI2S stabilization interrupt flag */ +#define RCU_INT_PLLSAISTBIF BIT(6) /*!< PLLSAI stabilization interrupt flag */ +#define RCU_INT_CKMIF BIT(7) /*!< HXTAL clock stuck interrupt flag */ +#define RCU_INT_IRC32KSTBIE BIT(8) /*!< IRC32K stabilization interrupt enable */ +#define RCU_INT_LXTALSTBIE BIT(9) /*!< LXTAL stabilization interrupt enable */ +#define RCU_INT_IRC16MSTBIE BIT(10) /*!< IRC16M stabilization interrupt enable */ +#define RCU_INT_HXTALSTBIE BIT(11) /*!< HXTAL stabilization interrupt enable */ +#define RCU_INT_PLLSTBIE BIT(12) /*!< PLL stabilization interrupt enable */ +#define RCU_INT_PLLI2SSTBIE BIT(13) /*!< PLLI2S Stabilization Interrupt Enable */ +#define RCU_INT_PLLSAISTBIE BIT(14) /*!< PLLSAI Stabilization Interrupt Enable */ +#define RCU_INT_IRC32KSTBIC BIT(16) /*!< IRC32K Stabilization Interrupt Clear */ +#define RCU_INT_LXTALSTBIC BIT(17) /*!< LXTAL Stabilization Interrupt Clear */ +#define RCU_INT_IRC16MSTBIC BIT(18) /*!< IRC16M Stabilization Interrupt Clear */ +#define RCU_INT_HXTALSTBIC BIT(19) /*!< HXTAL Stabilization Interrupt Clear */ +#define RCU_INT_PLLSTBIC BIT(20) /*!< PLL stabilization Interrupt Clear */ +#define RCU_INT_PLLI2SSTBIC BIT(21) /*!< PLLI2S stabilization Interrupt Clear */ +#define RCU_INT_PLLSAISTBIC BIT(22) /*!< PLLSAI stabilization Interrupt Clear */ +#define RCU_INT_CKMIC BIT(23) /*!< HXTAL Clock Stuck Interrupt Clear */ + +/* RCU_AHB1RST */ +#define RCU_AHB1RST_PARST BIT(0) /*!< GPIO port A reset */ +#define RCU_AHB1RST_PBRST BIT(1) /*!< GPIO port B reset */ +#define RCU_AHB1RST_PCRST BIT(2) /*!< GPIO port C reset */ +#define RCU_AHB1RST_PDRST BIT(3) /*!< GPIO port D reset */ +#define RCU_AHB1RST_PERST BIT(4) /*!< GPIO port E reset */ +#define RCU_AHB1RST_PFRST BIT(5) /*!< GPIO port F reset */ +#define RCU_AHB1RST_PGRST BIT(6) /*!< GPIO port G reset */ +#define RCU_AHB1RST_PHRST BIT(7) /*!< GPIO port H reset */ +#define RCU_AHB1RST_PIRST BIT(8) /*!< GPIO port I reset */ +#define RCU_AHB1RST_CRCRST BIT(12) /*!< CRC reset */ +#define RCU_AHB1RST_DMA0RST BIT(21) /*!< DMA0 reset */ +#define RCU_AHB1RST_DMA1RST BIT(22) /*!< DMA1 reset */ +#define RCU_AHB1RST_IPARST BIT(23) /*!< IPA reset */ +#define RCU_AHB1RST_ENETRST BIT(25) /*!< ENET reset */ +#define RCU_AHB1RST_USBHSRST BIT(29) /*!< USBHS reset */ + +/* RCU_AHB2RST */ +#define RCU_AHB2RST_DCIRST BIT(0) /*!< DCI reset */ +#define RCU_AHB2RST_PKCAURST BIT(3) /*!< PKCAU reset */ +#define RCU_AHB2RST_CAURST BIT(4) /*!< CAU reset */ +#define RCU_AHB2RST_HAURST BIT(5) /*!< HAU reset */ +#define RCU_AHB2RST_TRNGRST BIT(6) /*!< TRNG reset */ +#define RCU_AHB2RST_USBFSRST BIT(7) /*!< USBFS reset */ + +/* RCU_AHB3RST */ +#define RCU_AHB3RST_EXMCRST BIT(0) /*!< EXMC reset */ + +/* RCU_APB1RST */ +#define RCU_APB1RST_TIMER1RST BIT(0) /*!< TIMER1 reset */ +#define RCU_APB1RST_TIMER2RST BIT(1) /*!< TIMER2 reset */ +#define RCU_APB1RST_TIMER3RST BIT(2) /*!< TIMER3 reset */ +#define RCU_APB1RST_TIMER4RST BIT(3) /*!< TIMER4 reset */ +#define RCU_APB1RST_TIMER5RST BIT(4) /*!< TIMER5 reset */ +#define RCU_APB1RST_TIMER6RST BIT(5) /*!< TIMER6 reset */ +#define RCU_APB1RST_TIMER11RST BIT(6) /*!< TIMER11 reset */ +#define RCU_APB1RST_TIMER12RST BIT(7) /*!< TIMER12 reset */ +#define RCU_APB1RST_TIMER13RST BIT(8) /*!< TIMER13 reset */ +#define RCU_APB1RST_I2C3RST BIT(10) /*!< I2C3 reset */ +#define RCU_APB1RST_WWDGTRST BIT(11) /*!< WWDGT reset */ +#define RCU_APB1RST_I2C4RST BIT(12) /*!< I2C4 reset */ +#define RCU_APB1RST_I2C5RST BIT(13) /*!< I2C5 reset */ +#define RCU_APB1RST_SPI1RST BIT(14) /*!< SPI1 reset */ +#define RCU_APB1RST_SPI2RST BIT(15) /*!< SPI2 reset */ +#define RCU_APB1RST_USART1RST BIT(17) /*!< USART1 reset */ +#define RCU_APB1RST_USART2RST BIT(18) /*!< USART2 reset */ +#define RCU_APB1RST_UART3RST BIT(19) /*!< UART3 reset */ +#define RCU_APB1RST_UART4RST BIT(20) /*!< UART4 reset */ +#define RCU_APB1RST_I2C0RST BIT(21) /*!< I2C0 reset */ +#define RCU_APB1RST_I2C1RST BIT(22) /*!< I2C1 reset */ +#define RCU_APB1RST_I2C2RST BIT(23) /*!< I2C2 reset */ +#define RCU_APB1RST_CAN0RST BIT(25) /*!< CAN0 reset */ +#define RCU_APB1RST_CAN1RST BIT(26) /*!< CAN1 reset */ +#define RCU_APB1RST_PMURST BIT(28) /*!< PMU reset */ +#define RCU_APB1RST_DACRST BIT(29) /*!< DAC reset */ +#define RCU_APB1RST_UART6RST BIT(30) /*!< UART6 reset */ +#define RCU_APB1RST_UART7RST BIT(31) /*!< UART7 reset */ + +/* RCU_APB2RST */ +#define RCU_APB2RST_TIMER0RST BIT(0) /*!< TIMER0 reset */ +#define RCU_APB2RST_TIMER7RST BIT(1) /*!< TIMER7 reset */ +#define RCU_APB2RST_USART0RST BIT(4) /*!< USART0 reset */ +#define RCU_APB2RST_USART5RST BIT(5) /*!< USART5 reset */ +#define RCU_APB2RST_ADCRST BIT(8) /*!< ADC reset */ +#define RCU_APB2RST_SDIORST BIT(11) /*!< SDIO reset */ +#define RCU_APB2RST_SPI0RST BIT(12) /*!< SPI0 reset */ +#define RCU_APB2RST_SPI3RST BIT(13) /*!< SPI3 reset */ +#define RCU_APB2RST_SYSCFGRST BIT(14) /*!< SYSCFG reset */ +#define RCU_APB2RST_TIMER8RST BIT(16) /*!< TIMER8 reset */ +#define RCU_APB2RST_TIMER9RST BIT(17) /*!< TIMER9 reset */ +#define RCU_APB2RST_TIMER10RST BIT(18) /*!< TIMER10 reset */ +#define RCU_APB2RST_SPI4RST BIT(20) /*!< SPI4 reset */ +#define RCU_APB2RST_SPI5RST BIT(21) /*!< SPI5 reset */ +#define RCU_APB2RST_SAIRST BIT(22) /*!< SAI reset */ +#define RCU_APB2RST_TLIRST BIT(26) /*!< TLI reset */ + +/* RCU_AHB1EN */ +#define RCU_AHB1EN_PAEN BIT(0) /*!< GPIO port A clock enable */ +#define RCU_AHB1EN_PBEN BIT(1) /*!< GPIO port B clock enable */ +#define RCU_AHB1EN_PCEN BIT(2) /*!< GPIO port C clock enable */ +#define RCU_AHB1EN_PDEN BIT(3) /*!< GPIO port D clock enable */ +#define RCU_AHB1EN_PEEN BIT(4) /*!< GPIO port E clock enable */ +#define RCU_AHB1EN_PFEN BIT(5) /*!< GPIO port F clock enable */ +#define RCU_AHB1EN_PGEN BIT(6) /*!< GPIO port G clock enable */ +#define RCU_AHB1EN_PHEN BIT(7) /*!< GPIO port H clock enable */ +#define RCU_AHB1EN_PIEN BIT(8) /*!< GPIO port I clock enable */ +#define RCU_AHB1EN_CRCEN BIT(12) /*!< CRC clock enable */ +#define RCU_AHB1EN_BKPSRAMEN BIT(18) /*!< BKPSRAM clock enable */ +#define RCU_AHB1EN_TCMSRAMEN BIT(20) /*!< TCMSRAM clock enable */ +#define RCU_AHB1EN_DMA0EN BIT(21) /*!< DMA0 clock enable */ +#define RCU_AHB1EN_DMA1EN BIT(22) /*!< DMA1 clock enable */ +#define RCU_AHB1EN_IPAEN BIT(23) /*!< IPA clock enable */ +#define RCU_AHB1EN_ENETEN BIT(25) /*!< ENET clock enable */ +#define RCU_AHB1EN_ENETTXEN BIT(26) /*!< ethernet TX clock enable */ +#define RCU_AHB1EN_ENETRXEN BIT(27) /*!< ethernet RX clock enable */ +#define RCU_AHB1EN_ENETPTPEN BIT(28) /*!< ethernet PTP clock enable */ +#define RCU_AHB1EN_USBHSEN BIT(29) /*!< USBHS clock enable */ +#define RCU_AHB1EN_USBHSULPIEN BIT(30) /*!< USBHS ULPI clock enable */ + +/* RCU_AHB2EN */ +#define RCU_AHB2EN_DCIEN BIT(0) /*!< DCI clock enable */ +#define RCU_AHB2EN_PKCAU BIT(3) /*!< PKCAU clock enable */ +#define RCU_AHB2EN_CAU BIT(4) /*!< CAU clock enable */ +#define RCU_AHB2EN_HAU BIT(5) /*!< HAU clock enable */ +#define RCU_AHB2EN_TRNGEN BIT(6) /*!< TRNG clock enable */ +#define RCU_AHB2EN_USBFSEN BIT(7) /*!< USBFS clock enable */ + +/* RCU_AHB3EN */ +#define RCU_AHB3EN_EXMCEN BIT(0) /*!< EXMC clock enable */ + +/* RCU_APB1EN */ +#define RCU_APB1EN_TIMER1EN BIT(0) /*!< TIMER1 clock enable */ +#define RCU_APB1EN_TIMER2EN BIT(1) /*!< TIMER2 clock enable */ +#define RCU_APB1EN_TIMER3EN BIT(2) /*!< TIMER3 clock enable */ +#define RCU_APB1EN_TIMER4EN BIT(3) /*!< TIMER4 clock enable */ +#define RCU_APB1EN_TIMER5EN BIT(4) /*!< TIMER5 clock enable */ +#define RCU_APB1EN_TIMER6EN BIT(5) /*!< TIMER6 clock enable */ +#define RCU_APB1EN_TIMER11EN BIT(6) /*!< TIMER11 clock enable */ +#define RCU_APB1EN_TIMER12EN BIT(7) /*!< TIMER12 clock enable */ +#define RCU_APB1EN_TIMER13EN BIT(8) /*!< TIMER13 clock enable */ +#define RCU_APB1EN_I2C3EN BIT(10) /*!< I2C3 clock enable */ +#define RCU_APB1EN_WWDGTEN BIT(11) /*!< WWDGT clock enable */ +#define RCU_APB1EN_I2C4EN BIT(12) /*!< I2C4 clock enable */ +#define RCU_APB1EN_I2C5EN BIT(13) /*!< I2C5 clock enable */ +#define RCU_APB1EN_SPI1EN BIT(14) /*!< SPI1 clock enable */ +#define RCU_APB1EN_SPI2EN BIT(15) /*!< SPI2 clock enable */ +#define RCU_APB1EN_USART1EN BIT(17) /*!< USART1 clock enable */ +#define RCU_APB1EN_USART2EN BIT(18) /*!< USART2 clock enable */ +#define RCU_APB1EN_UART3EN BIT(19) /*!< UART3 clock enable */ +#define RCU_APB1EN_UART4EN BIT(20) /*!< UART4 clock enable */ +#define RCU_APB1EN_I2C0EN BIT(21) /*!< I2C0 clock enable */ +#define RCU_APB1EN_I2C1EN BIT(22) /*!< I2C1 clock enable */ +#define RCU_APB1EN_I2C2EN BIT(23) /*!< I2C2 clock enable */ +#define RCU_APB1EN_CAN0EN BIT(25) /*!< CAN0 clock enable */ +#define RCU_APB1EN_CAN1EN BIT(26) /*!< CAN1 clock enable */ +#define RCU_APB1EN_PMUEN BIT(28) /*!< PMU clock enable */ +#define RCU_APB1EN_DACEN BIT(29) /*!< DAC clock enable */ +#define RCU_APB1EN_UART6EN BIT(30) /*!< UART6 clock enable */ +#define RCU_APB1EN_UART7EN BIT(31) /*!< UART7 clock enable */ + +/* RCU_APB2EN */ +#define RCU_APB2EN_TIMER0EN BIT(0) /*!< TIMER0 clock enable */ +#define RCU_APB2EN_TIMER7EN BIT(1) /*!< TIMER7 clock enable */ +#define RCU_APB2EN_USART0EN BIT(4) /*!< USART0 clock enable */ +#define RCU_APB2EN_USART5EN BIT(5) /*!< USART5 clock enable */ +#define RCU_APB2EN_ADC0EN BIT(8) /*!< ADC0 clock enable */ +#define RCU_APB2EN_ADC1EN BIT(9) /*!< ADC1 clock enable */ +#define RCU_APB2EN_ADC2EN BIT(10) /*!< ADC2 clock enable */ +#define RCU_APB2EN_SDIOEN BIT(11) /*!< SDIO clock enable */ +#define RCU_APB2EN_SPI0EN BIT(12) /*!< SPI0 clock enable */ +#define RCU_APB2EN_SPI3EN BIT(13) /*!< SPI3 clock enable */ +#define RCU_APB2EN_SYSCFGEN BIT(14) /*!< SYSCFG clock enable */ +#define RCU_APB2EN_TIMER8EN BIT(16) /*!< TIMER8 clock enable */ +#define RCU_APB2EN_TIMER9EN BIT(17) /*!< TIMER9 clock enable */ +#define RCU_APB2EN_TIMER10EN BIT(18) /*!< TIMER10 clock enable */ +#define RCU_APB2EN_SPI4EN BIT(20) /*!< SPI4 clock enable */ +#define RCU_APB2EN_SPI5EN BIT(21) /*!< SPI5 clock enable */ +#define RCU_APB2EN_SAIEN BIT(22) /*!< SAI clock enable */ +#define RCU_APB2EN_TLIEN BIT(26) /*!< TLI clock enable */ + +/* RCU_AHB1SPEN */ +#define RCU_AHB1SPEN_PASPEN BIT(0) /*!< GPIO port A clock enable when sleep mode */ +#define RCU_AHB1SPEN_PBSPEN BIT(1) /*!< GPIO port B clock enable when sleep mode */ +#define RCU_AHB1SPEN_PCSPEN BIT(2) /*!< GPIO port C clock enable when sleep mode */ +#define RCU_AHB1SPEN_PDSPEN BIT(3) /*!< GPIO port D clock enable when sleep mode */ +#define RCU_AHB1SPEN_PESPEN BIT(4) /*!< GPIO port E clock enable when sleep mode */ +#define RCU_AHB1SPEN_PFSPEN BIT(5) /*!< GPIO port F clock enable when sleep mode */ +#define RCU_AHB1SPEN_PGSPEN BIT(6) /*!< GPIO port G clock enable when sleep mode */ +#define RCU_AHB1SPEN_PHSPEN BIT(7) /*!< GPIO port H clock enable when sleep mode */ +#define RCU_AHB1SPEN_PISPEN BIT(8) /*!< GPIO port I clock enable when sleep mode */ +#define RCU_AHB1SPEN_CRCSPEN BIT(12) /*!< CRC clock enable when sleep mode */ +#define RCU_AHB1SPEN_FMCSPEN BIT(15) /*!< FMC clock enable when sleep mode */ +#define RCU_AHB1SPEN_SRAM0SPEN BIT(16) /*!< SRAM0 clock enable when sleep mode */ +#define RCU_AHB1SPEN_SRAM1SPEN BIT(17) /*!< SRAM1 clock enable when sleep mode */ +#define RCU_AHB1SPEN_BKPSRAMSPEN BIT(18) /*!< BKPSRAM clock enable when sleep mode */ +#define RCU_AHB1SPEN_SRAM2SPEN BIT(19) /*!< SRAM2 clock enable when sleep mode */ +#define RCU_AHB1SPEN_DMA0SPEN BIT(21) /*!< DMA0 clock when sleep mode enable */ +#define RCU_AHB1SPEN_DMA1SPEN BIT(22) /*!< DMA1 clock when sleep mode enable */ +#define RCU_AHB1SPEN_IPASPEN BIT(23) /*!< IPA clock enable when sleep mode */ +#define RCU_AHB1SPEN_ENETSPEN BIT(25) /*!< ENET clock enable when sleep mode */ +#define RCU_AHB1SPEN_ENETTXSPEN BIT(26) /*!< ethernet TX clock enable when sleep mode */ +#define RCU_AHB1SPEN_ENETRXSPEN BIT(27) /*!< ethernet RX clock enable when sleep mode */ +#define RCU_AHB1SPEN_ENETPTPSPEN BIT(28) /*!< ethernet PTP clock enable when sleep mode */ +#define RCU_AHB1SPEN_USBHSSPEN BIT(29) /*!< USBHS clock enable when sleep mode */ +#define RCU_AHB1SPEN_USBHSULPISPEN BIT(30) /*!< USBHS ULPI clock enable when sleep mode */ + +/* RCU_AHB2SPEN */ +#define RCU_AHB2SPEN_DCISPEN BIT(0) /*!< DCI clock enable when sleep mode */ +#define RCU_AHB2SPEN_PKCAUSPEN BIT(3) /*!< PKCAU clock enable when sleep mode */ +#define RCU_AHB2SPEN_CAUSPEN BIT(4) /*!< CAU clock enable when sleep mode */ +#define RCU_AHB2SPEN_HAUSPEN BIT(5) /*!< HAU clock enable when sleep mode */ +#define RCU_AHB2SPEN_TRNGSPEN BIT(6) /*!< TRNG clock enable when sleep mode */ +#define RCU_AHB2SPEN_USBFSSPEN BIT(7) /*!< USBFS clock enable when sleep mode */ + +/* RCU_AHB3SPEN */ +#define RCU_AHB3SPEN_EXMCSPEN BIT(0) /*!< EXMC clock enable when sleep mode */ + +/* RCU_APB1SPEN */ +#define RCU_APB1SPEN_TIMER1SPEN BIT(0) /*!< TIMER1 clock enable when sleep mode */ +#define RCU_APB1SPEN_TIMER2SPEN BIT(1) /*!< TIMER2 clock enable when sleep mode */ +#define RCU_APB1SPEN_TIMER3SPEN BIT(2) /*!< TIMER3 clock enable when sleep mode */ +#define RCU_APB1SPEN_TIMER4SPEN BIT(3) /*!< TIMER4 clock enable when sleep mode */ +#define RCU_APB1SPEN_TIMER5SPEN BIT(4) /*!< TIMER5 clock enable when sleep mode */ +#define RCU_APB1SPEN_TIMER6SPEN BIT(5) /*!< TIMER6 clock enable when sleep mode */ +#define RCU_APB1SPEN_TIMER11SPEN BIT(6) /*!< TIMER11 clock enable when sleep mode */ +#define RCU_APB1SPEN_TIMER12SPEN BIT(7) /*!< TIMER12 clock enable when sleep mode */ +#define RCU_APB1SPEN_TIMER13SPEN BIT(8) /*!< TIMER13 clock enable when sleep mode */ +#define RCU_APB1SPEN_I2C3SPEN BIT(10) /*!< I2C3 clock enable when sleep mode */ +#define RCU_APB1SPEN_WWDGTSPEN BIT(11) /*!< WWDGT clock enable when sleep mode */ +#define RCU_APB1SPEN_I2C4SPEN BIT(12) /*!< I2C4 clock enable when sleep mode */ +#define RCU_APB1SPEN_I2C5SPEN BIT(13) /*!< I2C5 clock enable when sleep mode*/ +#define RCU_APB1SPEN_SPI1SPEN BIT(14) /*!< SPI1 clock enable when sleep mode */ +#define RCU_APB1SPEN_SPI2SPEN BIT(15) /*!< SPI2 clock enable when sleep mode */ +#define RCU_APB1SPEN_USART1SPEN BIT(17) /*!< USART1 clock enable when sleep mode*/ +#define RCU_APB1SPEN_USART2SPEN BIT(18) /*!< USART2 clock enable when sleep mode*/ +#define RCU_APB1SPEN_UART3SPEN BIT(19) /*!< UART3 clock enable when sleep mode*/ +#define RCU_APB1SPEN_UART4SPEN BIT(20) /*!< UART4 clock enable when sleep mode */ +#define RCU_APB1SPEN_I2C0SPEN BIT(21) /*!< I2C0 clock enable when sleep mode */ +#define RCU_APB1SPEN_I2C1SPEN BIT(22) /*!< I2C1 clock enable when sleep mode*/ +#define RCU_APB1SPEN_I2C2SPEN BIT(23) /*!< I2C2 clock enable when sleep mode */ +#define RCU_APB1SPEN_CAN0SPEN BIT(25) /*!< CAN0 clock enable when sleep mode*/ +#define RCU_APB1SPEN_CAN1SPEN BIT(26) /*!< CAN1 clock enable when sleep mode */ +#define RCU_APB1SPEN_PMUSPEN BIT(28) /*!< PMU clock enable when sleep mode */ +#define RCU_APB1SPEN_DACSPEN BIT(29) /*!< DAC clock enable when sleep mode */ +#define RCU_APB1SPEN_UART6SPEN BIT(30) /*!< UART6 clock enable when sleep mode */ +#define RCU_APB1SPEN_UART7SPEN BIT(31) /*!< UART7 clock enable when sleep mode */ + +/* RCU_APB2SPEN */ +#define RCU_APB2SPEN_TIMER0SPEN BIT(0) /*!< TIMER0 clock enable when sleep mode */ +#define RCU_APB2SPEN_TIMER7SPEN BIT(1) /*!< TIMER7 clock enable when sleep mode */ +#define RCU_APB2SPEN_USART0SPEN BIT(4) /*!< USART0 clock enable when sleep mode */ +#define RCU_APB2SPEN_USART5SPEN BIT(5) /*!< USART5 clock enable when sleep mode */ +#define RCU_APB2SPEN_ADC0SPEN BIT(8) /*!< ADC0 clock enable when sleep mode */ +#define RCU_APB2SPEN_ADC1SPEN BIT(9) /*!< ADC1 clock enable when sleep mode */ +#define RCU_APB2SPEN_ADC2SPEN BIT(10) /*!< ADC2 clock enable when sleep mode */ +#define RCU_APB2SPEN_SDIOSPEN BIT(11) /*!< SDIO clock enable when sleep mode */ +#define RCU_APB2SPEN_SPI0SPEN BIT(12) /*!< SPI0 clock enable when sleep mode */ +#define RCU_APB2SPEN_SPI3SPEN BIT(13) /*!< SPI3 clock enable when sleep mode */ +#define RCU_APB2SPEN_SYSCFGSPEN BIT(14) /*!< SYSCFG clock enable when sleep mode */ +#define RCU_APB2SPEN_TIMER8SPEN BIT(16) /*!< TIMER8 clock enable when sleep mode */ +#define RCU_APB2SPEN_TIMER9SPEN BIT(17) /*!< TIMER9 clock enable when sleep mode */ +#define RCU_APB2SPEN_TIMER10SPEN BIT(18) /*!< TIMER10 clock enable when sleep mode */ +#define RCU_APB2SPEN_SPI4SPEN BIT(20) /*!< SPI4 clock enable when sleep mode */ +#define RCU_APB2SPEN_SPI5SPEN BIT(21) /*!< SPI5 clock enable when sleep mode */ +#define RCU_APB2SPEN_SAISPEN BIT(22) /*!< SAI clock enable when sleep mode */ +#define RCU_APB2SPEN_TLISPEN BIT(26) /*!< TLI clock enable when sleep mode*/ + +/* RCU_BDCTL */ +#define RCU_BDCTL_LXTALEN BIT(0) /*!< LXTAL enable */ +#define RCU_BDCTL_LXTALSTB BIT(1) /*!< low speed crystal oscillator stabilization flag */ +#define RCU_BDCTL_LXTALBPS BIT(2) /*!< LXTAL bypass mode enable */ +#define RCU_BDCTL_LXTALDRI BIT(3) /*!< LXTAL drive capability */ +#define RCU_BDCTL_RTCSRC BITS(8,9) /*!< RTC clock entry selection */ +#define RCU_BDCTL_RTCEN BIT(15) /*!< RTC clock enable */ +#define RCU_BDCTL_BKPRST BIT(16) /*!< backup domain reset */ + +/* RCU_RSTSCK */ +#define RCU_RSTSCK_IRC32KEN BIT(0) /*!< IRC32K enable */ +#define RCU_RSTSCK_IRC32KSTB BIT(1) /*!< IRC32K stabilization flag */ +#define RCU_RSTSCK_RSTFC BIT(24) /*!< reset flag clear */ +#define RCU_RSTSCK_BORRSTF BIT(25) /*!< BOR reset flag */ +#define RCU_RSTSCK_EPRSTF BIT(26) /*!< external pin reset flag */ +#define RCU_RSTSCK_PORRSTF BIT(27) /*!< power reset flag */ +#define RCU_RSTSCK_SWRSTF BIT(28) /*!< software reset flag */ +#define RCU_RSTSCK_FWDGTRSTF BIT(29) /*!< free watchdog timer reset flag */ +#define RCU_RSTSCK_WWDGTRSTF BIT(30) /*!< window watchdog timer reset flag */ +#define RCU_RSTSCK_LPRSTF BIT(31) /*!< low-power reset flag */ + +/* RCU_PLLSSCTL */ +#define RCU_PLLSSCTL_MODCNT BITS(0,12) /*!< these bits configure PLL spread spectrum modulation + profile amplitude and frequency. the following criteria + must be met: MODSTEP*MODCNT=215-1 */ +#define RCU_PLLSSCTL_MODSTEP BITS(13,27) /*!< these bits configure PLL spread spectrum modulation + profile amplitude and frequency. the following criteria + must be met: MODSTEP*MODCNT=215-1 */ +#define RCU_PLLSSCTL_SS_TYPE BIT(30) /*!< PLL spread spectrum modulation type select */ +#define RCU_PLLSSCTL_SSCGON BIT(31) /*!< PLL spread spectrum modulation enable */ + +/* RCU_PLLI2S */ +#define RCU_PLLI2S_PLLI2SN BITS(6,14) /*!< the PLLI2S VCO clock multi factor */ +#define RCU_PLLI2S_PLLI2SQ BITS(24,27) /*!< the PLLI2S Q output frequency division factor from PLLI2S VCO clock */ +#define RCU_PLLI2S_PLLI2SR BITS(28,30) /*!< the PLLI2S R output frequency division factor from PLLI2S VCO clock */ + +/* RCU_PLLSAI */ +#define RCU_PLLSAI_PLLSAIN BITS(6,14) /*!< the PLLSAI VCO clock multi factor */ +#define RCU_PLLSAI_PLLSAIP BITS(16,17) /*!< the PLLSAI P output frequency division factor from PLLSAI VCO clock */ +#define RCU_PLLSAI_PLLSAIQ BITS(24,27) /*!< the PLLSAI Q output frequency division factor from PLLSAI VCO clock */ +#define RCU_PLLSAI_PLLSAIR BITS(28,30) /*!< the PLLSAI R output frequency division factor from PLLSAI VCO clock */ + +/* RCU_CFG1 */ +#define RCU_CFG1_PLLSAIRDIV BITS(16,17) /*!< the divider factor from PLLSAIR clock */ + +/* RCU_SAISEL */ +#define RCU_CFG1_SAISEL BITS(20,21) /*!< SAI clock selection */ +#define RCU_CFG1_TIMERSEL BIT(24) /*!< TIMER clock selection */ + +/* RCU_CFG2 */ +#define RCU_CFG2_I2C3SEL BITS(0,1) /*!< I2C3 clock source selection */ +#define RCU_CFG2_I2C4SEL BITS(2,3) /*!< I2C4 clock source selection */ +#define RCU_CFG2_I2C5SEL BITS(4,5) /*!< I2C5 clock source selection */ + +/* RCU_ADDCTL */ +#define RCU_ADDCTL_CK48MSEL BIT(0) /*!< 48MHz clock selection */ +#define RCU_ADDCTL_PLL48MSEL BIT(1) /*!< PLL48M clock selection */ +#define RCU_ADDCTL_IRC48MEN BIT(16) /*!< internal 48MHz RC oscillator enable */ +#define RCU_ADDCTL_IRC48MSTB BIT(17) /*!< internal 48MHz RC oscillator clock stabilization flag */ +#define RCU_ADDCTL_IRC48MCAL BITS(24,31) /*!< internal 48MHz RC oscillator calibration value register */ + +/* RCU_ADDINT */ +#define RCU_ADDINT_IRC48MSTBIF BIT(6) /*!< IRC48M stabilization interrupt flag */ +#define RCU_ADDINT_IRC48MSTBIE BIT(14) /*!< internal 48 MHz RC oscillator stabilization interrupt enable */ +#define RCU_ADDINT_IRC48MSTBIC BIT(22) /*!< internal 48 MHz RC oscillator stabilization interrupt clear */ + +/* RCU_ADDAPB1RST */ +#define RCU_ADDAPB1RST_CTCRST BIT(27) /*!< CTC reset */ +#define RCU_ADDAPB1RST_IREFRST BIT(31) /*!< IREF reset */ + +/* RCU_ADDAPB1EN */ +#define RCU_ADDAPB1EN_CTCEN BIT(27) /*!< CTC clock enable */ +#define RCU_ADDAPB1EN_IREFEN BIT(31) /*!< IREF interface clock enable */ + +/* RCU_ADDAPB1SPEN */ +#define RCU_ADDAPB1SPEN_CTCSPEN BIT(27) /*!< CTC clock enable during sleep mode */ +#define RCU_ADDAPB1SPEN_IREFSPEN BIT(31) /*!< IREF interface clock enable during sleep mode */ + +/* RCU_VKEY */ +#define RCU_VKEY_KEY BITS(0,31) /*!< RCU_DSV key register */ + +/* RCU_DSV */ +#define RCU_DSV_DSLPVS BITS(0,2) /*!< deep-sleep mode voltage select */ + +/* constants definitions */ +/* define the peripheral clock enable bit position and its register index offset */ +#define RCU_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)) +#define RCU_REG_VAL(periph) (REG32(RCU + ((uint32_t)(periph) >> 6))) +#define RCU_BIT_POS(val) ((uint32_t)(val) & 0x1FU) +/* define the voltage key unlock value */ +#define RCU_VKEY_UNLOCK ((uint32_t)0x1A2B3C4DU) + +/* register offset */ +/* peripherals enable */ +#define AHB1EN_REG_OFFSET 0x30U /*!< AHB1 enable register offset */ +#define AHB2EN_REG_OFFSET 0x34U /*!< AHB2 enable register offset */ +#define AHB3EN_REG_OFFSET 0x38U /*!< AHB3 enable register offset */ +#define APB1EN_REG_OFFSET 0x40U /*!< APB1 enable register offset */ +#define APB2EN_REG_OFFSET 0x44U /*!< APB2 enable register offset */ +#define AHB1SPEN_REG_OFFSET 0x50U /*!< AHB1 sleep mode enable register offset */ +#define AHB2SPEN_REG_OFFSET 0x54U /*!< AHB2 sleep mode enable register offset */ +#define AHB3SPEN_REG_OFFSET 0x58U /*!< AHB3 sleep mode enable register offset */ +#define APB1SPEN_REG_OFFSET 0x60U /*!< APB1 sleep mode enable register offset */ +#define APB2SPEN_REG_OFFSET 0x64U /*!< APB2 sleep mode enable register offset */ +#define ADD_APB1EN_REG_OFFSET 0xE4U /*!< APB1 additional enable register offset */ +#define ADD_APB1SPEN_REG_OFFSET 0xE8U /*!< APB1 additional sleep mode enable register offset */ + +/* peripherals reset */ +#define AHB1RST_REG_OFFSET 0x10U /*!< AHB1 reset register offset */ +#define AHB2RST_REG_OFFSET 0x14U /*!< AHB2 reset register offset */ +#define AHB3RST_REG_OFFSET 0x18U /*!< AHB3 reset register offset */ +#define APB1RST_REG_OFFSET 0x20U /*!< APB1 reset register offset */ +#define APB2RST_REG_OFFSET 0x24U /*!< APB2 reset register offset */ +#define ADD_APB1RST_REG_OFFSET 0xE0U /*!< APB1 additional reset register offset */ +#define RSTSCK_REG_OFFSET 0x74U /*!< reset source/clock register offset */ + +/* clock control */ +#define CTL_REG_OFFSET 0x00U /*!< control register offset */ +#define BDCTL_REG_OFFSET 0x70U /*!< backup domain control register offset */ +#define ADDCTL_REG_OFFSET 0xC0U /*!< additional clock control register offset */ + +/* clock stabilization and stuck interrupt */ +#define INT_REG_OFFSET 0x0CU /*!< clock interrupt register offset */ +#define ADDINT_REG_OFFSET 0xCCU /*!< additional clock interrupt register offset */ + +/* configuration register */ +#define PLL_REG_OFFSET 0x04U /*!< PLL register offset */ +#define CFG0_REG_OFFSET 0x08U /*!< clock configuration register 0 offset */ +#define PLLSSCTL_REG_OFFSET 0x80U /*!< PLL clock spread spectrum control register offset */ +#define PLLI2S_REG_OFFSET 0x84U /*!< PLLI2S register offset */ +#define PLLSAI_REG_OFFSET 0x88U /*!< PLLSAI register offset */ +#define CFG1_REG_OFFSET 0x8CU /*!< clock configuration register 1 offset */ + +/* peripheral clock enable */ +typedef enum +{ + /* AHB1 peripherals */ + RCU_GPIOA = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 0U), /*!< GPIOA clock */ + RCU_GPIOB = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 1U), /*!< GPIOB clock */ + RCU_GPIOC = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 2U), /*!< GPIOC clock */ + RCU_GPIOD = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 3U), /*!< GPIOD clock */ + RCU_GPIOE = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 4U), /*!< GPIOE clock */ + RCU_GPIOF = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 5U), /*!< GPIOF clock */ + RCU_GPIOG = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 6U), /*!< GPIOG clock */ + RCU_GPIOH = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 7U), /*!< GPIOH clock */ + RCU_GPIOI = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 8U), /*!< GPIOI clock */ + RCU_CRC = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 12U), /*!< CRC clock */ + RCU_BKPSRAM = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 18U), /*!< BKPSRAM clock */ + RCU_TCMSRAM = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 20U), /*!< TCMSRAM clock */ + RCU_DMA0 = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 21U), /*!< DMA0 clock */ + RCU_DMA1 = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 22U), /*!< DMA1 clock */ + RCU_IPA = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 23U), /*!< IPA clock */ + RCU_ENET = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 25U), /*!< ENET clock */ + RCU_ENETTX = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 26U), /*!< ENETTX clock */ + RCU_ENETRX = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 27U), /*!< ENETRX clock */ + RCU_ENETPTP = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 28U), /*!< ENETPTP clock */ + RCU_USBHS = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 29U), /*!< USBHS clock */ + RCU_USBHSULPI = RCU_REGIDX_BIT(AHB1EN_REG_OFFSET, 30U), /*!< USBHSULPI clock */ + /* AHB2 peripherals */ + RCU_DCI = RCU_REGIDX_BIT(AHB2EN_REG_OFFSET, 0U), /*!< DCI clock */ + RCU_PKCAU = RCU_REGIDX_BIT(AHB2EN_REG_OFFSET, 3U), /*!< PKCAU clock */ + RCU_CAU = RCU_REGIDX_BIT(AHB2EN_REG_OFFSET, 4U), /*!< CAU clock */ + RCU_HAU = RCU_REGIDX_BIT(AHB2EN_REG_OFFSET, 5U), /*!< HAU clock */ + RCU_TRNG = RCU_REGIDX_BIT(AHB2EN_REG_OFFSET, 6U), /*!< TRNG clock */ + RCU_USBFS = RCU_REGIDX_BIT(AHB2EN_REG_OFFSET, 7U), /*!< USBFS clock */ + /* AHB3 peripherals */ + RCU_EXMC = RCU_REGIDX_BIT(AHB3EN_REG_OFFSET, 0U), /*!< EXMC clock */ + /* APB1 peripherals */ + RCU_TIMER1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 0U), /*!< TIMER1 clock */ + RCU_TIMER2 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 1U), /*!< TIMER2 clock */ + RCU_TIMER3 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 2U), /*!< TIMER3 clock */ + RCU_TIMER4 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 3U), /*!< TIMER4 clock */ + RCU_TIMER5 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 4U), /*!< TIMER5 clock */ + RCU_TIMER6 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 5U), /*!< TIMER6 clock */ + RCU_TIMER11 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 6U), /*!< TIMER11 clock */ + RCU_TIMER12 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 7U), /*!< TIMER12 clock */ + RCU_TIMER13 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 8U), /*!< TIMER13 clock */ + RCU_I2C3 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 10U), /*!< I2C3 clock */ + RCU_WWDGT = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 11U), /*!< WWDGT clock */ + RCU_I2C4 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 12U), /*!< I2C4 clock */ + RCU_I2C5 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 13U), /*!< I2C5 clock */ + RCU_SPI1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 14U), /*!< SPI1 clock */ + RCU_SPI2 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 15U), /*!< SPI2 clock */ + RCU_USART1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 17U), /*!< USART1 clock */ + RCU_USART2 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 18U), /*!< USART2 clock */ + RCU_UART3 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 19U), /*!< UART3 clock */ + RCU_UART4 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 20U), /*!< UART4 clock */ + RCU_I2C0 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 21U), /*!< I2C0 clock */ + RCU_I2C1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 22U), /*!< I2C1 clock */ + RCU_I2C2 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 23U), /*!< I2C2 clock */ + RCU_CAN0 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 25U), /*!< CAN0 clock */ + RCU_CAN1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 26U), /*!< CAN1 clock */ + RCU_PMU = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 28U), /*!< PMU clock */ + RCU_DAC = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 29U), /*!< DAC clock */ + RCU_UART6 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 30U), /*!< UART6 clock */ + RCU_UART7 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 31U), /*!< UART7 clock */ + RCU_RTC = RCU_REGIDX_BIT(BDCTL_REG_OFFSET, 15U), /*!< RTC clock */ + /* APB2 peripherals */ + RCU_TIMER0 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 0U), /*!< TIMER0 clock */ + RCU_TIMER7 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 1U), /*!< TIMER7 clock */ + RCU_USART0 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 4U), /*!< USART0 clock */ + RCU_USART5 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 5U), /*!< USART5 clock */ + RCU_ADC0 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 8U), /*!< ADC0 clock */ + RCU_ADC1 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 9U), /*!< ADC1 clock */ + RCU_ADC2 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 10U), /*!< ADC2 clock */ + RCU_SDIO = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 11U), /*!< SDIO clock */ + RCU_SPI0 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 12U), /*!< SPI0 clock */ + RCU_SPI3 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 13U), /*!< SPI3 clock */ + RCU_SYSCFG = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 14U), /*!< SYSCFG clock */ + RCU_TIMER8 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 16U), /*!< TIMER8 clock */ + RCU_TIMER9 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 17U), /*!< TIMER9 clock */ + RCU_TIMER10 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 18U), /*!< TIMER10 clock */ + RCU_SPI4 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 20U), /*!< SPI4 clock */ + RCU_SPI5 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 21U), /*!< SPI5 clock */ + RCU_SAI = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 22U), /*!< SAI clock */ + RCU_TLI = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 26U), /*!< TLI clock */ + /* APB1 additional peripherals */ + RCU_CTC = RCU_REGIDX_BIT(ADD_APB1EN_REG_OFFSET, 27U), /*!< CTC clock */ + RCU_IREF = RCU_REGIDX_BIT(ADD_APB1EN_REG_OFFSET, 31U), /*!< IREF clock */ +}rcu_periph_enum; + +/* peripheral clock enable when sleep mode*/ +typedef enum +{ + /* AHB1 peripherals */ + RCU_GPIOA_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 0U), /*!< GPIOA clock */ + RCU_GPIOB_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 1U), /*!< GPIOB clock */ + RCU_GPIOC_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 2U), /*!< GPIOC clock */ + RCU_GPIOD_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 3U), /*!< GPIOD clock */ + RCU_GPIOE_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 4U), /*!< GPIOE clock */ + RCU_GPIOF_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 5U), /*!< GPIOF clock */ + RCU_GPIOG_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 6U), /*!< GPIOG clock */ + RCU_GPIOH_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 7U), /*!< GPIOH clock */ + RCU_GPIOI_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 8U), /*!< GPIOI clock */ + RCU_CRC_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 12U), /*!< CRC clock */ + RCU_FMC_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 15U), /*!< FMC clock */ + RCU_SRAM0_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 16U), /*!< SRAM0 clock */ + RCU_SRAM1_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 17U), /*!< SRAM1 clock */ + RCU_BKPSRAM_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 18U), /*!< BKPSRAM clock */ + RCU_SRAM2_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 19U), /*!< SRAM2 clock */ + RCU_DMA0_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 21U), /*!< DMA0 clock */ + RCU_DMA1_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 22U), /*!< DMA1 clock */ + RCU_IPA_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 23U), /*!< IPA clock */ + RCU_ENET_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 25U), /*!< ENET clock */ + RCU_ENETTX_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 26U), /*!< ENETTX clock */ + RCU_ENETRX_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 27U), /*!< ENETRX clock */ + RCU_ENETPTP_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 28U), /*!< ENETPTP clock */ + RCU_USBHS_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 29U), /*!< USBHS clock */ + RCU_USBHSULPI_SLP = RCU_REGIDX_BIT(AHB1SPEN_REG_OFFSET, 30U), /*!< USBHSULPI clock */ + /* AHB2 peripherals */ + RCU_DCI_SLP = RCU_REGIDX_BIT(AHB2SPEN_REG_OFFSET, 0U), /*!< DCI clock */ + RCU_PKCAU_SLP = RCU_REGIDX_BIT(AHB2SPEN_REG_OFFSET, 3U), /*!< PKCAU clock */ + RCU_CAU_SLP = RCU_REGIDX_BIT(AHB2SPEN_REG_OFFSET, 4U), /*!< CAU clock */ + RCU_HAU_SLP = RCU_REGIDX_BIT(AHB2SPEN_REG_OFFSET, 5U), /*!< HAU clock */ + RCU_TRNG_SLP = RCU_REGIDX_BIT(AHB2SPEN_REG_OFFSET, 6U), /*!< TRNG clock */ + RCU_USBFS_SLP = RCU_REGIDX_BIT(AHB2SPEN_REG_OFFSET, 7U), /*!< USBFS clock */ + /* AHB3 peripherals */ + RCU_EXMC_SLP = RCU_REGIDX_BIT(AHB3SPEN_REG_OFFSET, 0U), /*!< EXMC clock */ + /* APB1 peripherals */ + RCU_TIMER1_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 0U), /*!< TIMER1 clock */ + RCU_TIMER2_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 1U), /*!< TIMER2 clock */ + RCU_TIMER3_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 2U), /*!< TIMER3 clock */ + RCU_TIMER4_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 3U), /*!< TIMER4 clock */ + RCU_TIMER5_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 4U), /*!< TIMER5 clock */ + RCU_TIMER6_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 5U), /*!< TIMER6 clock */ + RCU_TIMER11_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 6U), /*!< TIMER11 clock */ + RCU_TIMER12_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 7U), /*!< TIMER12 clock */ + RCU_TIMER13_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 8U), /*!< TIMER13 clock */ + RCU_I2C3_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 10U), /*!< I2C3 clock */ + RCU_WWDGT_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 11U), /*!< WWDGT clock */ + RCU_I2C4_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 12U), /*!< I2C4 clock */ + RCU_I2C5_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 13U), /*!< I2C5 clock */ + RCU_SPI1_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 14U), /*!< SPI1 clock */ + RCU_SPI2_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 15U), /*!< SPI2 clock */ + RCU_USART1_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 17U), /*!< USART1 clock */ + RCU_USART2_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 18U), /*!< USART2 clock */ + RCU_UART3_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 19U), /*!< UART3 clock */ + RCU_UART4_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 20U), /*!< UART4 clock */ + RCU_I2C0_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 21U), /*!< I2C0 clock */ + RCU_I2C1_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 22U), /*!< I2C1 clock */ + RCU_I2C2_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 23U), /*!< I2C2 clock */ + RCU_CAN0_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 25U), /*!< CAN0 clock */ + RCU_CAN1_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 26U), /*!< CAN1 clock */ + RCU_PMU_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 28U), /*!< PMU clock */ + RCU_DAC_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 29U), /*!< DAC clock */ + RCU_UART6_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 30U), /*!< UART6 clock */ + RCU_UART7_SLP = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 31U), /*!< UART7 clock */ + /* APB2 peripherals */ + RCU_TIMER0_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 0U), /*!< TIMER0 clock */ + RCU_TIMER7_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 1U), /*!< TIMER7 clock */ + RCU_USART0_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 4U), /*!< USART0 clock */ + RCU_USART5_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 5U), /*!< USART5 clock */ + RCU_ADC0_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 8U), /*!< ADC0 clock */ + RCU_ADC1_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 9U), /*!< ADC1 clock */ + RCU_ADC2_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 10U), /*!< ADC2 clock */ + RCU_SDIO_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 11U), /*!< SDIO clock */ + RCU_SPI0_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 12U), /*!< SPI0 clock */ + RCU_SPI3_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 13U), /*!< SPI3 clock */ + RCU_SYSCFG_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 14U), /*!< SYSCFG clock */ + RCU_TIMER8_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 16U), /*!< TIMER8 clock */ + RCU_TIMER9_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 17U), /*!< TIMER9 clock */ + RCU_TIMER10_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 18U), /*!< TIMER10 clock */ + RCU_SPI4_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 20U), /*!< SPI4 clock */ + RCU_SPI5_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 21U), /*!< SPI5 clock */ + RCU_SAI_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 22U), /*!< SAI clock */ + RCU_TLI_SLP = RCU_REGIDX_BIT(APB2SPEN_REG_OFFSET, 26U), /*!< TLI clock */ + /* APB1 additional peripherals */ + RCU_CTC_SLP = RCU_REGIDX_BIT(ADD_APB1SPEN_REG_OFFSET, 27U), /*!< CTC clock */ + RCU_IREF_SLP = RCU_REGIDX_BIT(ADD_APB1SPEN_REG_OFFSET, 31U), /*!< IREF clock */ +}rcu_periph_sleep_enum; + +/* peripherals reset */ +typedef enum +{ + /* AHB1 peripherals */ + RCU_GPIOARST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 0U), /*!< GPIOA clock reset */ + RCU_GPIOBRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 1U), /*!< GPIOB clock reset */ + RCU_GPIOCRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 2U), /*!< GPIOC clock reset */ + RCU_GPIODRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 3U), /*!< GPIOD clock reset */ + RCU_GPIOERST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 4U), /*!< GPIOE clock reset */ + RCU_GPIOFRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 5U), /*!< GPIOF clock reset */ + RCU_GPIOGRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 6U), /*!< GPIOG clock reset */ + RCU_GPIOHRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 7U), /*!< GPIOH clock reset */ + RCU_GPIOIRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 8U), /*!< GPIOI clock reset */ + RCU_CRCRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 12U), /*!< CRC clock reset */ + RCU_DMA0RST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 21U), /*!< DMA0 clock reset */ + RCU_DMA1RST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 22U), /*!< DMA1 clock reset */ + RCU_IPARST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 23U), /*!< IPA clock reset */ + RCU_ENETRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 25U), /*!< ENET clock reset */ + RCU_USBHSRST = RCU_REGIDX_BIT(AHB1RST_REG_OFFSET, 29U), /*!< USBHS clock reset */ + /* AHB2 peripherals */ + RCU_DCIRST = RCU_REGIDX_BIT(AHB2RST_REG_OFFSET, 0U), /*!< DCI clock reset */ + RCU_PKCAURST = RCU_REGIDX_BIT(AHB2RST_REG_OFFSET, 3U), /*!< PKCAU clock reset */ + RCU_CAURST = RCU_REGIDX_BIT(AHB2RST_REG_OFFSET, 4U), /*!< CAU clock reset */ + RCU_HAURST = RCU_REGIDX_BIT(AHB2RST_REG_OFFSET, 5U), /*!< HAU clock reset */ + RCU_TRNGRST = RCU_REGIDX_BIT(AHB2RST_REG_OFFSET, 6U), /*!< TRNG clock reset */ + RCU_USBFSRST = RCU_REGIDX_BIT(AHB2RST_REG_OFFSET, 7U), /*!< USBFS clock reset */ + /* AHB3 peripherals */ + RCU_EXMCRST = RCU_REGIDX_BIT(AHB3RST_REG_OFFSET, 0U), /*!< EXMC clock reset */ + /* APB1 peripherals */ + RCU_TIMER1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 0U), /*!< TIMER1 clock reset */ + RCU_TIMER2RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 1U), /*!< TIMER2 clock reset */ + RCU_TIMER3RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 2U), /*!< TIMER3 clock reset */ + RCU_TIMER4RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 3U), /*!< TIMER4 clock reset */ + RCU_TIMER5RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 4U), /*!< TIMER5 clock reset */ + RCU_TIMER6RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 5U), /*!< TIMER6 clock reset */ + RCU_TIMER11RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 6U), /*!< TIMER11 clock reset */ + RCU_TIMER12RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 7U), /*!< TIMER12 clock reset */ + RCU_TIMER13RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 8U), /*!< TIMER13 clock reset */ + RCU_I2C3RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 10U), /*!< I2C3 clock reset */ + RCU_WWDGTRST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 11U), /*!< WWDGT clock reset */ + RCU_I2C4RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 12U), /*!< I2C4 clock reset */ + RCU_I2C5RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 13U), /*!< I2C5 clock reset */ + RCU_SPI1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 14U), /*!< SPI1 clock reset */ + RCU_SPI2RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 15U), /*!< SPI2 clock reset */ + RCU_USART1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 17U), /*!< USART1 clock reset */ + RCU_USART2RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 18U), /*!< USART2 clock reset */ + RCU_UART3RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 19U), /*!< UART3 clock reset */ + RCU_UART4RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 20U), /*!< UART4 clock reset */ + RCU_I2C0RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 21U), /*!< I2C0 clock reset */ + RCU_I2C1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 22U), /*!< I2C1 clock reset */ + RCU_I2C2RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 23U), /*!< I2C2 clock reset */ + RCU_CAN0RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 25U), /*!< CAN0 clock reset */ + RCU_CAN1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 26U), /*!< CAN1 clock reset */ + RCU_PMURST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 28U), /*!< PMU clock reset */ + RCU_DACRST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 29U), /*!< DAC clock reset */ + RCU_UART6RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 30U), /*!< UART6 clock reset */ + RCU_UART7RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 31U), /*!< UART7 clock reset */ + /* APB2 peripherals */ + RCU_TIMER0RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 0U), /*!< TIMER0 clock reset */ + RCU_TIMER7RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 1U), /*!< TIMER7 clock reset */ + RCU_USART0RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 4U), /*!< USART0 clock reset */ + RCU_USART5RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 5U), /*!< USART5 clock reset */ + RCU_ADCRST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 8U), /*!< ADCs all clock reset */ + RCU_SDIORST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 11U), /*!< SDIO clock reset */ + RCU_SPI0RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 12U), /*!< SPI0 clock reset */ + RCU_SPI3RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 13U), /*!< SPI3 clock reset */ + RCU_SYSCFGRST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 14U), /*!< SYSCFG clock reset */ + RCU_TIMER8RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 16U), /*!< TIMER8 clock reset */ + RCU_TIMER9RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 17U), /*!< TIMER9 clock reset */ + RCU_TIMER10RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 18U), /*!< TIMER10 clock reset */ + RCU_SPI4RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 20U), /*!< SPI4 clock reset */ + RCU_SPI5RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 21U), /*!< SPI5 clock reset */ + RCU_SAIRST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 22U), /*!< SAI clock reset */ + RCU_TLIRST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 26U), /*!< TLI clock reset */ + /* APB1 additional peripherals */ + RCU_CTCRST = RCU_REGIDX_BIT(ADD_APB1RST_REG_OFFSET, 27U), /*!< CTC clock reset */ + RCU_IREFRST = RCU_REGIDX_BIT(ADD_APB1RST_REG_OFFSET, 31U) /*!< IREF clock reset */ +}rcu_periph_reset_enum; + +/* clock stabilization and peripheral reset flags */ +typedef enum +{ + /* clock stabilization flags */ + RCU_FLAG_IRC16MSTB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 1U), /*!< IRC16M stabilization flags */ + RCU_FLAG_HXTALSTB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 17U), /*!< HXTAL stabilization flags */ + RCU_FLAG_PLLSTB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 25U), /*!< PLL stabilization flags */ + RCU_FLAG_PLLI2SSTB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 27U), /*!< PLLI2S stabilization flags */ + RCU_FLAG_PLLSAISTB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 29U), /*!< PLLSAI stabilization flags */ + RCU_FLAG_LXTALSTB = RCU_REGIDX_BIT(BDCTL_REG_OFFSET, 1U), /*!< LXTAL stabilization flags */ + RCU_FLAG_IRC32KSTB = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 1U), /*!< IRC32K stabilization flags */ + RCU_FLAG_IRC48MSTB = RCU_REGIDX_BIT(ADDCTL_REG_OFFSET, 17U), /*!< IRC48M stabilization flags */ + /* reset source flags */ + RCU_FLAG_BORRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 25U), /*!< BOR reset flags */ + RCU_FLAG_EPRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 26U), /*!< External PIN reset flags */ + RCU_FLAG_PORRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 27U), /*!< power reset flags */ + RCU_FLAG_SWRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 28U), /*!< Software reset flags */ + RCU_FLAG_FWDGTRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 29U), /*!< FWDGT reset flags */ + RCU_FLAG_WWDGTRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 30U), /*!< WWDGT reset flags */ + RCU_FLAG_LPRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 31U), /*!< Low-power reset flags */ +}rcu_flag_enum; + +/* clock stabilization and ckm interrupt flags */ +typedef enum +{ + RCU_INT_FLAG_IRC32KSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 0U), /*!< IRC32K stabilization interrupt flag */ + RCU_INT_FLAG_LXTALSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 1U), /*!< LXTAL stabilization interrupt flag */ + RCU_INT_FLAG_IRC16MSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 2U), /*!< IRC16M stabilization interrupt flag */ + RCU_INT_FLAG_HXTALSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 3U), /*!< HXTAL stabilization interrupt flag */ + RCU_INT_FLAG_PLLSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 4U), /*!< PLL stabilization interrupt flag */ + RCU_INT_FLAG_PLLI2SSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 5U), /*!< PLLI2S stabilization interrupt flag */ + RCU_INT_FLAG_PLLSAISTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 6U), /*!< PLLSAI stabilization interrupt flag */ + RCU_INT_FLAG_CKM = RCU_REGIDX_BIT(INT_REG_OFFSET, 7U), /*!< HXTAL clock stuck interrupt flag */ + RCU_INT_FLAG_IRC48MSTB = RCU_REGIDX_BIT(ADDINT_REG_OFFSET, 6U), /*!< IRC48M stabilization interrupt flag */ +}rcu_int_flag_enum; + +/* clock stabilization and stuck interrupt flags clear */ +typedef enum +{ + RCU_INT_FLAG_IRC32KSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 16U), /*!< IRC32K stabilization interrupt flags clear */ + RCU_INT_FLAG_LXTALSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 17U), /*!< LXTAL stabilization interrupt flags clear */ + RCU_INT_FLAG_IRC16MSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 18U), /*!< IRC16M stabilization interrupt flags clear */ + RCU_INT_FLAG_HXTALSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 19U), /*!< HXTAL stabilization interrupt flags clear */ + RCU_INT_FLAG_PLLSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 20U), /*!< PLL stabilization interrupt flags clear */ + RCU_INT_FLAG_PLLI2SSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 21U), /*!< PLLI2S stabilization interrupt flags clear */ + RCU_INT_FLAG_PLLSAISTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 22U), /*!< PLLSAI stabilization interrupt flags clear */ + RCU_INT_FLAG_CKM_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 23U), /*!< CKM interrupt flags clear */ + RCU_INT_FLAG_IRC48MSTB_CLR = RCU_REGIDX_BIT(ADDINT_REG_OFFSET, 22U), /*!< internal 48 MHz RC oscillator stabilization interrupt clear */ +}rcu_int_flag_clear_enum; + +/* clock stabilization interrupt enable or disable */ +typedef enum +{ + RCU_INT_IRC32KSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 8U), /*!< IRC32K stabilization interrupt */ + RCU_INT_LXTALSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 9U), /*!< LXTAL stabilization interrupt */ + RCU_INT_IRC16MSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 10U), /*!< IRC16M stabilization interrupt */ + RCU_INT_HXTALSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 11U), /*!< HXTAL stabilization interrupt */ + RCU_INT_PLLSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 12U), /*!< PLL stabilization interrupt */ + RCU_INT_PLLI2SSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 13U), /*!< PLLI2S stabilization interrupt */ + RCU_INT_PLLSAISTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 14U), /*!< PLLSAI stabilization interrupt */ + RCU_INT_IRC48MSTB = RCU_REGIDX_BIT(ADDINT_REG_OFFSET, 14U), /*!< internal 48 MHz RC oscillator stabilization interrupt */ +}rcu_int_enum; + +/* oscillator types */ +typedef enum +{ + RCU_HXTAL = RCU_REGIDX_BIT(CTL_REG_OFFSET, 16U), /*!< HXTAL */ + RCU_LXTAL = RCU_REGIDX_BIT(BDCTL_REG_OFFSET, 0U), /*!< LXTAL */ + RCU_IRC16M = RCU_REGIDX_BIT(CTL_REG_OFFSET, 0U), /*!< IRC16M */ + RCU_IRC48M = RCU_REGIDX_BIT(ADDCTL_REG_OFFSET, 16U), /*!< IRC48M */ + RCU_IRC32K = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 0U), /*!< IRC32K */ + RCU_PLL_CK = RCU_REGIDX_BIT(CTL_REG_OFFSET, 24U), /*!< PLL */ + RCU_PLLI2S_CK = RCU_REGIDX_BIT(CTL_REG_OFFSET, 26U), /*!< PLLI2S */ + RCU_PLLSAI_CK = RCU_REGIDX_BIT(CTL_REG_OFFSET, 28U), /*!< PLLSAI */ +}rcu_osci_type_enum; + +/* rcu clock frequency */ +typedef enum +{ + CK_SYS = 0, /*!< system clock */ + CK_AHB, /*!< AHB clock */ + CK_APB1, /*!< APB1 clock */ + CK_APB2, /*!< APB2 clock */ +}rcu_clock_freq_enum; + +typedef enum { + IDX_I2C3 = 0U, /*!< idnex of I2C3 */ + IDX_I2C4, /*!< idnex of I2C4 */ + IDX_I2C5 /*!< idnex of I2C5 */ +} i2c_idx_enum; + +/* RCU_CFG0 register bit define */ +/* system clock source select */ +#define CFG0_SCS(regval) (BITS(0,1) & ((uint32_t)(regval) << 0)) +#define RCU_CKSYSSRC_IRC16M CFG0_SCS(0) /*!< system clock source select IRC16M */ +#define RCU_CKSYSSRC_HXTAL CFG0_SCS(1) /*!< system clock source select HXTAL */ +#define RCU_CKSYSSRC_PLLP CFG0_SCS(2) /*!< system clock source select PLLP */ + +/* system clock source select status */ +#define CFG0_SCSS(regval) (BITS(2,3) & ((uint32_t)(regval) << 2)) +#define RCU_SCSS_IRC16M CFG0_SCSS(0) /*!< system clock source select IRC16M */ +#define RCU_SCSS_HXTAL CFG0_SCSS(1) /*!< system clock source select HXTAL */ +#define RCU_SCSS_PLLP CFG0_SCSS(2) /*!< system clock source select PLLP */ + +/* AHB prescaler selection */ +#define CFG0_AHBPSC(regval) (BITS(4,7) & ((uint32_t)(regval) << 4)) +#define RCU_AHB_CKSYS_DIV1 CFG0_AHBPSC(0) /*!< AHB prescaler select CK_SYS */ +#define RCU_AHB_CKSYS_DIV2 CFG0_AHBPSC(8) /*!< AHB prescaler select CK_SYS/2 */ +#define RCU_AHB_CKSYS_DIV4 CFG0_AHBPSC(9) /*!< AHB prescaler select CK_SYS/4 */ +#define RCU_AHB_CKSYS_DIV8 CFG0_AHBPSC(10) /*!< AHB prescaler select CK_SYS/8 */ +#define RCU_AHB_CKSYS_DIV16 CFG0_AHBPSC(11) /*!< AHB prescaler select CK_SYS/16 */ +#define RCU_AHB_CKSYS_DIV64 CFG0_AHBPSC(12) /*!< AHB prescaler select CK_SYS/64 */ +#define RCU_AHB_CKSYS_DIV128 CFG0_AHBPSC(13) /*!< AHB prescaler select CK_SYS/128 */ +#define RCU_AHB_CKSYS_DIV256 CFG0_AHBPSC(14) /*!< AHB prescaler select CK_SYS/256 */ +#define RCU_AHB_CKSYS_DIV512 CFG0_AHBPSC(15) /*!< AHB prescaler select CK_SYS/512 */ + +/* APB1 prescaler selection */ +#define CFG0_APB1PSC(regval) (BITS(10,12) & ((uint32_t)(regval) << 10)) +#define RCU_APB1_CKAHB_DIV1 CFG0_APB1PSC(0) /*!< APB1 prescaler select CK_AHB */ +#define RCU_APB1_CKAHB_DIV2 CFG0_APB1PSC(4) /*!< APB1 prescaler select CK_AHB/2 */ +#define RCU_APB1_CKAHB_DIV4 CFG0_APB1PSC(5) /*!< APB1 prescaler select CK_AHB/4 */ +#define RCU_APB1_CKAHB_DIV8 CFG0_APB1PSC(6) /*!< APB1 prescaler select CK_AHB/8 */ +#define RCU_APB1_CKAHB_DIV16 CFG0_APB1PSC(7) /*!< APB1 prescaler select CK_AHB/16 */ + +/* APB2 prescaler selection */ +#define CFG0_APB2PSC(regval) (BITS(13,15) & ((uint32_t)(regval) << 13)) +#define RCU_APB2_CKAHB_DIV1 CFG0_APB2PSC(0) /*!< APB2 prescaler select CK_AHB */ +#define RCU_APB2_CKAHB_DIV2 CFG0_APB2PSC(4) /*!< APB2 prescaler select CK_AHB/2 */ +#define RCU_APB2_CKAHB_DIV4 CFG0_APB2PSC(5) /*!< APB2 prescaler select CK_AHB/4 */ +#define RCU_APB2_CKAHB_DIV8 CFG0_APB2PSC(6) /*!< APB2 prescaler select CK_AHB/8 */ +#define RCU_APB2_CKAHB_DIV16 CFG0_APB2PSC(7) /*!< APB2 prescaler select CK_AHB/16 */ + +/* RTC clock divider factor from HXTAL clock */ +#define CFG0_RTCDIV(regval) (BITS(16,20) & ((uint32_t)(regval) << 16)) +#define RCU_RTC_HXTAL_NONE CFG0_RTCDIV(0) /*!< no clock for RTC */ +#define RCU_RTC_HXTAL_DIV2 CFG0_RTCDIV(2) /*!< RTCDIV clock select CK_HXTAL/2 */ +#define RCU_RTC_HXTAL_DIV3 CFG0_RTCDIV(3) /*!< RTCDIV clock select CK_HXTAL/3 */ +#define RCU_RTC_HXTAL_DIV4 CFG0_RTCDIV(4) /*!< RTCDIV clock select CK_HXTAL/4 */ +#define RCU_RTC_HXTAL_DIV5 CFG0_RTCDIV(5) /*!< RTCDIV clock select CK_HXTAL/5 */ +#define RCU_RTC_HXTAL_DIV6 CFG0_RTCDIV(6) /*!< RTCDIV clock select CK_HXTAL/6 */ +#define RCU_RTC_HXTAL_DIV7 CFG0_RTCDIV(7) /*!< RTCDIV clock select CK_HXTAL/7 */ +#define RCU_RTC_HXTAL_DIV8 CFG0_RTCDIV(8) /*!< RTCDIV clock select CK_HXTAL/8 */ +#define RCU_RTC_HXTAL_DIV9 CFG0_RTCDIV(9) /*!< RTCDIV clock select CK_HXTAL/9 */ +#define RCU_RTC_HXTAL_DIV10 CFG0_RTCDIV(10) /*!< RTCDIV clock select CK_HXTAL/10 */ +#define RCU_RTC_HXTAL_DIV11 CFG0_RTCDIV(11) /*!< RTCDIV clock select CK_HXTAL/11 */ +#define RCU_RTC_HXTAL_DIV12 CFG0_RTCDIV(12) /*!< RTCDIV clock select CK_HXTAL/12 */ +#define RCU_RTC_HXTAL_DIV13 CFG0_RTCDIV(13) /*!< RTCDIV clock select CK_HXTAL/13 */ +#define RCU_RTC_HXTAL_DIV14 CFG0_RTCDIV(14) /*!< RTCDIV clock select CK_HXTAL/14 */ +#define RCU_RTC_HXTAL_DIV15 CFG0_RTCDIV(15) /*!< RTCDIV clock select CK_HXTAL/15 */ +#define RCU_RTC_HXTAL_DIV16 CFG0_RTCDIV(16) /*!< RTCDIV clock select CK_HXTAL/16 */ +#define RCU_RTC_HXTAL_DIV17 CFG0_RTCDIV(17) /*!< RTCDIV clock select CK_HXTAL/17 */ +#define RCU_RTC_HXTAL_DIV18 CFG0_RTCDIV(18) /*!< RTCDIV clock select CK_HXTAL/18 */ +#define RCU_RTC_HXTAL_DIV19 CFG0_RTCDIV(19) /*!< RTCDIV clock select CK_HXTAL/19 */ +#define RCU_RTC_HXTAL_DIV20 CFG0_RTCDIV(20) /*!< RTCDIV clock select CK_HXTAL/20 */ +#define RCU_RTC_HXTAL_DIV21 CFG0_RTCDIV(21) /*!< RTCDIV clock select CK_HXTAL/21 */ +#define RCU_RTC_HXTAL_DIV22 CFG0_RTCDIV(22) /*!< RTCDIV clock select CK_HXTAL/22 */ +#define RCU_RTC_HXTAL_DIV23 CFG0_RTCDIV(23) /*!< RTCDIV clock select CK_HXTAL/23 */ +#define RCU_RTC_HXTAL_DIV24 CFG0_RTCDIV(24) /*!< RTCDIV clock select CK_HXTAL/24 */ +#define RCU_RTC_HXTAL_DIV25 CFG0_RTCDIV(25) /*!< RTCDIV clock select CK_HXTAL/25 */ +#define RCU_RTC_HXTAL_DIV26 CFG0_RTCDIV(26) /*!< RTCDIV clock select CK_HXTAL/26 */ +#define RCU_RTC_HXTAL_DIV27 CFG0_RTCDIV(27) /*!< RTCDIV clock select CK_HXTAL/27 */ +#define RCU_RTC_HXTAL_DIV28 CFG0_RTCDIV(28) /*!< RTCDIV clock select CK_HXTAL/28 */ +#define RCU_RTC_HXTAL_DIV29 CFG0_RTCDIV(29) /*!< RTCDIV clock select CK_HXTAL/29 */ +#define RCU_RTC_HXTAL_DIV30 CFG0_RTCDIV(30) /*!< RTCDIV clock select CK_HXTAL/30 */ +#define RCU_RTC_HXTAL_DIV31 CFG0_RTCDIV(31) /*!< RTCDIV clock select CK_HXTAL/31 */ + +/* CKOUT0 Clock source selection */ +#define CFG0_CKOUT0SEL(regval) (BITS(21,22) & ((uint32_t)(regval) << 21)) +#define RCU_CKOUT0SRC_IRC16M CFG0_CKOUT0SEL(0) /*!< internal 16M RC oscillator clock selected */ +#define RCU_CKOUT0SRC_LXTAL CFG0_CKOUT0SEL(1) /*!< low speed crystal oscillator clock (LXTAL) selected */ +#define RCU_CKOUT0SRC_HXTAL CFG0_CKOUT0SEL(2) /*!< high speed crystal oscillator clock (HXTAL) selected */ +#define RCU_CKOUT0SRC_PLLP CFG0_CKOUT0SEL(3) /*!< CK_PLLP clock selected */ + +/* I2S Clock source selection */ +#define RCU_I2SSRC_PLLI2S ((uint32_t)0x00000000U) /*!< PLLI2S output clock selected as I2S source clock */ +#define RCU_I2SSRC_I2S_CKIN RCU_CFG0_I2SSEL /*!< external I2S_CKIN pin selected as I2S source clock */ + +/* I2Cx(x=3,4,5) clock source selection */ +#define CFG2_I2C3SEL(regval) (BITS(0,1) & ((uint32_t)(regval) << 0U)) +#define RCU_I2CSRC_CKAPB1 CFG2_I2C3SEL(0) /*!< CK_I2C select CK_APB1 */ +#define RCU_I2CSRC_PLLSAIR CFG2_I2C3SEL(1) /*!< CK_I2C select CK_PLLSAIR */ +#define RCU_I2CSRC_IRC16M CFG2_I2C3SEL(2) /*!< CK_I2C select IRC16M */ + +/* The CK_OUT0 divider */ +#define CFG0_CKOUT0DIV(regval) (BITS(24,26) & ((uint32_t)(regval) << 24)) +#define RCU_CKOUT0_DIV1 CFG0_CKOUT0DIV(0) /*!< CK_OUT0 is divided by 1 */ +#define RCU_CKOUT0_DIV2 CFG0_CKOUT0DIV(4) /*!< CK_OUT0 is divided by 2 */ +#define RCU_CKOUT0_DIV3 CFG0_CKOUT0DIV(5) /*!< CK_OUT0 is divided by 3 */ +#define RCU_CKOUT0_DIV4 CFG0_CKOUT0DIV(6) /*!< CK_OUT0 is divided by 4 */ +#define RCU_CKOUT0_DIV5 CFG0_CKOUT0DIV(7) /*!< CK_OUT0 is divided by 5 */ + +/* The CK_OUT1 divider */ +#define CFG0_CKOUT1DIV(regval) (BITS(27,29) & ((uint32_t)(regval) << 27)) +#define RCU_CKOUT1_DIV1 CFG0_CKOUT1DIV(0) /*!< CK_OUT1 is divided by 1 */ +#define RCU_CKOUT1_DIV2 CFG0_CKOUT1DIV(4) /*!< CK_OUT1 is divided by 2 */ +#define RCU_CKOUT1_DIV3 CFG0_CKOUT1DIV(5) /*!< CK_OUT1 is divided by 3 */ +#define RCU_CKOUT1_DIV4 CFG0_CKOUT1DIV(6) /*!< CK_OUT1 is divided by 4 */ +#define RCU_CKOUT1_DIV5 CFG0_CKOUT1DIV(7) /*!< CK_OUT1 is divided by 5 */ + +/* CKOUT1 Clock source selection */ +#define CFG0_CKOUT1SEL(regval) (BITS(30,31) & ((uint32_t)(regval) << 30)) +#define RCU_CKOUT1SRC_SYSTEMCLOCK CFG0_CKOUT1SEL(0) /*!< system clock selected */ +#define RCU_CKOUT1SRC_PLLI2SR CFG0_CKOUT1SEL(1) /*!< CK_PLLI2SR clock selected */ +#define RCU_CKOUT1SRC_HXTAL CFG0_CKOUT1SEL(2) /*!< high speed crystal oscillator clock (HXTAL) selected */ +#define RCU_CKOUT1SRC_PLLP CFG0_CKOUT1SEL(3) /*!< CK_PLLP clock selected */ + +/* RCU_CFG1 register bit define */ +/* the divider factor from PLLI2SQ clock */ +#define CFG1_PLLI2SQDIV(regval) (BITS(0,4) & ((uint32_t)(regval) << 0)) +#define RCU_PLLI2SQ_DIV1 CFG1_PLLI2SQDIV(0) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/1 */ +#define RCU_PLLI2SQ_DIV2 CFG1_PLLI2SQDIV(1) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/2 */ +#define RCU_PLLI2SQ_DIV3 CFG1_PLLI2SQDIV(2) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/3 */ +#define RCU_PLLI2SQ_DIV4 CFG1_PLLI2SQDIV(3) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/4 */ +#define RCU_PLLI2SQ_DIV5 CFG1_PLLI2SQDIV(4) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/5 */ +#define RCU_PLLI2SQ_DIV6 CFG1_PLLI2SQDIV(5) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/6 */ +#define RCU_PLLI2SQ_DIV7 CFG1_PLLI2SQDIV(6) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/7 */ +#define RCU_PLLI2SQ_DIV8 CFG1_PLLI2SQDIV(7) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/8 */ +#define RCU_PLLI2SQ_DIV9 CFG1_PLLI2SQDIV(8) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/9 */ +#define RCU_PLLI2SQ_DIV10 CFG1_PLLI2SQDIV(9) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/10 */ +#define RCU_PLLI2SQ_DIV11 CFG1_PLLI2SQDIV(10) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/11 */ +#define RCU_PLLI2SQ_DIV12 CFG1_PLLI2SQDIV(11) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/12 */ +#define RCU_PLLI2SQ_DIV13 CFG1_PLLI2SQDIV(12) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/13 */ +#define RCU_PLLI2SQ_DIV14 CFG1_PLLI2SQDIV(13) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/14 */ +#define RCU_PLLI2SQ_DIV15 CFG1_PLLI2SQDIV(14) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/15 */ +#define RCU_PLLI2SQ_DIV16 CFG1_PLLI2SQDIV(15) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/16 */ +#define RCU_PLLI2SQ_DIV17 CFG1_PLLI2SQDIV(16) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/17 */ +#define RCU_PLLI2SQ_DIV18 CFG1_PLLI2SQDIV(17) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/18 */ +#define RCU_PLLI2SQ_DIV19 CFG1_PLLI2SQDIV(18) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/19 */ +#define RCU_PLLI2SQ_DIV20 CFG1_PLLI2SQDIV(19) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/20 */ +#define RCU_PLLI2SQ_DIV21 CFG1_PLLI2SQDIV(20) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/21 */ +#define RCU_PLLI2SQ_DIV22 CFG1_PLLI2SQDIV(21) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/22 */ +#define RCU_PLLI2SQ_DIV23 CFG1_PLLI2SQDIV(22) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/23 */ +#define RCU_PLLI2SQ_DIV24 CFG1_PLLI2SQDIV(23) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/24 */ +#define RCU_PLLI2SQ_DIV25 CFG1_PLLI2SQDIV(24) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/25 */ +#define RCU_PLLI2SQ_DIV26 CFG1_PLLI2SQDIV(25) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/26 */ +#define RCU_PLLI2SQ_DIV27 CFG1_PLLI2SQDIV(26) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/27 */ +#define RCU_PLLI2SQ_DIV28 CFG1_PLLI2SQDIV(27) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/28 */ +#define RCU_PLLI2SQ_DIV29 CFG1_PLLI2SQDIV(28) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/29 */ +#define RCU_PLLI2SQ_DIV30 CFG1_PLLI2SQDIV(29) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/30 */ +#define RCU_PLLI2SQ_DIV31 CFG1_PLLI2SQDIV(30) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/31 */ +#define RCU_PLLI2SQ_DIV32 CFG1_PLLI2SQDIV(31) /*!< CK_PLLI2SQDIV clock select CK_PLLI2SQ/32 */ + +/* SAI clock source selection */ +#define CFG1_SAISEL(regval) (BITS(20,21) & ((uint32_t)(regval) << 20U)) +#define RCU_SAISRC_PLLSAIQ CFG1_SAISEL(0) /*!< CK_SAI select CK_PLLSAIQ */ +#define RCU_SAISRC_PLLI2SQ CFG1_SAISEL(1) /*!< CK_SAI select CK_PLLI2SQ */ +#define RCU_SAISRC_I2S_CKIN BIT(21) /*!< CK_SAI select I2S_CKIN */ + +/* the divider factor from PLLSAIR clock */ +#define CFG1_PLLSAIRDIV(regval) (BITS(16,17) & ((uint32_t)(regval) << 16)) +#define RCU_PLLSAIR_DIV2 CFG1_PLLSAIRDIV(0) /*!< CK_PLLSAIRDIV clock select CK_PLLSAIR/2 */ +#define RCU_PLLSAIR_DIV4 CFG1_PLLSAIRDIV(1) /*!< CK_PLLSAIRDIV clock select CK_PLLSAIR/4 */ +#define RCU_PLLSAIR_DIV8 CFG1_PLLSAIRDIV(2) /*!< CK_PLLSAIRDIV clock select CK_PLLSAIR/8 */ +#define RCU_PLLSAIR_DIV16 CFG1_PLLSAIRDIV(3) /*!< CK_PLLSAIRDIV clock select CK_PLLSAIR/16 */ + +/* TIMER clock selection */ +#define RCU_TIMER_PSC_MUL2 ~RCU_CFG1_TIMERSEL /*!< if APB1PSC/APB2PSC in RCU_CFG0 register is 0b0xx(CK_APBx = CK_AHB) + or 0b100(CK_APBx = CK_AHB/2), the TIMER clock is equal to CK_AHB(CK_TIMERx = CK_AHB). + or else, the TIMER clock is twice the corresponding APB clock (TIMER in APB1 domain: CK_TIMERx = 2 x CK_APB1; + TIMER in APB2 domain: CK_TIMERx = 2 x CK_APB2) */ +#define RCU_TIMER_PSC_MUL4 RCU_CFG1_TIMERSEL /*!< if APB1PSC/APB2PSC in RCU_CFG0 register is 0b0xx(CK_APBx = CK_AHB), + 0b100(CK_APBx = CK_AHB/2), or 0b101(CK_APBx = CK_AHB/4), the TIMER clock is equal to CK_AHB(CK_TIMERx = CK_AHB). + or else, the TIMER clock is four timers the corresponding APB clock (TIMER in APB1 domain: CK_TIMERx = 4 x CK_APB1; + TIMER in APB2 domain: CK_TIMERx = 4 x CK_APB2) */ + +/* RCU_PLLSSCTL register bit define */ +/* PLL spread spectrum modulation type select */ +#define RCU_SS_TYPE_CENTER ((uint32_t)0x00000000U) /*!< center type is selected */ +#define RCU_SS_TYPE_DOWN RCU_PLLSSCTL_SS_TYPE /*!< down type is selected */ + +/* RCU_PLL register bit define */ +/* The PLL VCO source clock prescaler */ +#define RCU_PLLPSC_DIV_MIN ((uint32_t)2U) /*!< PLLPSC_DIV min value */ +#define RCU_PLLPSC_DIV_MAX ((uint32_t)63U) /*!< PLLPSC_DIV max value */ + +/* The PLL VCO clock multi factor */ +#define RCU_PLLN_MUL_MIN ((uint32_t)64U) /*!< PLLN_MUL min value */ +#define RCU_PLLN_MUL_MAX ((uint32_t)500U) /*!< PLLN_MUL max value */ +#define RCU_SS_MODULATION_CENTER_INC ((uint32_t)5U) /*!< minimum factor of PLLN in center mode */ +#define RCU_SS_MODULATION_DOWN_INC ((uint32_t)7U) /*!< minimum factor of PLLN in down mode */ + +/* The PLLP output frequency division factor from PLL VCO clock */ +#define RCU_PLLP_DIV_MIN ((uint32_t)2U) /*!< PLLP_DIV min value */ +#define RCU_PLLP_DIV_MAX ((uint32_t)8U) /*!< PLLP_DIV max value */ + +/* PLL Clock Source Selection */ +#define RCU_PLLSRC_IRC16M ((uint32_t)0x00000000U) /*!< IRC16M clock selected as source clock of PLL, PLLSAI, PLLI2S */ +#define RCU_PLLSRC_HXTAL RCU_PLL_PLLSEL /*!< HXTAL clock selected as source clock of PLL, PLLSAI, PLLI2S */ + +/* The PLL Q output frequency division factor from PLL VCO clock */ +#define RCU_PLLQ_DIV_MIN ((uint32_t)2U) /*!< PLLQ_DIV min value */ +#define RCU_PLLQ_DIV_MAX ((uint32_t)15U) /*!< PLLQ_DIV max value */ + +#define CHECK_PLL_PSC_VALID(val) (((val) >= RCU_PLLPSC_DIV_MIN)&&((val) <= RCU_PLLPSC_DIV_MAX)) +#define CHECK_PLL_N_VALID(val, inc) (((val) >= (RCU_PLLN_MUL_MIN + (inc)))&&((val) <= RCU_PLLN_MUL_MAX)) +#define CHECK_PLL_P_VALID(val) (((val) == 2U) || ((val) == 4U) || ((val) == 6U) || ((val) == 8U)) +#define CHECK_PLL_Q_VALID(val) (((val) >= RCU_PLLQ_DIV_MIN)&&((val) <= RCU_PLLQ_DIV_MAX)) + +/* RCU_BDCTL register bit define */ +/* LXTAL drive capability */ +#define RCU_LXTALDRI_LOWER_DRIVE ((uint32_t)0x00000000) /*!< LXTAL drive capability is selected lower */ +#define RCU_LXTALDRI_HIGHER_DRIVE RCU_BDCTL_LXTALDRI /*!< LXTAL drive capability is selected higher */ + +/* RTC clock entry selection */ +#define BDCTL_RTCSRC(regval) (BITS(8,9) & ((uint32_t)(regval) << 8)) +#define RCU_RTCSRC_NONE BDCTL_RTCSRC(0) /*!< no clock selected */ +#define RCU_RTCSRC_LXTAL BDCTL_RTCSRC(1) /*!< RTC source clock select LXTAL */ +#define RCU_RTCSRC_IRC32K BDCTL_RTCSRC(2) /*!< RTC source clock select IRC32K */ +#define RCU_RTCSRC_HXTAL_DIV_RTCDIV BDCTL_RTCSRC(3) /*!< RTC source clock select HXTAL/RTCDIV */ + +/* RCU_PLLI2S register bit define */ +/* The PLLI2S VCO clock multi factor */ +#define RCU_PLLI2SN_MUL_MIN 50U +#define RCU_PLLI2SN_MUL_MAX 500U + +/* The PLLI2S Q output frequency division factor from PLLI2S VCO clock */ +#define RCU_PLLI2SQ_DIV_MIN 2U +#define RCU_PLLI2SQ_DIV_MAX 15U + +/* The PLLI2S R output frequency division factor from PLLI2S VCO clock */ +#define RCU_PLLI2SR_DIV_MIN 2U +#define RCU_PLLI2SR_DIV_MAX 7U + +/* RCU_PLLSAI register bit define */ +/* The PLLSAI VCO clock multi factor */ +#define RCU_PLLSAIN_MUL_MIN 50U +#define RCU_PLLSAIN_MUL_MAX 500U + +/* The PLLSAI P output frequency division factor from PLLSAI VCO clock */ +#define RCU_PLLSAIP_DIV_MIN 2U +#define RCU_PLLSAIP_DIV_MAX 8U + +/* The PLLSAI Q output frequency division factor from PLLSAI VCO clock */ +#define RCU_PLLSAIQ_DIV_MIN 2U +#define RCU_PLLSAIQ_DIV_MAX 15U + +/* The PLLSAI R output frequency division factor from PLLSAI VCO clock */ +#define RCU_PLLSAIR_DIV_MIN 2U +#define RCU_PLLSAIR_DIV_MAX 7U + +#define CHECK_PLLI2S_PSC_VALID(val) (((val) >= RCU_PLLI2SPSC_DIV_MIN)&&((val) <= RCU_PLLI2SPSC_DIV_MAX)) +#define CHECK_PLLI2S_N_VALID(val) (((val) >= RCU_PLLI2SN_MUL_MIN)&&((val) <= RCU_PLLI2SN_MUL_MAX)) +#define CHECK_PLLI2S_Q_VALID(val) (((val) >= RCU_PLLI2SQ_DIV_MIN)&&((val) <= RCU_PLLI2SQ_DIV_MAX)) +#define CHECK_PLLI2S_R_VALID(val) (((val) >= RCU_PLLI2SR_DIV_MIN)&&((val) <= RCU_PLLI2SR_DIV_MAX)) + +#define CHECK_PLLSAI_N_VALID(val) (((val) >= (RCU_PLLSAIN_MUL_MIN))&&((val) <= RCU_PLLSAIN_MUL_MAX)) +#define CHECK_PLLSAI_P_VALID(val) (((val) == 2U) || ((val) == 4U) || ((val) == 6U) || ((val) == 8U)) +#define CHECK_PLLSAI_Q_VALID(val) (((val) >= RCU_PLLSAIQ_DIV_MIN)&&((val) <= RCU_PLLSAIQ_DIV_MAX)) +#define CHECK_PLLSAI_R_VALID(val) (((val) >= RCU_PLLSAIR_DIV_MIN)&&((val) <= RCU_PLLSAIR_DIV_MAX)) + +/* RCU_ADDCTL register bit define */ +/* 48MHz clock selection */ +#define RCU_CK48MSRC_PLL48M ((uint32_t)0x00000000U) /*!< CK48M source clock select PLL48M */ +#define RCU_CK48MSRC_IRC48M RCU_ADDCTL_CK48MSEL /*!< CK48M source clock select IRC48M */ + +/* PLL48M clock selection */ +#define RCU_PLL48MSRC_PLLQ ((uint32_t)0x00000000U) /*!< PLL48M source clock select PLLQ */ +#define RCU_PLL48MSRC_PLLSAIP RCU_ADDCTL_PLL48MSEL /*!< PLL48M source clock select PLLSAIP */ + +/* Deep-sleep mode voltage */ +#define DSV_DSLPVS(regval) (BITS(0,2) & ((uint32_t)(regval) << 0)) +#define RCU_DEEPSLEEP_V_0 DSV_DSLPVS(0) /*!< core voltage is default value in deep-sleep mode */ +#define RCU_DEEPSLEEP_V_1 DSV_DSLPVS(1) /*!< core voltage is (default value-0.1)V in deep-sleep mode(customers are not recommended to use it)*/ +#define RCU_DEEPSLEEP_V_2 DSV_DSLPVS(2) /*!< core voltage is (default value-0.2)V in deep-sleep mode(customers are not recommended to use it)*/ +#define RCU_DEEPSLEEP_V_3 DSV_DSLPVS(3) /*!< core voltage is (default value-0.3)V in deep-sleep mode(customers are not recommended to use it)*/ + + +/* function declarations */ +/* peripherals clock configure functions */ +/* deinitialize the RCU */ +void rcu_deinit(void); +/* enable the peripherals clock */ +void rcu_periph_clock_enable(rcu_periph_enum periph); +/* disable the peripherals clock */ +void rcu_periph_clock_disable(rcu_periph_enum periph); +/* enable the peripherals clock when sleep mode */ +void rcu_periph_clock_sleep_enable(rcu_periph_sleep_enum periph); +/* disable the peripherals clock when sleep mode */ +void rcu_periph_clock_sleep_disable(rcu_periph_sleep_enum periph); +/* reset the peripherals */ +void rcu_periph_reset_enable(rcu_periph_reset_enum periph_reset); +/* disable reset the peripheral */ +void rcu_periph_reset_disable(rcu_periph_reset_enum periph_reset); +/* reset the BKP */ +void rcu_bkp_reset_enable(void); +/* disable the BKP reset */ +void rcu_bkp_reset_disable(void); + +/* system and peripherals clock source, system reset configure functions */ +/* configure the system clock source */ +void rcu_system_clock_source_config(uint32_t ck_sys); +/* get the system clock source */ +uint32_t rcu_system_clock_source_get(void); +/* configure the AHB prescaler selection */ +void rcu_ahb_clock_config(uint32_t ck_ahb); +/* configure the APB1 prescaler selection */ +void rcu_apb1_clock_config(uint32_t ck_apb1); +/* configure the APB2 prescaler selection */ +void rcu_apb2_clock_config(uint32_t ck_apb2); +/* configure the CK_OUT0 clock source and divider */ +void rcu_ckout0_config(uint32_t ckout0_src, uint32_t ckout0_div); +/* configure the CK_OUT1 clock source and divider */ +void rcu_ckout1_config(uint32_t ckout1_src, uint32_t ckout1_div); +/* configure the main PLL clock */ +ErrStatus rcu_pll_config(uint32_t pll_src, uint32_t pll_psc, uint32_t pll_n, uint32_t pll_p, uint32_t pll_q); +/* configure the PLLI2S_Q clock */ +ErrStatus rcu_plli2s_q_config(uint32_t plli2s_n, uint32_t plli2s_q); +/* configure the PLLI2S_R clock */ +ErrStatus rcu_plli2s_r_config(uint32_t plli2s_n, uint32_t plli2s_r); +/* configure the PLLSAI_P clock */ +ErrStatus rcu_pllsai_p_config(uint32_t pllsai_n, uint32_t pllsai_p); +/* configure the PLLSAI_Q clock */ +ErrStatus rcu_pllsai_q_config(uint32_t pllsai_n, uint32_t pllsai_q); +/* configure the PLLSAI_R clock */ +ErrStatus rcu_pllsai_r_config(uint32_t pllsai_n, uint32_t pllsai_r); +/* configure the RTC clock source selection */ +void rcu_rtc_clock_config(uint32_t rtc_clock_source); +/* cconfigure the frequency division of RTC clock when HXTAL was selected as its clock source */ +void rcu_rtc_div_config(uint32_t rtc_div); +/* configure the I2S clock source selection */ +void rcu_i2s_clock_config(uint32_t i2s_clock_source); +/* configure the I2Cx(x=3,4,5) clock source selection */ +void rcu_i2c_clock_config(i2c_idx_enum i2c_idx, uint32_t ck_i2c); +/* configure the SAI clock source selection */ +void rcu_sai_clock_config(uint32_t sai_clock_source); +/* configure the CK48M clock selection */ +void rcu_ck48m_clock_config(uint32_t ck48m_clock_source); +/* configure the PLL48M clock selection */ +void rcu_pll48m_clock_config(uint32_t pll48m_clock_source); +/* configure the TIMER clock prescaler selection */ +void rcu_timer_clock_prescaler_config(uint32_t timer_clock_prescaler); +/* configure the TLI clock division selection */ +void rcu_tli_clock_div_config(uint32_t pllsai_r_div); + +/* LXTAL, IRC8M, PLL and other oscillator configure functions */ +/* configure the LXTAL drive capability */ +void rcu_lxtal_drive_capability_config(uint32_t lxtal_dricap); +/* wait for oscillator stabilization flags is SET or oscillator startup is timeout */ +ErrStatus rcu_osci_stab_wait(rcu_osci_type_enum osci); +/* turn on the oscillator */ +void rcu_osci_on(rcu_osci_type_enum osci); +/* turn off the oscillator */ +void rcu_osci_off(rcu_osci_type_enum osci); +/* enable the oscillator bypass mode, HXTALEN or LXTALEN must be reset before it */ +void rcu_osci_bypass_mode_enable(rcu_osci_type_enum osci); +/* disable the oscillator bypass mode, HXTALEN or LXTALEN must be reset before it */ +void rcu_osci_bypass_mode_disable(rcu_osci_type_enum osci); +/* set the IRC16M adjust value */ +void rcu_irc16m_adjust_value_set(uint32_t irc16m_adjval); +/* configure the spread spectrum modulation for the main PLL clock */ +void rcu_spread_spectrum_config(uint32_t spread_spectrum_type, uint32_t modstep, uint32_t modcnt); +/* enable the spread spectrum modulation for the main PLL clock */ +void rcu_spread_spectrum_enable(void); +/* disable the spread spectrum modulation for the main PLL clock */ +void rcu_spread_spectrum_disable(void); + +/* clock monitor configure functions */ +/* enable the HXTAL clock monitor */ +void rcu_hxtal_clock_monitor_enable(void); +/* disable the HXTAL clock monitor */ +void rcu_hxtal_clock_monitor_disable(void); + +/* voltage configure and clock frequency get functions */ +/* unlock the voltage key */ +void rcu_voltage_key_unlock(void); +/* set the deep sleep mode voltage */ +void rcu_deepsleep_voltage_set(uint32_t dsvol); +/* get the system clock, bus and peripheral clock frequency */ +uint32_t rcu_clock_freq_get(rcu_clock_freq_enum clock); + +/* flag & interrupt functions */ +/* get the clock stabilization and periphral reset flags */ +FlagStatus rcu_flag_get(rcu_flag_enum flag); +/* clear the reset flag */ +void rcu_all_reset_flag_clear(void); +/* get the clock stabilization interrupt and ckm flags */ +FlagStatus rcu_interrupt_flag_get(rcu_int_flag_enum int_flag); +/* clear the interrupt flags */ +void rcu_interrupt_flag_clear(rcu_int_flag_clear_enum int_flag); +/* enable the stabilization interrupt */ +void rcu_interrupt_enable(rcu_int_enum interrupt); +/* disable the stabilization interrupt */ +void rcu_interrupt_disable(rcu_int_enum interrupt); + +#endif /* GD32F5XX_RCU_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_rtc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_rtc.h new file mode 100644 index 0000000..3746161 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_rtc.h @@ -0,0 +1,638 @@ +/*! + \file gd32f5xx_rtc.c + \brief definitions for the RTC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_RTC_H +#define GD32F5XX_RTC_H + +#include "gd32f5xx.h" + +/* RTC definitions */ +#define RTC RTC_BASE + +/* registers definitions */ +#define RTC_TIME REG32((RTC) + 0x00U) /*!< RTC time of day register */ +#define RTC_DATE REG32((RTC) + 0x04U) /*!< RTC date register */ +#define RTC_CTL REG32((RTC) + 0x08U) /*!< RTC control register */ +#define RTC_STAT REG32((RTC) + 0x0CU) /*!< RTC status register */ +#define RTC_PSC REG32((RTC) + 0x10U) /*!< RTC time prescaler register */ +#define RTC_WUT REG32((RTC) + 0x14U) /*!< RTC wakeup timer register */ +#define RTC_COSC REG32((RTC) + 0x18U) /*!< RTC coarse calibration register */ +#define RTC_ALRM0TD REG32((RTC) + 0x1CU) /*!< RTC alarm 0 time and date register */ +#define RTC_ALRM1TD REG32((RTC) + 0x20U) /*!< RTC alarm 1 time and date register */ +#define RTC_WPK REG32((RTC) + 0x24U) /*!< RTC write protection key register */ +#define RTC_SS REG32((RTC) + 0x28U) /*!< RTC sub second register */ +#define RTC_SHIFTCTL REG32((RTC) + 0x2CU) /*!< RTC shift function control register */ +#define RTC_TTS REG32((RTC) + 0x30U) /*!< RTC time of timestamp register */ +#define RTC_DTS REG32((RTC) + 0x34U) /*!< RTC date of timestamp register */ +#define RTC_SSTS REG32((RTC) + 0x38U) /*!< RTC sub second of timestamp register */ +#define RTC_HRFC REG32((RTC) + 0x3CU) /*!< RTC high resolution frequency compensation register */ +#define RTC_TAMP REG32((RTC) + 0x40U) /*!< RTC tamper register */ +#define RTC_ALRM0SS REG32((RTC) + 0x44U) /*!< RTC alarm 0 sub second register */ +#define RTC_ALRM1SS REG32((RTC) + 0x48U) /*!< RTC alarm 1 sub second register */ +#define RTC_BKP0 REG32((RTC) + 0x50U) /*!< RTC backup register */ +#define RTC_BKP1 REG32((RTC) + 0x54U) /*!< RTC backup register */ +#define RTC_BKP2 REG32((RTC) + 0x58U) /*!< RTC backup register */ +#define RTC_BKP3 REG32((RTC) + 0x5CU) /*!< RTC backup register */ +#define RTC_BKP4 REG32((RTC) + 0x60U) /*!< RTC backup register */ +#define RTC_BKP5 REG32((RTC) + 0x64U) /*!< RTC backup register */ +#define RTC_BKP6 REG32((RTC) + 0x68U) /*!< RTC backup register */ +#define RTC_BKP7 REG32((RTC) + 0x6CU) /*!< RTC backup register */ +#define RTC_BKP8 REG32((RTC) + 0x70U) /*!< RTC backup register */ +#define RTC_BKP9 REG32((RTC) + 0x74U) /*!< RTC backup register */ +#define RTC_BKP10 REG32((RTC) + 0x78U) /*!< RTC backup register */ +#define RTC_BKP11 REG32((RTC) + 0x7CU) /*!< RTC backup register */ +#define RTC_BKP12 REG32((RTC) + 0x80U) /*!< RTC backup register */ +#define RTC_BKP13 REG32((RTC) + 0x84U) /*!< RTC backup register */ +#define RTC_BKP14 REG32((RTC) + 0x88U) /*!< RTC backup register */ +#define RTC_BKP15 REG32((RTC) + 0x8CU) /*!< RTC backup register */ +#define RTC_BKP16 REG32((RTC) + 0x90U) /*!< RTC backup register */ +#define RTC_BKP17 REG32((RTC) + 0x94U) /*!< RTC backup register */ +#define RTC_BKP18 REG32((RTC) + 0x98U) /*!< RTC backup register */ +#define RTC_BKP19 REG32((RTC) + 0x9CU) /*!< RTC backup register */ + +/* bits definitions */ +/* RTC_TIME */ +#define RTC_TIME_SCU BITS(0,3) /*!< second units in BCD code */ +#define RTC_TIME_SCT BITS(4,6) /*!< second tens in BCD code */ +#define RTC_TIME_MNU BITS(8,11) /*!< minute units in BCD code */ +#define RTC_TIME_MNT BITS(12,14) /*!< minute tens in BCD code */ +#define RTC_TIME_HRU BITS(16,19) /*!< hour units in BCD code */ +#define RTC_TIME_HRT BITS(20,21) /*!< hour tens in BCD code */ +#define RTC_TIME_PM BIT(22) /*!< AM/PM notation */ + +/* RTC_DATE */ +#define RTC_DATE_DAYU BITS(0,3) /*!< date units in BCD code */ +#define RTC_DATE_DAYT BITS(4,5) /*!< date tens in BCD code */ +#define RTC_DATE_MONU BITS(8,11) /*!< month units in BCD code */ +#define RTC_DATE_MONT BIT(12) /*!< month tens in BCD code */ +#define RTC_DATE_DOW BITS(13,15) /*!< day of week units */ +#define RTC_DATE_YRU BITS(16,19) /*!< year units in BCD code */ +#define RTC_DATE_YRT BITS(20,23) /*!< year tens in BCD code */ + +/* RTC_CTL */ +#define RTC_CTL_WTCS BITS(0,2) /*!< auto wakeup timer clock selection */ +#define RTC_CTL_TSEG BIT(3) /*!< valid event edge of time-stamp */ +#define RTC_CTL_REFEN BIT(4) /*!< reference clock detection function enable */ +#define RTC_CTL_BPSHAD BIT(5) /*!< shadow registers bypass control */ +#define RTC_CTL_CS BIT(6) /*!< display format of clock system */ +#define RTC_CTL_CCEN BIT(7) /*!< coarse calibration function enable */ +#define RTC_CTL_ALRM0EN BIT(8) /*!< alarm0 function enable */ +#define RTC_CTL_ALRM1EN BIT(9) /*!< alarm1 function enable */ +#define RTC_CTL_WTEN BIT(10) /*!< auto wakeup timer function enable */ +#define RTC_CTL_TSEN BIT(11) /*!< time-stamp function enable */ +#define RTC_CTL_ALRM0IE BIT(12) /*!< RTC alarm0 interrupt enable */ +#define RTC_CTL_ALRM1IE BIT(13) /*!< RTC alarm1 interrupt enable */ +#define RTC_CTL_WTIE BIT(14) /*!< auto wakeup timer interrupt enable */ +#define RTC_CTL_TSIE BIT(15) /*!< time-stamp interrupt enable */ +#define RTC_CTL_A1H BIT(16) /*!< add 1 hour(summer time change) */ +#define RTC_CTL_S1H BIT(17) /*!< subtract 1 hour(winter time change) */ +#define RTC_CTL_DSM BIT(18) /*!< daylight saving mark */ +#define RTC_CTL_COS BIT(19) /*!< calibration output selection */ +#define RTC_CTL_OPOL BIT(20) /*!< output polarity */ +#define RTC_CTL_OS BITS(21,22) /*!< output selection */ +#define RTC_CTL_COEN BIT(23) /*!< calibration output enable */ + +/* RTC_STAT */ +#define RTC_STAT_ALRM0WF BIT(0) /*!< alarm0 configuration can be write flag */ +#define RTC_STAT_ALRM1WF BIT(1) /*!< alarm1 configuration can be write flag */ +#define RTC_STAT_WTWF BIT(2) /*!< wakeup timer can be write flag */ +#define RTC_STAT_SOPF BIT(3) /*!< shift function operation pending flag */ +#define RTC_STAT_YCM BIT(4) /*!< year configuration mark status flag */ +#define RTC_STAT_RSYNF BIT(5) /*!< register synchronization flag */ +#define RTC_STAT_INITF BIT(6) /*!< initialization state flag */ +#define RTC_STAT_INITM BIT(7) /*!< enter initialization mode */ +#define RTC_STAT_ALRM0F BIT(8) /*!< alarm0 occurs flag */ +#define RTC_STAT_ALRM1F BIT(9) /*!< alarm1 occurs flag */ +#define RTC_STAT_WTF BIT(10) /*!< wakeup timer occurs flag */ +#define RTC_STAT_TSF BIT(11) /*!< time-stamp flag */ +#define RTC_STAT_TSOVRF BIT(12) /*!< time-stamp overflow flag */ +#define RTC_STAT_TP0F BIT(13) /*!< RTC tamper 0 detected flag */ +#define RTC_STAT_TP1F BIT(14) /*!< RTC tamper 1 detected flag */ +#define RTC_STAT_SCPF BIT(16) /*!< smooth calibration pending flag */ + +/* RTC_PSC */ +#define RTC_PSC_FACTOR_S BITS(0,14) /*!< synchronous prescaler factor */ +#define RTC_PSC_FACTOR_A BITS(16,22) /*!< asynchronous prescaler factor */ + +/* RTC_WUT */ +#define RTC_WUT_WTRV BITS(0,15) /*!< auto wakeup timer reloads value */ + +/* RTC_COSC */ +#define RTC_COSC_COSS BITS(0,4) /*!< coarse calibration step */ +#define RTC_COSC_COSD BIT(7) /*!< coarse calibration direction */ + +/* RTC_ALRMxTD */ +#define RTC_ALRMXTD_SCU BITS(0,3) /*!< second units in BCD code */ +#define RTC_ALRMXTD_SCT BITS(4,6) /*!< second tens in BCD code */ +#define RTC_ALRMXTD_MSKS BIT(7) /*!< alarm second mask bit */ +#define RTC_ALRMXTD_MNU BITS(8,11) /*!< minutes units in BCD code */ +#define RTC_ALRMXTD_MNT BITS(12,14) /*!< minutes tens in BCD code */ +#define RTC_ALRMXTD_MSKM BIT(15) /*!< alarm minutes mask bit */ +#define RTC_ALRMXTD_HRU BITS(16,19) /*!< hour units in BCD code */ +#define RTC_ALRMXTD_HRT BITS(20,21) /*!< hour units in BCD code */ +#define RTC_ALRMXTD_PM BIT(22) /*!< AM/PM flag */ +#define RTC_ALRMXTD_MSKH BIT(23) /*!< alarm hour mask bit */ +#define RTC_ALRMXTD_DAYU BITS(24,27) /*!< date units or week day in BCD code */ +#define RTC_ALRMXTD_DAYT BITS(28,29) /*!< date tens in BCD code */ +#define RTC_ALRMXTD_DOWS BIT(30) /*!< day of week selection */ +#define RTC_ALRMXTD_MSKD BIT(31) /*!< alarm date mask bit */ + +/* RTC_WPK */ +#define RTC_WPK_WPK BITS(0,7) /*!< key for write protection */ + +/* RTC_SS */ +#define RTC_SS_SSC BITS(0,15) /*!< sub second value */ + +/* RTC_SHIFTCTL */ +#define RTC_SHIFTCTL_SFS BITS(0,14) /*!< subtract a fraction of a second */ +#define RTC_SHIFTCTL_A1S BIT(31) /*!< one second add */ + +/* RTC_TTS */ +#define RTC_TTS_SCU BITS(0,3) /*!< second units in BCD code */ +#define RTC_TTS_SCT BITS(4,6) /*!< second units in BCD code */ +#define RTC_TTS_MNU BITS(8,11) /*!< minute units in BCD code */ +#define RTC_TTS_MNT BITS(12,14) /*!< minute tens in BCD code */ +#define RTC_TTS_HRU BITS(16,19) /*!< hour units in BCD code */ +#define RTC_TTS_HRT BITS(20,21) /*!< hour tens in BCD code */ +#define RTC_TTS_PM BIT(22) /*!< AM/PM notation */ + +/* RTC_DTS */ +#define RTC_DTS_DAYU BITS(0,3) /*!< date units in BCD code */ +#define RTC_DTS_DAYT BITS(4,5) /*!< date tens in BCD code */ +#define RTC_DTS_MONU BITS(8,11) /*!< month units in BCD code */ +#define RTC_DTS_MONT BIT(12) /*!< month tens in BCD code */ +#define RTC_DTS_DOW BITS(13,15) /*!< day of week units */ + +/* RTC_SSTS */ +#define RTC_SSTS_SSC BITS(0,15) /*!< timestamp sub second units */ + +/* RTC_HRFC */ +#define RTC_HRFC_CMSK BITS(0,8) /*!< calibration mask number */ +#define RTC_HRFC_CWND16 BIT(13) /*!< calibration window select 16 seconds */ +#define RTC_HRFC_CWND8 BIT(14) /*!< calibration window select 16 seconds */ +#define RTC_HRFC_FREQI BIT(15) /*!< increase RTC frequency by 488.5ppm */ + +/* RTC_TAMP */ +#define RTC_TAMP_TP0EN BIT(0) /*!< tamper 0 detection enable */ +#define RTC_TAMP_TP0EG BIT(1) /*!< tamper 0 event trigger edge for RTC tamp 0 input */ +#define RTC_TAMP_TPIE BIT(2) /*!< tamper detection interrupt enable */ +#define RTC_TAMP_TP1EN BIT(3) /*!< tamper 1 detection enable */ +#define RTC_TAMP_TP1EG BIT(4) /*!< Tamper 1 event trigger edge for RTC tamp 1 input */ +#define RTC_TAMP_TPTS BIT(7) /*!< make tamper function used for timestamp function */ +#define RTC_TAMP_FREQ BITS(8,10) /*!< sample frequency of tamper event detection */ +#define RTC_TAMP_FLT BITS(11,12) /*!< RTC tamp x filter count setting */ +#define RTC_TAMP_PRCH BITS(13,14) /*!< precharge duration time of RTC tamp x */ +#define RTC_TAMP_DISPU BIT(15) /*!< RTC tamp x pull up disable bit */ +#define RTC_TAMP_TP0SEL BIT(16) /*!< Tamper 0 function input mapping selection */ +#define RTC_TAMP_TSSEL BIT(17) /*!< Timestamp input mapping selection */ +#define RTC_TAMP_AOT BIT(18) /*!< RTC_ALARM output Type */ + +/* RTC_ALRM0SS */ +#define RTC_ALRM0SS_SSC BITS(0,14) /*!< alarm0 sub second value */ +#define RTC_ALRM0SS_MASKSSC BITS(24,27) /*!< mask control bit of SS */ + +/* RTC_ALRM1SS */ +#define RTC_ALRM1SS_SSC BITS(0,14) /*!< alarm1 sub second value */ +#define RTC_ALRM1SS_MASKSSC BITS(24,27) /*!< mask control bit of SS */ + +/* constants definitions */ +/* structure for initialization of the RTC */ +typedef struct +{ + uint8_t year; /*!< RTC year value: 0x0 - 0x99(BCD format) */ + uint8_t month; /*!< RTC month value */ + uint8_t date; /*!< RTC date value: 0x1 - 0x31(BCD format) */ + uint8_t day_of_week; /*!< RTC weekday value */ + uint8_t hour; /*!< RTC hour value */ + uint8_t minute; /*!< RTC minute value: 0x0 - 0x59(BCD format) */ + uint8_t second; /*!< RTC second value: 0x0 - 0x59(BCD format) */ + uint16_t factor_asyn; /*!< RTC asynchronous prescaler value: 0x0 - 0x7F */ + uint16_t factor_syn; /*!< RTC synchronous prescaler value: 0x0 - 0x7FFF */ + uint32_t am_pm; /*!< RTC AM/PM value */ + uint32_t display_format; /*!< RTC time notation */ +}rtc_parameter_struct; + +/* structure for RTC alarm configuration */ +typedef struct +{ + uint32_t alarm_mask; /*!< RTC alarm mask */ + uint32_t weekday_or_date; /*!< specify RTC alarm is on date or weekday */ + uint8_t alarm_day; /*!< RTC alarm date or weekday value*/ + uint8_t alarm_hour; /*!< RTC alarm hour value */ + uint8_t alarm_minute; /*!< RTC alarm minute value: 0x0 - 0x59(BCD format) */ + uint8_t alarm_second; /*!< RTC alarm second value: 0x0 - 0x59(BCD format) */ + uint32_t am_pm; /*!< RTC alarm AM/PM value */ +}rtc_alarm_struct; + +/* structure for RTC time-stamp configuration */ +typedef struct +{ + uint8_t timestamp_month; /*!< RTC time-stamp month value */ + uint8_t timestamp_date; /*!< RTC time-stamp date value: 0x1 - 0x31(BCD format) */ + uint8_t timestamp_day; /*!< RTC time-stamp weekday value */ + uint8_t timestamp_hour; /*!< RTC time-stamp hour value */ + uint8_t timestamp_minute; /*!< RTC time-stamp minute value: 0x0 - 0x59(BCD format) */ + uint8_t timestamp_second; /*!< RTC time-stamp second value: 0x0 - 0x59(BCD format) */ + uint32_t am_pm; /*!< RTC time-stamp AM/PM value */ +}rtc_timestamp_struct; + +/* structure for RTC tamper configuration */ +typedef struct +{ + uint32_t tamper_source; /*!< RTC tamper source */ + uint32_t tamper_trigger; /*!< RTC tamper trigger */ + uint32_t tamper_filter; /*!< RTC tamper consecutive samples needed during a voltage level detection */ + uint32_t tamper_sample_frequency; /*!< RTC tamper sampling frequency during a voltage level detection */ + ControlStatus tamper_precharge_enable; /*!< RTC tamper precharge feature during a voltage level detection */ + uint32_t tamper_precharge_time; /*!< RTC tamper precharge duration if precharge feature is enabled */ + ControlStatus tamper_with_timestamp; /*!< RTC tamper time-stamp feature */ +}rtc_tamper_struct; + +/* time register value */ +#define TIME_SC(regval) (BITS(0,6) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_TIME_SC bit field */ +#define GET_TIME_SC(regval) GET_BITS((regval),0,6) /*!< get value of RTC_TIME_SC bit field */ + +#define TIME_MN(regval) (BITS(8,14) & ((uint32_t)(regval) << 8)) /*!< write value to RTC_TIME_MN bit field */ +#define GET_TIME_MN(regval) GET_BITS((regval),8,14) /*!< get value of RTC_TIME_MN bit field */ + +#define TIME_HR(regval) (BITS(16,21) & ((uint32_t)(regval) << 16)) /*!< write value to RTC_TIME_HR bit field */ +#define GET_TIME_HR(regval) GET_BITS((regval),16,21) /*!< get value of RTC_TIME_HR bit field */ + +#define RTC_AM ((uint32_t)0x00000000U) /*!< AM format */ +#define RTC_PM RTC_TIME_PM /*!< PM format */ + +/* date register value */ +#define DATE_DAY(regval) (BITS(0,5) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_DATE_DAY bit field */ +#define GET_DATE_DAY(regval) GET_BITS((regval),0,5) /*!< get value of RTC_DATE_DAY bit field */ + +#define DATE_MON(regval) (BITS(8,12) & ((uint32_t)(regval) << 8)) /*!< write value to RTC_DATE_MON bit field */ +#define GET_DATE_MON(regval) GET_BITS((regval),8,12) /*!< get value of RTC_DATE_MON bit field */ +#define RTC_JAN ((uint8_t)0x01U) /*!< janurary */ +#define RTC_FEB ((uint8_t)0x02U) /*!< february */ +#define RTC_MAR ((uint8_t)0x03U) /*!< march */ +#define RTC_APR ((uint8_t)0x04U) /*!< april */ +#define RTC_MAY ((uint8_t)0x05U) /*!< may */ +#define RTC_JUN ((uint8_t)0x06U) /*!< june */ +#define RTC_JUL ((uint8_t)0x07U) /*!< july */ +#define RTC_AUG ((uint8_t)0x08U) /*!< august */ +#define RTC_SEP ((uint8_t)0x09U) /*!< september */ +#define RTC_OCT ((uint8_t)0x10U) /*!< october */ +#define RTC_NOV ((uint8_t)0x11U) /*!< november */ +#define RTC_DEC ((uint8_t)0x12U) /*!< december */ + +#define DATE_DOW(regval) (BITS(13,15) & ((uint32_t)(regval) << 13)) /*!< write value to RTC_DATE_DOW bit field */ +#define GET_DATE_DOW(regval) GET_BITS((uint32_t)(regval),13,15) /*!< get value of RTC_DATE_DOW bit field */ +#define RTC_MONDAY ((uint8_t)0x01) /*!< monday */ +#define RTC_TUESDAY ((uint8_t)0x02) /*!< tuesday */ +#define RTC_WEDSDAY ((uint8_t)0x03) /*!< wednesday */ +#define RTC_THURSDAY ((uint8_t)0x04) /*!< thursday */ +#define RTC_FRIDAY ((uint8_t)0x05) /*!< friday */ +#define RTC_SATURDAY ((uint8_t)0x06) /*!< saturday */ +#define RTC_SUNDAY ((uint8_t)0x07) /*!< sunday */ + +#define DATE_YR(regval) (BITS(16,23) & ((uint32_t)(regval) << 16)) /*!< write value to RTC_DATE_YR bit field */ +#define GET_DATE_YR(regval) GET_BITS((regval),16,23) /*!< get value of RTC_DATE_YR bit field */ + +/* ctl register value */ +#define CTL_OS(regval) (BITS(21,22) & ((uint32_t)(regval) << 21)) /*!< write value to RTC_CTL_OS bit field */ +#define RTC_OS_DISABLE CTL_OS(0) /*!< disable output RTC_ALARM */ +#define RTC_OS_ALARM0 CTL_OS(1) /*!< enable alarm0 flag output */ +#define RTC_OS_ALARM1 CTL_OS(2) /*!< enable alarm1 flag output */ +#define RTC_OS_WAKEUP CTL_OS(3) /*!< enable wakeup flag output */ + +#define RTC_CALIBRATION_512HZ RTC_CTL_COEN /*!< calibration output of 512Hz is enable */ +#define RTC_CALIBRATION_1HZ (RTC_CTL_COEN | RTC_CTL_COS) /*!< calibration output of 1Hz is enable */ +#define RTC_ALARM0_HIGH RTC_OS_ALARM0 /*!< enable alarm0 flag output with high level */ +#define RTC_ALARM0_LOW (RTC_OS_ALARM0 | RTC_CTL_OPOL) /*!< enable alarm0 flag output with low level*/ +#define RTC_ALARM1_HIGH RTC_OS_ALARM1 /*!< enable alarm1 flag output with high level */ +#define RTC_ALARM1_LOW (RTC_OS_ALARM1 | RTC_CTL_OPOL) /*!< enable alarm1 flag output with low level*/ +#define RTC_WAKEUP_HIGH RTC_OS_WAKEUP /*!< enable wakeup flag output with high level */ +#define RTC_WAKEUP_LOW (RTC_OS_WAKEUP | RTC_CTL_OPOL) /*!< enable wakeup flag output with low level*/ + +#define RTC_24HOUR ((uint32_t)0x00000000U) /*!< 24-hour format */ +#define RTC_12HOUR RTC_CTL_CS /*!< 12-hour format */ + +#define RTC_TIMESTAMP_RISING_EDGE ((uint32_t)0x00000000U) /*!< rising edge is valid event edge for time-stamp event */ +#define RTC_TIMESTAMP_FALLING_EDGE RTC_CTL_TSEG /*!< falling edge is valid event edge for time-stamp event */ + +/* psc register value */ +#define PSC_FACTOR_S(regval) (BITS(0,14) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_PSC_FACTOR_S bit field */ +#define GET_PSC_FACTOR_S(regval) GET_BITS((regval),0,14) /*!< get value of RTC_PSC_FACTOR_S bit field */ + +#define PSC_FACTOR_A(regval) (BITS(16,22) & ((uint32_t)(regval) << 16)) /*!< write value to RTC_PSC_FACTOR_A bit field */ +#define GET_PSC_FACTOR_A(regval) GET_BITS((regval),16,22) /*!< get value of RTC_PSC_FACTOR_A bit field */ + +/* alrmtd register value */ +#define ALRMTD_SC(regval) (BITS(0,6) & ((uint32_t)(regval)<< 0)) /*!< write value to RTC_ALRMTD_SC bit field */ +#define GET_ALRMTD_SC(regval) GET_BITS((regval),0,6) /*!< get value of RTC_ALRMTD_SC bit field */ + +#define ALRMTD_MN(regval) (BITS(8,14) & ((uint32_t)(regval) << 8)) /*!< write value to RTC_ALRMTD_MN bit field */ +#define GET_ALRMTD_MN(regval) GET_BITS((regval),8,14) /*!< get value of RTC_ALRMTD_MN bit field */ + +#define ALRMTD_HR(regval) (BITS(16,21) & ((uint32_t)(regval) << 16)) /*!< write value to RTC_ALRMTD_HR bit field */ +#define GET_ALRMTD_HR(regval) GET_BITS((regval),16,21) /*!< get value of RTC_ALRMTD_HR bit field */ + +#define ALRMTD_DAY(regval) (BITS(24,29) & ((uint32_t)(regval) << 24)) /*!< write value to RTC_ALRMTD_DAY bit field */ +#define GET_ALRMTD_DAY(regval) GET_BITS((regval),24,29) /*!< get value of RTC_ALRMTD_DAY bit field */ + +#define RTC_ALARM_NONE_MASK ((uint32_t)0x00000000U) /*!< alarm none mask */ +#define RTC_ALARM_DATE_MASK RTC_ALRMXTD_MSKD /*!< alarm date mask */ +#define RTC_ALARM_HOUR_MASK RTC_ALRMXTD_MSKH /*!< alarm hour mask */ +#define RTC_ALARM_MINUTE_MASK RTC_ALRMXTD_MSKM /*!< alarm minute mask */ +#define RTC_ALARM_SECOND_MASK RTC_ALRMXTD_MSKS /*!< alarm second mask */ +#define RTC_ALARM_ALL_MASK (RTC_ALRMXTD_MSKD|RTC_ALRMXTD_MSKH|RTC_ALRMXTD_MSKM|RTC_ALRMXTD_MSKS) /*!< alarm all mask */ + +#define RTC_ALARM_DATE_SELECTED ((uint32_t)0x00000000U) /*!< alarm date format selected */ +#define RTC_ALARM_WEEKDAY_SELECTED RTC_ALRMXTD_DOWS /*!< alarm weekday format selected */ + +/* wpk register value */ +#define WPK_WPK(regval) (BITS(0,7) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_WPK_WPK bit field */ + +/* ss register value */ +#define SS_SSC(regval) (BITS(0,15) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_SS_SSC bit field */ + +/* shiftctl register value */ +#define SHIFTCTL_SFS(regval) (BITS(0,14) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_SHIFTCTL_SFS bit field */ + +#define RTC_SHIFT_ADD1S_RESET ((uint32_t)0x00000000U) /*!< not add 1 second */ +#define RTC_SHIFT_ADD1S_SET RTC_SHIFTCTL_A1S /*!< add one second to the clock */ + +/* tts register value */ +#define TTS_SC(regval) (BITS(0,6) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_TTS_SC bit field */ +#define GET_TTS_SC(regval) GET_BITS((regval),0,6) /*!< get value of RTC_TTS_SC bit field */ + +#define TTS_MN(regval) (BITS(8,14) & ((uint32_t)(regval) << 8)) /*!< write value to RTC_TTS_MN bit field */ +#define GET_TTS_MN(regval) GET_BITS((regval),8,14) /*!< get value of RTC_TTS_MN bit field */ + +#define TTS_HR(regval) (BITS(16,21) & ((uint32_t)(regval) << 16)) /*!< write value to RTC_TTS_HR bit field */ +#define GET_TTS_HR(regval) GET_BITS((regval),16,21) /*!< get value of RTC_TTS_HR bit field */ + +/* dts register value */ +#define DTS_DAY(regval) (BITS(0,5) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_DTS_DAY bit field */ +#define GET_DTS_DAY(regval) GET_BITS((regval),0,5) /*!< get value of RTC_DTS_DAY bit field */ + +#define DTS_MON(regval) (BITS(8,12) & ((uint32_t)(regval) << 8)) /*!< write value to RTC_DTS_MON bit field */ +#define GET_DTS_MON(regval) GET_BITS((regval),8,12) /*!< get value of RTC_DTS_MON bit field */ + +#define DTS_DOW(regval) (BITS(13,15) & ((uint32_t)(regval) << 13)) /*!< write value to RTC_DTS_DOW bit field */ +#define GET_DTS_DOW(regval) GET_BITS((regval),13,15) /*!< get value of RTC_DTS_DOW bit field */ + +/* ssts register value */ +#define SSTS_SSC(regval) (BITS(0,15) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_SSTS_SSC bit field */ + +/* hrfc register value */ +#define HRFC_CMSK(regval) (BITS(0,8) & ((uint32_t)(regval) << 0)) /*!< write value to RTC_HRFC_CMSK bit field */ + +#define RTC_CALIBRATION_WINDOW_32S ((uint32_t)0x00000000U) /*!< 2exp20 RTCCLK cycles, 32s if RTCCLK = 32768 Hz */ +#define RTC_CALIBRATION_WINDOW_16S RTC_HRFC_CWND16 /*!< 2exp19 RTCCLK cycles, 16s if RTCCLK = 32768 Hz */ +#define RTC_CALIBRATION_WINDOW_8S RTC_HRFC_CWND8 /*!< 2exp18 RTCCLK cycles, 8s if RTCCLK = 32768 Hz */ + +#define RTC_CALIBRATION_PLUS_SET RTC_HRFC_FREQI /*!< increase RTC frequency by 488.5ppm */ +#define RTC_CALIBRATION_PLUS_RESET ((uint32_t)0x00000000U) /*!< no effect */ + +/* tamp register value */ +#define TAMP_FREQ(regval) (BITS(8,10) & ((uint32_t)(regval) << 8)) /*!< write value to RTC_TAMP_FREQ bit field */ +#define RTC_FREQ_DIV32768 TAMP_FREQ(0) /*!< sample once every 32768 RTCCLK(1Hz if RTCCLK=32.768KHz) */ +#define RTC_FREQ_DIV16384 TAMP_FREQ(1) /*!< sample once every 16384 RTCCLK(2Hz if RTCCLK=32.768KHz) */ +#define RTC_FREQ_DIV8192 TAMP_FREQ(2) /*!< sample once every 8192 RTCCLK(4Hz if RTCCLK=32.768KHz) */ +#define RTC_FREQ_DIV4096 TAMP_FREQ(3) /*!< sample once every 4096 RTCCLK(8Hz if RTCCLK=32.768KHz) */ +#define RTC_FREQ_DIV2048 TAMP_FREQ(4) /*!< sample once every 2048 RTCCLK(16Hz if RTCCLK=32.768KHz) */ +#define RTC_FREQ_DIV1024 TAMP_FREQ(5) /*!< sample once every 1024 RTCCLK(32Hz if RTCCLK=32.768KHz) */ +#define RTC_FREQ_DIV512 TAMP_FREQ(6) /*!< sample once every 512 RTCCLK(64Hz if RTCCLK=32.768KHz) */ +#define RTC_FREQ_DIV256 TAMP_FREQ(7) /*!< sample once every 256 RTCCLK(128Hz if RTCCLK=32.768KHz) */ + +#define TAMP_FLT(regval) (BITS(11,12) & ((uint32_t)(regval) << 11)) /*!< write value to RTC_TAMP_FLT bit field */ +#define RTC_FLT_EDGE TAMP_FLT(0) /*!< detecting tamper event using edge mode. precharge duration is disabled automatically */ +#define RTC_FLT_2S TAMP_FLT(1) /*!< detecting tamper event using level mode.2 consecutive valid level samples will make a effective tamper event */ +#define RTC_FLT_4S TAMP_FLT(2) /*!< detecting tamper event using level mode.4 consecutive valid level samples will make an effective tamper event */ +#define RTC_FLT_8S TAMP_FLT(3) /*!< detecting tamper event using level mode.8 consecutive valid level samples will make a effective tamper event */ + +#define TAMP_PRCH(regval) (BITS(13,14) & ((uint32_t)(regval) << 13)) /*!< write value to RTC_TAMP_PRCH bit field */ +#define RTC_PRCH_1C TAMP_PRCH(0) /*!< 1 RTC clock prechagre time before each sampling */ +#define RTC_PRCH_2C TAMP_PRCH(1) /*!< 2 RTC clock prechagre time before each sampling */ +#define RTC_PRCH_4C TAMP_PRCH(2) /*!< 4 RTC clock prechagre time before each sampling */ +#define RTC_PRCH_8C TAMP_PRCH(3) /*!< 8 RTC clock prechagre time before each sampling */ + +#define RTC_TAMPER0 RTC_TAMP_TP0EN /*!< tamper 0 detection enable */ +#define RTC_TAMPER1 RTC_TAMP_TP1EN /*!< tamper 1 detection enable */ + +#define RTC_TAMPER_TRIGGER_EDGE_RISING ((uint32_t)0x00000000U) /*!< tamper detection is in rising edge mode */ +#define RTC_TAMPER_TRIGGER_EDGE_FALLING RTC_TAMP_TP0EG /*!< tamper detection is in falling edge mode */ +#define RTC_TAMPER_TRIGGER_LEVEL_LOW ((uint32_t)0x00000000U) /*!< tamper detection is in low level mode */ +#define RTC_TAMPER_TRIGGER_LEVEL_HIGH RTC_TAMP_TP0EG /*!< tamper detection is in high level mode */ + +#define RTC_TAMPER_TRIGGER_POS ((uint32_t)0x00000001U) /* shift position of trigger relative to source */ + +#define RTC_ALARM_OUTPUT_OD ((uint32_t)0x00000000U) /*!< RTC alarm output open-drain mode */ +#define RTC_ALARM_OUTPUT_PP RTC_TAMP_AOT /*!< RTC alarm output push-pull mode */ + +/* ALRMXSS register value */ +#define ALRMXSS_SSC(regval) (BITS(0,14) & ((uint32_t)(regval)<< 0)) /*!< write value to RTC_ALRMXSS_SSC bit field */ + +#define ALRMXSS_MASKSSC(regval) (BITS(24,27) & ((uint32_t)(regval) << 24)) /*!< write value to RTC_ALRMXSS_MASKSSC bit field */ +#define RTC_MASKSSC_0_14 ALRMXSS_MASKSSC(0) /*!< mask alarm subsecond configuration */ +#define RTC_MASKSSC_1_14 ALRMXSS_MASKSSC(1) /*!< mask RTC_ALRMXSS_SSC[14:1], and RTC_ALRMXSS_SSC[0] is to be compared */ +#define RTC_MASKSSC_2_14 ALRMXSS_MASKSSC(2) /*!< mask RTC_ALRMXSS_SSC[14:2], and RTC_ALRMXSS_SSC[1:0] is to be compared */ +#define RTC_MASKSSC_3_14 ALRMXSS_MASKSSC(3) /*!< mask RTC_ALRMXSS_SSC[14:3], and RTC_ALRMXSS_SSC[2:0] is to be compared */ +#define RTC_MASKSSC_4_14 ALRMXSS_MASKSSC(4) /*!< mask RTC_ALRMXSS_SSC[14:4]], and RTC_ALRMXSS_SSC[3:0] is to be compared */ +#define RTC_MASKSSC_5_14 ALRMXSS_MASKSSC(5) /*!< mask RTC_ALRMXSS_SSC[14:5], and RTC_ALRMXSS_SSC[4:0] is to be compared */ +#define RTC_MASKSSC_6_14 ALRMXSS_MASKSSC(6) /*!< mask RTC_ALRMXSS_SSC[14:6], and RTC_ALRMXSS_SSC[5:0] is to be compared */ +#define RTC_MASKSSC_7_14 ALRMXSS_MASKSSC(7) /*!< mask RTC_ALRMXSS_SSC[14:7], and RTC_ALRMXSS_SSC[6:0] is to be compared */ +#define RTC_MASKSSC_8_14 ALRMXSS_MASKSSC(8) /*!< mask RTC_ALRMXSS_SSC[14:7], and RTC_ALRMXSS_SSC[6:0] is to be compared */ +#define RTC_MASKSSC_9_14 ALRMXSS_MASKSSC(9) /*!< mask RTC_ALRMXSS_SSC[14:9], and RTC_ALRMXSS_SSC[8:0] is to be compared */ +#define RTC_MASKSSC_10_14 ALRMXSS_MASKSSC(10) /*!< mask RTC_ALRMXSS_SSC[14:10], and RTC_ALRMXSS_SSC[9:0] is to be compared */ +#define RTC_MASKSSC_11_14 ALRMXSS_MASKSSC(11) /*!< mask RTC_ALRMXSS_SSC[14:11], and RTC_ALRMXSS_SSC[10:0] is to be compared */ +#define RTC_MASKSSC_12_14 ALRMXSS_MASKSSC(12) /*!< mask RTC_ALRMXSS_SSC[14:12], and RTC_ALRMXSS_SSC[11:0] is to be compared */ +#define RTC_MASKSSC_13_14 ALRMXSS_MASKSSC(13) /*!< mask RTC_ALRMXSS_SSC[14:13], and RTC_ALRMXSS_SSC[12:0] is to be compared */ +#define RTC_MASKSSC_14 ALRMXSS_MASKSSC(14) /*!< mask RTC_ALRMXSS_SSC[14], and RTC_ALRMXSS_SSC[13:0] is to be compared */ +#define RTC_MASKSSC_NONE ALRMXSS_MASKSSC(15) /*!< mask none, and RTC_ALRMXSS_SSC[14:0] is to be compared */ + +/* RTC interrupt source */ +#define RTC_INT_TIMESTAMP RTC_CTL_TSIE /*!< time-stamp interrupt enable */ +#define RTC_INT_ALARM0 RTC_CTL_ALRM0IE /*!< RTC alarm0 interrupt enable */ +#define RTC_INT_ALARM1 RTC_CTL_ALRM1IE /*!< RTC alarm1 interrupt enable */ +#define RTC_INT_TAMP RTC_TAMP_TPIE /*!< tamper detection interrupt enable */ +#define RTC_INT_WAKEUP RTC_CTL_WTIE /*!< RTC wakeup timer interrupt enable */ + +/* write protect key */ +#define RTC_UNLOCK_KEY1 ((uint8_t)0xCAU) /*!< RTC unlock key1 */ +#define RTC_UNLOCK_KEY2 ((uint8_t)0x53U) /*!< RTC unlock key2 */ +#define RTC_LOCK_KEY ((uint8_t)0xFFU) /*!< RTC lock key */ + +/* registers reset value */ +#define RTC_REGISTER_RESET ((uint32_t)0x00000000U) /*!< RTC common register reset value */ +#define RTC_DATE_RESET ((uint32_t)0x00002101U) /*!< RTC_DATE register reset value */ +#define RTC_STAT_RESET ((uint32_t)0x00000000U) /*!< RTC_STAT register reset value */ +#define RTC_PSC_RESET ((uint32_t)0x007F00FFU) /*!< RTC_PSC register reset value */ +#define RTC_WUT_RESET ((uint32_t)0x0000FFFFU) /*!< RTC_WUT register reset value */ + +/* RTC alarm */ +#define RTC_ALARM0 ((uint8_t)0x01U) /*!< RTC alarm 0 */ +#define RTC_ALARM1 ((uint8_t)0x02U) /*!< RTC alarm 1 */ + +/* RTC coarse calibration direction */ +#define CALIB_INCREASE ((uint8_t)0x01U) /*!< RTC coarse calibration increase */ +#define CALIB_DECREASE ((uint8_t)0x02U) /*!< RTC coarse calibration decrease */ + +/* RTC wakeup timer clock */ +#define CTL_WTCS(regval) (BITS(0,2) & ((regval)<< 0)) +#define WAKEUP_RTCCK_DIV16 CTL_WTCS(0) /*!< wakeup timer clock is RTC clock divided by 16 */ +#define WAKEUP_RTCCK_DIV8 CTL_WTCS(1) /*!< wakeup timer clock is RTC clock divided by 8 */ +#define WAKEUP_RTCCK_DIV4 CTL_WTCS(2) /*!< wakeup timer clock is RTC clock divided by 4 */ +#define WAKEUP_RTCCK_DIV2 CTL_WTCS(3) /*!< wakeup timer clock is RTC clock divided by 2 */ +#define WAKEUP_CKSPRE CTL_WTCS(4) /*!< wakeup timer clock is ckspre */ +#define WAKEUP_CKSPRE_2EXP16 CTL_WTCS(6) /*!< wakeup timer clock is ckspre and wakeup timer add 2exp16 */ + +/* RTC_AF pin */ +#define RTC_AF0_TIMESTAMP ((uint32_t)0x00000000) /*!< RTC_AF0 use for timestamp */ +#define RTC_AF1_TIMESTAMP RTC_TAMP_TSSEL /*!< RTC_AF1 use for timestamp */ +#define RTC_AF0_TAMPER0 ((uint32_t)0x00000000) /*!< RTC_AF0 use for tamper0 */ +#define RTC_AF1_TAMPER0 RTC_TAMP_TP0SEL /*!< RTC_AF1 use for tamper0 */ + +/* RTC flags */ +#define RTC_FLAG_ALRM0W RTC_STAT_ALRM0WF /*!< alarm0 configuration can be write flag */ +#define RTC_FLAG_ALRM1W RTC_STAT_ALRM1WF /*!< alarm1 configuration can be write flag */ +#define RTC_FLAG_WTW RTC_STAT_WTWF /*!< wakeup timer can be write flag */ +#define RTC_FLAG_SOP RTC_STAT_SOPF /*!< shift function operation pending flag */ +#define RTC_FLAG_YCM RTC_STAT_YCM /*!< year configuration mark status flag */ +#define RTC_FLAG_RSYN RTC_STAT_RSYNF /*!< register synchronization flag */ +#define RTC_FLAG_INIT RTC_STAT_INITF /*!< initialization state flag */ +#define RTC_FLAG_ALRM0 RTC_STAT_ALRM0F /*!< alarm0 occurs flag */ +#define RTC_FLAG_ALRM1 RTC_STAT_ALRM1F /*!< alarm1 occurs flag */ +#define RTC_FLAG_WT RTC_STAT_WTF /*!< wakeup timer occurs flag */ +#define RTC_FLAG_TS RTC_STAT_TSF /*!< time-stamp flag */ +#define RTC_FLAG_TSOVR RTC_STAT_TSOVRF /*!< time-stamp overflow flag */ +#define RTC_FLAG_TP0 RTC_STAT_TP0F /*!< RTC tamper 0 detected flag */ +#define RTC_FLAG_TP1 RTC_STAT_TP1F /*!< RTC tamper 1 detected flag */ +#define RTC_STAT_SCP RTC_STAT_SCPF /*!< smooth calibration pending flag */ + +/* function declarations */ +/* reset most of the RTC registers */ +ErrStatus rtc_deinit(void); +/* initialize RTC registers */ +ErrStatus rtc_init(rtc_parameter_struct* rtc_initpara_struct); +/* enter RTC init mode */ +ErrStatus rtc_init_mode_enter(void); +/* exit RTC init mode */ +void rtc_init_mode_exit(void); +/* wait until RTC_TIME and RTC_DATE registers are synchronized with APB clock, and the shadow registers are updated */ +ErrStatus rtc_register_sync_wait(void); + +/* get current time and date */ +void rtc_current_time_get(rtc_parameter_struct* rtc_initpara_struct); +/* get current subsecond value */ +uint32_t rtc_subsecond_get(void); + +/* configure RTC alarm */ +void rtc_alarm_config(uint8_t rtc_alarm, rtc_alarm_struct* rtc_alarm_time); +/* configure subsecond of RTC alarm */ +void rtc_alarm_subsecond_config(uint8_t rtc_alarm, uint32_t mask_subsecond, uint32_t subsecond); +/* get RTC alarm */ +void rtc_alarm_get(uint8_t rtc_alarm,rtc_alarm_struct* rtc_alarm_time); +/* get RTC alarm subsecond */ +uint32_t rtc_alarm_subsecond_get(uint8_t rtc_alarm); +/* enable RTC alarm */ +void rtc_alarm_enable(uint8_t rtc_alarm); +/* disable RTC alarm */ +ErrStatus rtc_alarm_disable(uint8_t rtc_alarm); + +/* enable RTC time-stamp */ +void rtc_timestamp_enable(uint32_t edge); +/* disable RTC time-stamp */ +void rtc_timestamp_disable(void); +/* get RTC timestamp time and date */ +void rtc_timestamp_get(rtc_timestamp_struct* rtc_timestamp); +/* get RTC time-stamp subsecond */ +uint32_t rtc_timestamp_subsecond_get(void); +/* RTC time-stamp pin map */ +void rtc_timestamp_pin_map(uint32_t rtc_af); + +/* enable RTC tamper */ +void rtc_tamper_enable(rtc_tamper_struct* rtc_tamper); +/* disable RTC tamper */ +void rtc_tamper_disable(uint32_t source); +/* RTC tamper0 pin map */ +void rtc_tamper0_pin_map(uint32_t rtc_af); + +/* enable specified RTC interrupt */ +void rtc_interrupt_enable(uint32_t interrupt); +/* disable specified RTC interrupt */ +void rtc_interrupt_disable(uint32_t interrupt); +/* check specified flag */ +FlagStatus rtc_flag_get(uint32_t flag); +/* clear specified flag */ +void rtc_flag_clear(uint32_t flag); + +/* configure RTC alarm output source */ +void rtc_alarm_output_config(uint32_t source, uint32_t mode); +/* configure RTC calibration output source */ +void rtc_calibration_output_config(uint32_t source); + +/* adjust the daylight saving time by adding or substracting one hour from the current time */ +void rtc_hour_adjust(uint32_t operation); +/* adjust RTC second or subsecond value of current time */ +ErrStatus rtc_second_adjust(uint32_t add, uint32_t minus); + +/* enable RTC bypass shadow registers function */ +void rtc_bypass_shadow_enable(void); +/* disable RTC bypass shadow registers function */ +void rtc_bypass_shadow_disable(void); + +/* enable RTC reference clock detection function */ +ErrStatus rtc_refclock_detection_enable(void); +/* disable RTC reference clock detection function */ +ErrStatus rtc_refclock_detection_disable(void); + +/* enable RTC wakeup timer */ +void rtc_wakeup_enable(void); +/* disable RTC wakeup timer */ +ErrStatus rtc_wakeup_disable(void); +/* set auto wakeup timer clock */ +ErrStatus rtc_wakeup_clock_set(uint8_t wakeup_clock); +/* set auto wakeup timer value */ +ErrStatus rtc_wakeup_timer_set(uint16_t wakeup_timer); +/* get auto wakeup timer value */ +uint16_t rtc_wakeup_timer_get(void); + +/* configure RTC smooth calibration */ +ErrStatus rtc_smooth_calibration_config(uint32_t window, uint32_t plus, uint32_t minus); +/* enable RTC coarse calibration */ +ErrStatus rtc_coarse_calibration_enable(void); +/* disable RTC coarse calibration */ +ErrStatus rtc_coarse_calibration_disable(void); +/* configure RTC coarse calibration direction and step */ +ErrStatus rtc_coarse_calibration_config(uint8_t direction, uint8_t step); + +#endif /* GD32F5XX_RTC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_sai.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_sai.h new file mode 100644 index 0000000..1ccd771 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_sai.h @@ -0,0 +1,473 @@ +/*! + \file gd32f5xx_sai.h + \brief definitions for the SAI + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + 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 the copyright holder 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 GD32F5XX_SAI_H +#define GD32F5XX_SAI_H + +#include "gd32f5xx.h" + +/* SAI definitions */ +#define SAI SAI_BASE /*!< SAI base address */ + +/* registers definitions */ +#define SAI_SYNCFG REG32((SAI) + 0x00000000U) /*!< SAI synchronize configuration register */ +#define SAI_B0CFG0 REG32((SAI) + 0x00000004U) /*!< SAI block 0 configuration register0 */ +#define SAI_B0CFG1 REG32((SAI) + 0x00000008U) /*!< SAI block 0 configuration register1 */ +#define SAI_B0FCFG REG32((SAI) + 0x0000000CU) /*!< SAI block 0 frame configuration register */ +#define SAI_B0SCFG REG32((SAI) + 0x00000010U) /*!< SAI block 0 slot configuration register */ +#define SAI_B0INTEN REG32((SAI) + 0x00000014U) /*!< SAI block 0 interrupt enable register */ +#define SAI_B0STAT REG32((SAI) + 0x00000018U) /*!< SAI block 0 status register */ +#define SAI_B0INTC REG32((SAI) + 0x0000001CU) /*!< SAI block 0 interrupt flag clear register */ +#define SAI_B0DATA REG32((SAI) + 0x00000020U) /*!< SAI block 0 data register */ +#define SAI_B1CFG0 REG32((SAI) + 0x00000024U) /*!< SAI block 1 configuration register0 */ +#define SAI_B1CFG1 REG32((SAI) + 0x00000028U) /*!< SAI block 1 configuration register1 */ +#define SAI_B1FCFG REG32((SAI) + 0x0000002CU) /*!< SAI block 1 frame configuration register */ +#define SAI_B1SCFG REG32((SAI) + 0x00000030U) /*!< SAI block 1 slot configuration register */ +#define SAI_B1INTEN REG32((SAI) + 0x00000034U) /*!< SAI block 1 interrupt enable register */ +#define SAI_B1STAT REG32((SAI) + 0x00000038U) /*!< SAI block 1 status register */ +#define SAI_B1INTC REG32((SAI) + 0x0000003CU) /*!< SAI block 1 interrupt flag clear register */ +#define SAI_B1DATA REG32((SAI) + 0x00000040U) /*!< SAI block 1 data register */ + +#define SAI_CFG0(blocky) REG32(((SAI) + 0x00000004U) + 0x20U*(blocky)) /*!< SAI block configuration register0 */ +#define SAI_CFG1(blocky) REG32(((SAI) + 0x00000008U) + 0x20U*(blocky)) /*!< SAI block configuration register1 */ +#define SAI_FCFG(blocky) REG32(((SAI) + 0x0000000CU) + 0x20U*(blocky)) /*!< SAI block frame configuration register */ +#define SAI_SCFG(blocky) REG32(((SAI) + 0x00000010U) + 0x20U*(blocky)) /*!< SAI block slot configuration register */ +#define SAI_INTEN(blocky) REG32(((SAI) + 0x00000014U) + 0x20U*(blocky)) /*!< SAI block interrupt enable register */ +#define SAI_STAT(blocky) REG32(((SAI) + 0x00000018U) + 0x20U*(blocky)) /*!< SAI block status register */ +#define SAI_INTC(blocky) REG32(((SAI) + 0x0000001CU) + 0x20U*(blocky)) /*!< SAI block interrupt flag clear register */ +#define SAI_DATA(blocky) REG32(((SAI) + 0x00000020U) + 0x20U*(blocky)) /*!< SAI block data register */ + +/* bits definitions */ +/* SAI_SYNCFG */ +#define SAI_SYNCFG_SYNI BITS(0,1) /*!< synchronization inputs */ +#define SAI_SYNCFG_SYNO BITS(4,5) /*!< synchronization outputs */ + +/* SAI_CFG0 */ +#define SAI_CFG0_OPTMOD BITS(0,1) /*!< operating mode */ +#define SAI_CFG0_PROT BITS(2,3) /*!< protocol selection */ +#define SAI_CFG0_DATAWD BITS(5,7) /*!< data width */ +#define SAI_CFG0_SHIFTDIR BIT(8) /*!< shift direction */ +#define SAI_CFG0_SAMPEDGE BIT(9) /*!< sampling clock edge */ +#define SAI_CFG0_SYNCMOD BITS(10,11) /*!< synchronization mode */ +#define SAI_CFG0_MONO BIT(12) /*!< stereo and mono mode selection */ +#define SAI_CFG0_ODRIV BIT(13) /*!< output drive */ +#define SAI_CFG0_SAIEN BIT(16) /*!< sai sub-block enable */ +#define SAI_CFG0_DMAEN BIT(17) /*!< DMA enable */ +#define SAI_CFG0_BYPASS BIT(19) /*!< clock divider logic bypass */ +#define SAI_CFG0_MDIV BITS(20,25) /*!< master clock divider ratio */ +#define SAI_CFG0_MOSPR BIT(26) /*!< the master clock oversampling rate */ +#define SAI_CFG0_MCLKEN BIT(27) /*!< the master clock enable */ + +/* SAI_CFG1 */ +#define SAI_CFG1_FFTH BITS(0,2) /*!< FIFO threshold */ +#define SAI_CFG1_FLUSH BIT(3) /*!< FIFO flush */ +#define SAI_CFG1_SDOM BIT(4) /*!< serial data output management */ +#define SAI_CFG1_MT BIT(5) /*!< mute mode on */ +#define SAI_CFG1_MTVAL BIT(6) /*!< mute value */ +#define SAI_CFG1_MTFCNT BITS(7,12) /*!< mute frame count */ +#define SAI_CFG1_CPLMOD BIT(13) /*!< complement mode */ +#define SAI_CFG1_CPAMOD BITS(14,15) /*!< compander mode */ + +/* SAI_FCFG */ +#define SAI_FCFG_FWD BITS(0,7) /*!< frame width */ +#define SAI_FCFG_FSAWD BITS(8,14) /*!< frame synchronization active width */ +#define SAI_FCFG_FSFUNC BIT(16) /*!< frame synchronization function */ +#define SAI_FCFG_FSPL BIT(17) /*!< Frame synchronization active polarity */ +#define SAI_FCFG_FSOST BIT(18) /*!< frame synchronization offset */ + +/* SAI_SCFG */ +#define SAI_SCFG_DATAOST BITS(0,4) /*!< data offset */ +#define SAI_SCFG_SLOTWD BITS(6,7) /*!< slot width */ +#define SAI_SCFG_SLOTNUM BITS(8,11) /*!< slot number within frame */ +#define SAI_SCFG_SLOTAV BITS(16,31) /*!< slot activation vector */ + +/* SAI_INTEN */ +#define SAI_INTEN_OUERRIE BIT(0) /*!< FIFO overrun or underrun interrupt enable */ +#define SAI_INTEN_MTDETIE BIT(1) /*!< mute detection interrupt enable */ +#define SAI_INTEN_ERRCKIE BIT(2) /*!< error clock interrupt enable */ +#define SAI_INTEN_FFREQIE BIT(3) /*!< FIFO request interrupt enable */ +#define SAI_INTEN_ACNRDYIE BIT(4) /*!< audio codec not ready interrupt enable */ +#define SAI_INTEN_FSADETIE BIT(5) /*!< frame synchronization advanced detection interrupt enable */ +#define SAI_INTEN_FSPDETIE BIT(6) /*!< frame synchronization postpone detection interrupt enable */ + +/* SAI_STAT */ +#define SAI_STAT_OUERR BIT(0) /*!< FIFO overrun or underrun */ +#define SAI_STAT_MTDET BIT(1) /*!< mute detection */ +#define SAI_STAT_ERRCK BIT(2) /*!< error clock */ +#define SAI_STAT_FFREQ BIT(3) /*!< FIFO request */ +#define SAI_STAT_ACNRDY BIT(4) /*!< audio codec not ready */ +#define SAI_STAT_FSADET BIT(5) /*!< frame synchronization advanced detection */ +#define SAI_STAT_FSPDET BIT(6) /*!< frame synchronization postpone detection */ +#define SAI_STAT_FFSTAT BITS(16,18) /*!< FIFO status */ + +/* SAI_INTC */ +#define SAI_INTC_OUERRC BIT(0) /*!< FIFO overrun or underrun interrupt clear */ +#define SAI_INTC_MTDETC BIT(1) /*!< mute detection interrupt clear */ +#define SAI_INTC_ERRCKC BIT(2) /*!< error clock interrupt clear */ +#define SAI_INTC_ACNRDYC BIT(4) /*!< audio codec not ready interrupt clear */ +#define SAI_INTC_FSADETC BIT(5) /*!< frame synchronization advanced detection interrupt clear */ +#define SAI_INTC_FSPDETC BIT(6) /*!< frame synchronization postpone detection interrupt clear */ + +/* SAI_DATA */ +#define SAI_DATA_DATA BITS(0,31) /*!< transfer data or receive data */ + +/* constants definitions */ +/* SAI initialize parameter struct definitions */ +typedef struct { + uint32_t operating_mode; /*!< operating mode */ + uint32_t protocol; /*!< protocol selection */ + uint32_t data_width; /*!< data width */ + uint32_t shift_dir; /*!< shift direction */ + uint32_t sample_edge; /*!< sampling clock edge */ + uint32_t sync_mode; /*!< synchronization mode */ + uint32_t output_drive; /*!< output drive */ + uint32_t clk_div_bypass; /*!< clock divider logic bypass */ + uint32_t mclk_div; /*!< master clock divider ratio */ + uint32_t mclk_oversampling; /*!< the master clock oversampling rate */ + uint32_t mclk_enable; /*!< the master clock enable */ + uint32_t fifo_threshold; /*!< FIFO threshold */ +} sai_parameter_struct; + +/* SAI frame initialize parameter struct definitions */ +typedef struct { + uint32_t frame_width; /*!< frame width */ + uint32_t frame_sync_width; /*!< frame synchronization active width */ + uint32_t frame_sync_function; /*!< frame synchronization function */ + uint32_t frame_sync_polarity; /*!< frame synchronization active polarity */ + uint32_t frame_sync_offset; /*!< frame synchronization offset */ +} sai_frame_parameter_struct; + +/* SAI slot initialize parameter struct definitions */ +typedef struct { + uint32_t slot_number; /*!< slot number */ + uint32_t slot_width; /*!< slot width */ + uint32_t data_offset; /*!< data offset */ + uint32_t slot_active; /*!< slot activation vector */ +} sai_slot_parameter_struct; + +/* SAI FIFO status */ +typedef enum { + FIFO_EMPTY = 0U, /*!< empty */ + FIFO_EMPTY_TO_1_4_FULL, /*!< empty < fifo_level <= 1/4_full. */ + FIFO_1_4_FULL_TO_1_2_FULL, /*!< 1/4_full < fifo_level <= 1/2_full. */ + FIFO_1_2_FULL_TO_3_4_FULL, /*!< 1/2_full < fifo_level <= 3/4_full. */ + FIFO_3_4_FULL_TO_FULL, /*!< 3/4_full < fifo_level < full */ + FIFO_FULL /*!< full */ +} sai_fifo_state_enum; +/* SAI master clock enable */ +#define SAI_MCLK_DISABLE ((uint32_t)0x00000000U) /*!< the master clock is enable when SAI enable */ +#define SAI_MCLK_ENABLE SAI_CFG0_MCLKEN /*!< the master clock is enable now */ + +/* SAI master clock oversampling rate */ +#define SAI_MCLK_OVERSAMP_256 ((uint32_t)0x00000000U) /*!< MCLK = 256 * Ffs */ +#define SAI_MCLK_OVERSAMP_512 SAI_CFG0_MOSPR /*!< MCLK = 512 * Ffs */ + +/* SAI master clock divider ratio definitions */ +#define CFG0_MDIV(regval) (BITS(20,25)&((uint32_t)(regval) << 20U)) +#define SAI_MCLKDIV_1 CFG0_MDIV(0) /*!< primary frequency divider logic bypass */ +#define SAI_MCLKDIV_2 CFG0_MDIV(2) /*!< SAI clock is divided by 2 */ +#define SAI_MCLKDIV_3 CFG0_MDIV(3) /*!< SAI clock is divided by 3 */ +#define SAI_MCLKDIV_4 CFG0_MDIV(4) /*!< SAI clock is divided by 4 */ +#define SAI_MCLKDIV_5 CFG0_MDIV(5) /*!< SAI clock is divided by 5 */ +#define SAI_MCLKDIV_6 CFG0_MDIV(6) /*!< SAI clock is divided by 6 */ +#define SAI_MCLKDIV_7 CFG0_MDIV(7) /*!< SAI clock is divided by 7 */ +#define SAI_MCLKDIV_8 CFG0_MDIV(8) /*!< SAI clock is divided by 8 */ +#define SAI_MCLKDIV_9 CFG0_MDIV(9) /*!< SAI clock is divided by 9 */ +#define SAI_MCLKDIV_10 CFG0_MDIV(10) /*!< SAI clock is divided by 10 */ +#define SAI_MCLKDIV_11 CFG0_MDIV(11) /*!< SAI clock is divided by 11 */ +#define SAI_MCLKDIV_12 CFG0_MDIV(12) /*!< SAI clock is divided by 12 */ +#define SAI_MCLKDIV_13 CFG0_MDIV(13) /*!< SAI clock is divided by 13 */ +#define SAI_MCLKDIV_14 CFG0_MDIV(14) /*!< SAI clock is divided by 14 */ +#define SAI_MCLKDIV_15 CFG0_MDIV(15) /*!< SAI clock is divided by 15 */ +#define SAI_MCLKDIV_16 CFG0_MDIV(16) /*!< SAI clock is divided by 16 */ +#define SAI_MCLKDIV_17 CFG0_MDIV(17) /*!< SAI clock is divided by 17 */ +#define SAI_MCLKDIV_18 CFG0_MDIV(18) /*!< SAI clock is divided by 18 */ +#define SAI_MCLKDIV_19 CFG0_MDIV(19) /*!< SAI clock is divided by 19 */ +#define SAI_MCLKDIV_20 CFG0_MDIV(20) /*!< SAI clock is divided by 20 */ +#define SAI_MCLKDIV_21 CFG0_MDIV(21) /*!< SAI clock is divided by 21 */ +#define SAI_MCLKDIV_22 CFG0_MDIV(22) /*!< SAI clock is divided by 22 */ +#define SAI_MCLKDIV_23 CFG0_MDIV(23) /*!< SAI clock is divided by 23 */ +#define SAI_MCLKDIV_24 CFG0_MDIV(24) /*!< SAI clock is divided by 24 */ +#define SAI_MCLKDIV_25 CFG0_MDIV(25) /*!< SAI clock is divided by 25 */ +#define SAI_MCLKDIV_26 CFG0_MDIV(26) /*!< SAI clock is divided by 26 */ +#define SAI_MCLKDIV_27 CFG0_MDIV(27) /*!< SAI clock is divided by 27 */ +#define SAI_MCLKDIV_28 CFG0_MDIV(28) /*!< SAI clock is divided by 28 */ +#define SAI_MCLKDIV_29 CFG0_MDIV(29) /*!< SAI clock is divided by 29 */ +#define SAI_MCLKDIV_30 CFG0_MDIV(30) /*!< SAI clock is divided by 30 */ +#define SAI_MCLKDIV_31 CFG0_MDIV(31) /*!< SAI clock is divided by 31 */ +#define SAI_MCLKDIV_32 CFG0_MDIV(32) /*!< SAI clock is divided by 32 */ +#define SAI_MCLKDIV_33 CFG0_MDIV(33) /*!< SAI clock is divided by 33 */ +#define SAI_MCLKDIV_34 CFG0_MDIV(34) /*!< SAI clock is divided by 34 */ +#define SAI_MCLKDIV_35 CFG0_MDIV(35) /*!< SAI clock is divided by 35 */ +#define SAI_MCLKDIV_36 CFG0_MDIV(36) /*!< SAI clock is divided by 36 */ +#define SAI_MCLKDIV_37 CFG0_MDIV(37) /*!< SAI clock is divided by 37 */ +#define SAI_MCLKDIV_38 CFG0_MDIV(38) /*!< SAI clock is divided by 38 */ +#define SAI_MCLKDIV_39 CFG0_MDIV(39) /*!< SAI clock is divided by 39 */ +#define SAI_MCLKDIV_40 CFG0_MDIV(40) /*!< SAI clock is divided by 40 */ +#define SAI_MCLKDIV_41 CFG0_MDIV(41) /*!< SAI clock is divided by 41 */ +#define SAI_MCLKDIV_42 CFG0_MDIV(42) /*!< SAI clock is divided by 42 */ +#define SAI_MCLKDIV_43 CFG0_MDIV(43) /*!< SAI clock is divided by 43 */ +#define SAI_MCLKDIV_44 CFG0_MDIV(44) /*!< SAI clock is divided by 44 */ +#define SAI_MCLKDIV_45 CFG0_MDIV(45) /*!< SAI clock is divided by 45 */ +#define SAI_MCLKDIV_46 CFG0_MDIV(46) /*!< SAI clock is divided by 46 */ +#define SAI_MCLKDIV_47 CFG0_MDIV(47) /*!< SAI clock is divided by 47 */ +#define SAI_MCLKDIV_48 CFG0_MDIV(48) /*!< SAI clock is divided by 48 */ +#define SAI_MCLKDIV_49 CFG0_MDIV(49) /*!< SAI clock is divided by 49 */ +#define SAI_MCLKDIV_50 CFG0_MDIV(50) /*!< SAI clock is divided by 50 */ +#define SAI_MCLKDIV_51 CFG0_MDIV(51) /*!< SAI clock is divided by 51 */ +#define SAI_MCLKDIV_52 CFG0_MDIV(52) /*!< SAI clock is divided by 52 */ +#define SAI_MCLKDIV_53 CFG0_MDIV(53) /*!< SAI clock is divided by 53 */ +#define SAI_MCLKDIV_54 CFG0_MDIV(54) /*!< SAI clock is divided by 54 */ +#define SAI_MCLKDIV_55 CFG0_MDIV(55) /*!< SAI clock is divided by 55 */ +#define SAI_MCLKDIV_56 CFG0_MDIV(56) /*!< SAI clock is divided by 56 */ +#define SAI_MCLKDIV_57 CFG0_MDIV(57) /*!< SAI clock is divided by 57 */ +#define SAI_MCLKDIV_58 CFG0_MDIV(58) /*!< SAI clock is divided by 58 */ +#define SAI_MCLKDIV_59 CFG0_MDIV(59) /*!< SAI clock is divided by 59 */ +#define SAI_MCLKDIV_60 CFG0_MDIV(60) /*!< SAI clock is divided by 60 */ +#define SAI_MCLKDIV_61 CFG0_MDIV(61) /*!< SAI clock is divided by 61 */ +#define SAI_MCLKDIV_62 CFG0_MDIV(62) /*!< SAI clock is divided by 62 */ +#define SAI_MCLKDIV_63 CFG0_MDIV(63) /*!< SAI clock is divided by 63 */ + +/* SAI clock divider logic bypass */ +#define SAI_CLKDIV_BYPASS_OFF ((uint32_t)0x00000000U) /*!< clock divider ratio is applied to both primary and secondary divider logic */ +#define SAI_CLKDIV_BYPASS_ON SAI_CFG0_BYPASS /*!< clock divider logic is bypassed */ + +/* SAI output drive */ +#define SAI_OUTPUT_WITH_SAIEN ((uint32_t)0x00000000U) /*!< SAI sub-block output driven only when SAIEN is set */ +#define SAI_OUTPUT_NOW SAI_CFG0_ODRIV /*!< SAI sub-block output driven according to ODRIV setting */ + +/* SAI stereo and mono mode selection */ +#define SAI_STEREO_MODE ((uint32_t)0x00000000U) /*!< stereo mode */ +#define SAI_MONO_MODE SAI_CFG0_MONO /*!< mono mode */ + +/* SAI synchronization mode definitions */ +#define CFG0_SYNCMOD(regval) (BITS(10,11)&((uint32_t)(regval) << 10U)) +#define SAI_SYNCMODE_ASYNC CFG0_SYNCMOD(0) /*!< asynchronous with the other sub-block */ +#define SAI_SYNCMODE_OTHERBLOCK CFG0_SYNCMOD(1) /*!< synchronous with the other sub-block */ + +/* SAI sampling clock edge */ +#define SAI_SAMPEDGE_FALLING ((uint32_t)0x00000000U) /*!< data sampled on SCK falling edge */ +#define SAI_SAMPEDGE_RISING SAI_CFG0_SAMPEDGE /*!< data sampled on SCK rising edge */ + +/* SAI Shift direction */ +#define SAI_SHIFT_MSB ((uint32_t)0x00000000U) /*!< data is shifted with MSB first */ +#define SAI_SHIFT_LSB SAI_CFG0_SHIFTDIR /*!< data is shifted with LSB first */ + +/* SAI data width definitions */ +#define CFG0_DW(regval) (BITS(5,7)&((uint32_t)(regval) << 5U)) +#define SAI_DATAWIDTH_8BIT CFG0_DW(2) /*!< SAI data width 8 bit */ +#define SAI_DATAWIDTH_10BIT CFG0_DW(3) /*!< SAI data width 10 bit */ +#define SAI_DATAWIDTH_16BIT CFG0_DW(4) /*!< SAI data width 16 bit */ +#define SAI_DATAWIDTH_20BIT CFG0_DW(5) /*!< SAI data width 20 bit */ +#define SAI_DATAWIDTH_24BIT CFG0_DW(6) /*!< SAI data width 24 bit */ +#define SAI_DATAWIDTH_32BIT CFG0_DW(7) /*!< SAI data width 32 bit */ + +/* SAI protocol selection */ +#define CFG0_PROTOCOL(regval) (BITS(2,3)&((uint32_t)(regval) << 2U)) +#define SAI_PROTOCOL_POLYMORPHIC CFG0_PROTOCOL(0) /*!< polymorphic */ +#define SAI_PROTOCOL_SPDIF CFG0_PROTOCOL(1) /*!< SPDIF */ +#define SAI_PROTOCOL_AC97 CFG0_PROTOCOL(2) /*!< AC97 */ + +/* SAI operating mode */ +#define CFG0_OPERATING(regval) (BITS(0,1)&((uint32_t)(regval) << 0U)) +#define SAI_MASTER_TRANSMITTER CFG0_OPERATING(0) /*!< master transmitter */ +#define SAI_MASTER_RECEIVER CFG0_OPERATING(1) /*!< master receiver */ +#define SAI_SLAVE_TRANSMITTER CFG0_OPERATING(2) /*!< slave transmitter */ +#define SAI_SLAVE_RECEIVER CFG0_OPERATING(3) /*!< slave receiver */ + +/* SAI compander mode */ +#define CFG1_COMPANDER(regval) (BITS(14,15)&((uint32_t)(regval) << 14U)) +#define SAI_COMPANDER_OFF CFG1_COMPANDER(0) /*!< no compansion applies */ +#define SAI_COMPANDER_ULAW CFG1_COMPANDER(2) /*!< u-law algorithm */ +#define SAI_COMPANDER_ALAW CFG1_COMPANDER(3) /*!< A-law algorithm */ + +/* SAI complement mode */ +#define SAI_COMPLEMENT_1S ((uint32_t)0x00000000U) /*!< data represented in 1's complement form */ +#define SAI_COMPLEMENT_2S SAI_CFG1_CPLMOD /*!< data represented in 2's complement form */ + +/* SAI mute value */ +#define SAI_MUTESENT_0 ((uint32_t)0x00000000U) /*!< 0 is sent via the serial data line when mute is on */ +#define SAI_MUTESENT_LASTFREAM SAI_CFG1_MTVAL /*!< if SLOTNB is less or equals to two, last frame is sent via the serial data line */ + +/* SAI mute on */ +#define SAI_MUTE_OFF ((uint32_t)0x00000000U) /*!< mute mode off */ +#define SAI_MUTE_ON SAI_CFG1_MT /*!< mute mode on */ + +/* SAI serial data line output management */ +#define SAI_SDLINE_DRIVE ((uint32_t)0x00000000U) /*!< SD line output is driven entirely during the audio frame */ +#define SAI_SDLINE_RELEASE SAI_CFG1_SDOM /*!< SD line output is released near inactive slots */ + +/* SAI FIFO threshold */ +#define CFG1_FFTH(regval) (BITS(0,2)&((uint32_t)(regval) << 0U)) +#define SAI_FIFOTH_EMPTY CFG1_FFTH(0) /*!< FIFO threshold empty */ +#define SAI_FIFOTH_QUARTER CFG1_FFTH(1) /*!< FIFO threshold quarter full */ +#define SAI_FIFOTH_HALF CFG1_FFTH(2) /*!< FIFO threshold half full */ +#define SAI_FIFOTH_THREE_QUARTER CFG1_FFTH(3) /*!< FIFO threshold three quarter full */ +#define SAI_FIFOTH_FULL CFG1_FFTH(4) /*!< FIFO threshold full */ + +/* SAI frame synchronization offset */ +#define SAI_FS_OFFSET_BEGINNING ((uint32_t)0x00000000U) /*!< FS active edge asserted at the beginning of the first bit of the first slot */ +#define SAI_FS_OFFSET_ONEBITBEFORE SAI_FCFG_FSOST /*!< FS active edge asserted one bit cycle before normal FS when FSOST is 0 */ + +/* SAI frame synchronization active polarity */ +#define SAI_FS_POLARITY_LOW ((uint32_t)0x00000000U) /*!< FS low active polarity */ +#define SAI_FS_POLARITY_HIGH SAI_FCFG_FSPL /*!< FS high active polarity */ + +/* SAI frame synchronization function */ +#define SAI_FS_FUNC_START ((uint32_t)0x00000000U) /*!< FS only defines frame start */ +#define SAI_FS_FUNC_START_CHANNEL SAI_FCFG_FSFUNC /*!< FS define both frame start and channel number */ + +/* SAI slot active */ +#define SAI_SLOT_ACTIVE_NONE ((uint32_t)0x00000000U) /*!< all slot inactive */ +#define SAI_SLOT_ACTIVE_0 BIT(16) /*!< slot 0 active */ +#define SAI_SLOT_ACTIVE_1 BIT(17) /*!< slot 1 active */ +#define SAI_SLOT_ACTIVE_2 BIT(18) /*!< slot 2 active */ +#define SAI_SLOT_ACTIVE_3 BIT(19) /*!< slot 3 active */ +#define SAI_SLOT_ACTIVE_4 BIT(20) /*!< slot 4 active */ +#define SAI_SLOT_ACTIVE_5 BIT(21) /*!< slot 5 active */ +#define SAI_SLOT_ACTIVE_6 BIT(22) /*!< slot 6 active */ +#define SAI_SLOT_ACTIVE_7 BIT(23) /*!< slot 7 active */ +#define SAI_SLOT_ACTIVE_8 BIT(24) /*!< slot 8 active */ +#define SAI_SLOT_ACTIVE_9 BIT(25) /*!< slot 9 active */ +#define SAI_SLOT_ACTIVE_10 BIT(26) /*!< slot 10 active */ +#define SAI_SLOT_ACTIVE_11 BIT(27) /*!< slot 11 active */ +#define SAI_SLOT_ACTIVE_12 BIT(28) /*!< slot 12 active */ +#define SAI_SLOT_ACTIVE_13 BIT(29) /*!< slot 13 active */ +#define SAI_SLOT_ACTIVE_14 BIT(30) /*!< slot 14 active */ +#define SAI_SLOT_ACTIVE_15 BIT(31) /*!< slot 15 active */ +#define SAI_SLOT_ACTIVE_ALL BITS(16,31) /*!< slot all active */ + +/* SAI slot width definitions */ +#define SCFG_SW(regval) (BITS(6,7)&((uint32_t)(regval) << 6U)) +#define SAI_SLOT_WIDTH_DATA SCFG_SW(0) /*!< slot width equals data width */ +#define SAI_SLOT_WIDTH_16BIT SCFG_SW(1) /*!< slot width of 16-bits */ +#define SAI_SLOT_WIDTH_32BIT SCFG_SW(2) /*!< slot width of 32-bits */ + +/* SAI interrupt enable or disable */ +#define SAI_INT_OUERR SAI_INTEN_OUERRIE /*!< FIFO overrun or underrun interrupt enable */ +#define SAI_INT_MTDET SAI_INTEN_MTDETIE /*!< mute detection interrupt enable */ +#define SAI_INT_ERRCK SAI_INTEN_ERRCKIE /*!< error clock interrupt enable */ +#define SAI_INT_FFREQ SAI_INTEN_FFREQIE /*!< FIFO request interrupt enable */ +#define SAI_INT_ACNRDY SAI_INTEN_ACNRDYIE /*!< audio codec not ready interrupt enable */ +#define SAI_INT_FSADET SAI_INTEN_FSADETIE /*!< frame synchronization advanced detection interrupt enable */ +#define SAI_INT_FSPDET SAI_INTEN_FSPDETIE /*!< frame synchronization postpone detection interrupt enable */ + +/* SAI flags */ +#define SAI_FLAG_OUERR SAI_STAT_OUERR /*!< FIFO overrun or underrun flag */ +#define SAI_FLAG_MTDET SAI_STAT_MTDET /*!< mute detection flag */ +#define SAI_FLAG_ERRCK SAI_STAT_ERRCK /*!< error clock flag */ +#define SAI_FLAG_FFREQ SAI_STAT_FFREQ /*!< FIFO request flag */ +#define SAI_FLAG_ACNRDY SAI_STAT_ACNRDY /*!< audio codec not ready flag */ +#define SAI_FLAG_FSADET SAI_STAT_FSADET /*!< frame synchronization advanced detection flag */ +#define SAI_FLAG_FSPDET SAI_STAT_FSPDET /*!< frame synchronization postpone detection flag */ + +/* SAI FIFO status */ +#define STAT_FFSTAT(regval) (BITS(16,18)&((uint32_t)(regval) << 16U)) +#define SAI_FIFO_STAT_EMPTY STAT_FFSTAT(0) /*!< FIFO status empty */ +#define SAI_FIFO_STAT_QUARTER STAT_FFSTAT(1) /*!< receiver: empty < FIFO <= 1/4, transmitter: empty < FIFO < 1/4 */ +#define SAI_FIFO_STAT_HALF STAT_FFSTAT(2) /*!< receiver: 1/4 < FIFO <= 1/2, transmitter: 1/4 <= FIFO < 1/2 */ +#define SAI_FIFO_STAT_THREE_QUARTER STAT_FFSTAT(3) /*!< receiver: 1/2 < FIFO <= 3/4, transmitter: 1/2 <= FIFO < 3/4 */ +#define SAI_FIFO_STAT_NEARFULL STAT_FFSTAT(4) /*!< receiver: 3/4 < FIFO < full, transmitter: 3/4 <= FIFO < full */ +#define SAI_FIFO_STAT_FULL STAT_FFSTAT(5) /*!< FIFO status full */ + +#define SAI_BLOCK0 ((uint32_t)0x00000000U) /*!< Block 0 */ +#define SAI_BLOCK1 ((uint32_t)0x00000001U) /*!< Block 1 */ + +/* function declarations */ +/* SAI deinitialization and initialization functions */ +/* reset SAI */ +void sai_deinit(void); + +/* initialize SAI parameter struct with the default values */ +void sai_struct_para_init(sai_parameter_struct *sai_init_stuct); +/* initialize SAI frame parameter struct with the default values */ +void sai_frame_struct_para_init(sai_frame_parameter_struct *sai_frame_init_struct); +/* initialize SAI slot parameter struct with the default values */ +void sai_slot_struct_para_init(sai_slot_parameter_struct *sai_slot_init_struct); + +/* initialize SAI */ +void sai_init(uint32_t block, sai_parameter_struct *sai_struct); +/* initialize SAI frame */ +void sai_frame_init(uint32_t block, sai_frame_parameter_struct *sai_frame_struct); +/* initialize SAI slot */ +void sai_slot_init(uint32_t block, sai_slot_parameter_struct *sai_slot_struct); + +/* sai enable*/ +void sai_enable(uint32_t block); +/* sai disable*/ +void sai_disable(uint32_t block); + +/* SAI configuration functions */ +/* SAI serial data near inactive slot output management */ +void sai_sdoutput_config(uint32_t block, uint32_t sdout); +/* configure SAI mono mode */ +void sai_monomode_config(uint32_t block, uint32_t mono); +/* configure SAI companding mode */ +void sai_companding_config(uint32_t block, uint32_t compander, uint32_t complement); +/* enable SAI mute detected or mute send */ +void sai_mute_enable(uint32_t block); +/* disable SAI mute detected or mute send */ +void sai_mute_disable(uint32_t block); +/* configure SAI mute value */ +void sai_mute_value_config(uint32_t block, uint32_t value); +/* configure SAI mute frame count */ +void sai_mute_count_config(uint32_t block, uint32_t count); +/* SAI transmit data */ +void sai_data_transmit(uint32_t block, uint32_t data); +/* SAI receive data */ +uint32_t sai_data_receive(uint32_t block); +/* get SAI fifo status */ +sai_fifo_state_enum sai_fifo_status_get(uint32_t block); +/* SAI fifo flush */ +void sai_fifo_flush(uint32_t block); + +/* SAI DMA functions */ +/* enable SAI dma */ +void sai_dma_enable(uint32_t block); +/* disable SAI dma */ +void sai_dma_disable(uint32_t block); + +/* flag and interrupt functions */ +/* enable the SAI interrupt */ +void sai_interrupt_enable(uint32_t block, uint32_t interrupt); +/* disable the SAI interrupt */ +void sai_interrupt_disable(uint32_t block, uint32_t interrupt); +/* get SAI interrupt flag */ +FlagStatus sai_interrupt_flag_get(uint32_t block, uint32_t interrupt); +/* clear SAI interrupt flag */ +void sai_interrupt_flag_clear(uint32_t block, uint32_t interrupt); +/* get SAI flag */ +FlagStatus sai_flag_get(uint32_t block, uint32_t flag); +/* clear SAI flag */ +void sai_flag_clear(uint32_t block, uint32_t flag); + +#endif /* GD32F5XX_SAI_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_sdio.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_sdio.h new file mode 100644 index 0000000..bcb0d50 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_sdio.h @@ -0,0 +1,431 @@ +/*! + \file gd32f5xx_sdio.h + \brief definitions for the SDIO + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_SDIO_H +#define GD32F5XX_SDIO_H + +#include "gd32f5xx.h" + +/* SDIO definitions */ +#define SDIO SDIO_BASE + +/* registers definitions */ +#define SDIO_PWRCTL REG32(SDIO + 0x00000000U) /*!< SDIO power control register */ +#define SDIO_CLKCTL REG32(SDIO + 0x00000004U) /*!< SDIO clock control register */ +#define SDIO_CMDAGMT REG32(SDIO + 0x00000008U) /*!< SDIO command argument register */ +#define SDIO_CMDCTL REG32(SDIO + 0x0000000CU) /*!< SDIO command control register */ +#define SDIO_RSPCMDIDX REG32(SDIO + 0x00000010U) /*!< SDIO command index response register */ +#define SDIO_RESP0 REG32(SDIO + 0x00000014U) /*!< SDIO response register 0 */ +#define SDIO_RESP1 REG32(SDIO + 0x00000018U) /*!< SDIO response register 1 */ +#define SDIO_RESP2 REG32(SDIO + 0x0000001CU) /*!< SDIO response register 2 */ +#define SDIO_RESP3 REG32(SDIO + 0x00000020U) /*!< SDIO response register 3 */ +#define SDIO_DATATO REG32(SDIO + 0x00000024U) /*!< SDIO data timeout register */ +#define SDIO_DATALEN REG32(SDIO + 0x00000028U) /*!< SDIO data length register */ +#define SDIO_DATACTL REG32(SDIO + 0x0000002CU) /*!< SDIO data control register */ +#define SDIO_DATACNT REG32(SDIO + 0x00000030U) /*!< SDIO data counter register */ +#define SDIO_STAT REG32(SDIO + 0x00000034U) /*!< SDIO status register */ +#define SDIO_INTC REG32(SDIO + 0x00000038U) /*!< SDIO interrupt clear register */ +#define SDIO_INTEN REG32(SDIO + 0x0000003CU) /*!< SDIO interrupt enable register */ +#define SDIO_FIFOCNT REG32(SDIO + 0x00000048U) /*!< SDIO FIFO counter register */ +#define SDIO_FIFO REG32(SDIO + 0x00000080U) /*!< SDIO FIFO data register */ + +/* bits definitions */ +/* SDIO_PWRCTL */ +#define SDIO_PWRCTL_PWRCTL BITS(0,1) /*!< SDIO power control bits */ + +/* SDIO_CLKCTL */ +#define SDIO_CLKCTL_DIV BITS(0,7) /*!< clock division */ +#define SDIO_CLKCTL_CLKEN BIT(8) /*!< SDIO_CLK clock output enable bit */ +#define SDIO_CLKCTL_CLKPWRSAV BIT(9) /*!< SDIO_CLK clock dynamic switch on/off for power saving */ +#define SDIO_CLKCTL_CLKBYP BIT(10) /*!< clock bypass enable bit */ +#define SDIO_CLKCTL_BUSMODE BITS(11,12) /*!< SDIO card bus mode control bit */ +#define SDIO_CLKCTL_CLKEDGE BIT(13) /*!< SDIO_CLK clock edge selection bit */ +#define SDIO_CLKCTL_HWCLKEN BIT(14) /*!< hardware clock control enable bit */ +#define SDIO_CLKCTL_DIV8 BIT(31) /*!< MSB of clock division */ + +/* SDIO_CMDAGMT */ +#define SDIO_CMDAGMT_CMDAGMT BITS(0,31) /*!< SDIO card command argument */ + +/* SDIO_CMDCTL */ +#define SDIO_CMDCTL_CMDIDX BITS(0,5) /*!< command index */ +#define SDIO_CMDCTL_CMDRESP BITS(6,7) /*!< command response type bits */ +#define SDIO_CMDCTL_INTWAIT BIT(8) /*!< interrupt wait instead of timeout */ +#define SDIO_CMDCTL_WAITDEND BIT(9) /*!< wait for ends of data transfer */ +#define SDIO_CMDCTL_CSMEN BIT(10) /*!< command state machine(CSM) enable bit */ +#define SDIO_CMDCTL_SUSPEND BIT(11) /*!< SD I/O suspend command(SD I/O only) */ +#define SDIO_CMDCTL_ENCMDC BIT(12) /*!< CMD completion signal enabled (CE-ATA only) */ +#define SDIO_CMDCTL_NINTEN BIT(13) /*!< no CE-ATA interrupt (CE-ATA only) */ +#define SDIO_CMDCTL_ATAEN BIT(14) /*!< CE-ATA command enable(CE-ATA only) */ + +/* SDIO_DATATO */ +#define SDIO_DATATO_DATATO BITS(0,31) /*!< data timeout period */ + +/* SDIO_DATALEN */ +#define SDIO_DATALEN_DATALEN BITS(0,24) /*!< data transfer length */ + +/* SDIO_DATACTL */ +#define SDIO_DATACTL_DATAEN BIT(0) /*!< data transfer enabled bit */ +#define SDIO_DATACTL_DATADIR BIT(1) /*!< data transfer direction */ +#define SDIO_DATACTL_TRANSMOD BIT(2) /*!< data transfer mode */ +#define SDIO_DATACTL_DMAEN BIT(3) /*!< DMA enable bit */ +#define SDIO_DATACTL_BLKSZ BITS(4,7) /*!< data block size */ +#define SDIO_DATACTL_RWEN BIT(8) /*!< read wait mode enabled(SD I/O only) */ +#define SDIO_DATACTL_RWSTOP BIT(9) /*!< read wait stop(SD I/O only) */ +#define SDIO_DATACTL_RWTYPE BIT(10) /*!< read wait type(SD I/O only) */ +#define SDIO_DATACTL_IOEN BIT(11) /*!< SD I/O specific function enable(SD I/O only) */ + +/* SDIO_STAT */ +#define SDIO_STAT_CCRCERR BIT(0) /*!< command response received (CRC check failed) */ +#define SDIO_STAT_DTCRCERR BIT(1) /*!< data block sent/received (CRC check failed) */ +#define SDIO_STAT_CMDTMOUT BIT(2) /*!< command response timeout */ +#define SDIO_STAT_DTTMOUT BIT(3) /*!< data timeout */ +#define SDIO_STAT_TXURE BIT(4) /*!< transmit FIFO underrun error occurs */ +#define SDIO_STAT_RXORE BIT(5) /*!< received FIFO overrun error occurs */ +#define SDIO_STAT_CMDRECV BIT(6) /*!< command response received (CRC check passed) */ +#define SDIO_STAT_CMDSEND BIT(7) /*!< command sent (no response required) */ +#define SDIO_STAT_DTEND BIT(8) /*!< data end (data counter, SDIO_DATACNT, is zero) */ +#define SDIO_STAT_STBITE BIT(9) /*!< start bit error in the bus */ +#define SDIO_STAT_DTBLKEND BIT(10) /*!< data block sent/received (CRC check passed) */ +#define SDIO_STAT_CMDRUN BIT(11) /*!< command transmission in progress */ +#define SDIO_STAT_TXRUN BIT(12) /*!< data transmission in progress */ +#define SDIO_STAT_RXRUN BIT(13) /*!< data reception in progress */ +#define SDIO_STAT_TFH BIT(14) /*!< transmit FIFO is half empty: at least 8 words can be written into the FIFO */ +#define SDIO_STAT_RFH BIT(15) /*!< receive FIFO is half full: at least 8 words can be read in the FIFO */ +#define SDIO_STAT_TFF BIT(16) /*!< transmit FIFO is full */ +#define SDIO_STAT_RFF BIT(17) /*!< receive FIFO is full */ +#define SDIO_STAT_TFE BIT(18) /*!< transmit FIFO is empty */ +#define SDIO_STAT_RFE BIT(19) /*!< receive FIFO is empty */ +#define SDIO_STAT_TXDTVAL BIT(20) /*!< data is valid in transmit FIFO */ +#define SDIO_STAT_RXDTVAL BIT(21) /*!< data is valid in receive FIFO */ +#define SDIO_STAT_SDIOINT BIT(22) /*!< SD I/O interrupt received */ +#define SDIO_STAT_ATAEND BIT(23) /*!< CE-ATA command completion signal received (only for CMD61) */ + +/* SDIO_INTC */ +#define SDIO_INTC_CCRCERRC BIT(0) /*!< CCRCERR flag clear bit */ +#define SDIO_INTC_DTCRCERRC BIT(1) /*!< DTCRCERR flag clear bit */ +#define SDIO_INTC_CMDTMOUTC BIT(2) /*!< CMDTMOUT flag clear bit */ +#define SDIO_INTC_DTTMOUTC BIT(3) /*!< DTTMOUT flag clear bit */ +#define SDIO_INTC_TXUREC BIT(4) /*!< TXURE flag clear bit */ +#define SDIO_INTC_RXOREC BIT(5) /*!< RXORE flag clear bit */ +#define SDIO_INTC_CMDRECVC BIT(6) /*!< CMDRECV flag clear bit */ +#define SDIO_INTC_CMDSENDC BIT(7) /*!< CMDSEND flag clear bit */ +#define SDIO_INTC_DTENDC BIT(8) /*!< DTEND flag clear bit */ +#define SDIO_INTC_STBITEC BIT(9) /*!< STBITE flag clear bit */ +#define SDIO_INTC_DTBLKENDC BIT(10) /*!< DTBLKEND flag clear bit */ +#define SDIO_INTC_SDIOINTC BIT(22) /*!< SDIOINT flag clear bit */ +#define SDIO_INTC_ATAENDC BIT(23) /*!< ATAEND flag clear bit */ + +/* SDIO_INTEN */ +#define SDIO_INTEN_CCRCERRIE BIT(0) /*!< command response CRC fail interrupt enable */ +#define SDIO_INTEN_DTCRCERRIE BIT(1) /*!< data CRC fail interrupt enable */ +#define SDIO_INTEN_CMDTMOUTIE BIT(2) /*!< command response timeout interrupt enable */ +#define SDIO_INTEN_DTTMOUTIE BIT(3) /*!< data timeout interrupt enable */ +#define SDIO_INTEN_TXUREIE BIT(4) /*!< transmit FIFO underrun error interrupt enable */ +#define SDIO_INTEN_RXOREIE BIT(5) /*!< received FIFO overrun error interrupt enable */ +#define SDIO_INTEN_CMDRECVIE BIT(6) /*!< command response received interrupt enable */ +#define SDIO_INTEN_CMDSENDIE BIT(7) /*!< command sent interrupt enable */ +#define SDIO_INTEN_DTENDIE BIT(8) /*!< data end interrupt enable */ +#define SDIO_INTEN_STBITEIE BIT(9) /*!< start bit error interrupt enable */ +#define SDIO_INTEN_DTBLKENDIE BIT(10) /*!< data block end interrupt enable */ +#define SDIO_INTEN_CMDRUNIE BIT(11) /*!< command transmission interrupt enable */ +#define SDIO_INTEN_TXRUNIE BIT(12) /*!< data transmission interrupt enable */ +#define SDIO_INTEN_RXRUNIE BIT(13) /*!< data reception interrupt enable */ +#define SDIO_INTEN_TFHIE BIT(14) /*!< transmit FIFO half empty interrupt enable */ +#define SDIO_INTEN_RFHIE BIT(15) /*!< receive FIFO half full interrupt enable */ +#define SDIO_INTEN_TFFIE BIT(16) /*!< transmit FIFO full interrupt enable */ +#define SDIO_INTEN_RFFIE BIT(17) /*!< receive FIFO full interrupt enable */ +#define SDIO_INTEN_TFEIE BIT(18) /*!< transmit FIFO empty interrupt enable */ +#define SDIO_INTEN_RFEIE BIT(19) /*!< receive FIFO empty interrupt enable */ +#define SDIO_INTEN_TXDTVALIE BIT(20) /*!< data valid in transmit FIFO interrupt enable */ +#define SDIO_INTEN_RXDTVALIE BIT(21) /*!< data valid in receive FIFO interrupt enable */ +#define SDIO_INTEN_SDIOINTIE BIT(22) /*!< SD I/O interrupt received interrupt enable */ +#define SDIO_INTEN_ATAENDIE BIT(23) /*!< CE-ATA command completion signal received interrupt enable */ + +/* SDIO_FIFO */ +#define SDIO_FIFO_FIFODT BITS(0,31) /*!< receive FIFO data or transmit FIFO data */ + +/* constants definitions */ +/* SDIO flags */ +#define SDIO_FLAG_CCRCERR BIT(0) /*!< command response received (CRC check failed) flag */ +#define SDIO_FLAG_DTCRCERR BIT(1) /*!< data block sent/received (CRC check failed) flag */ +#define SDIO_FLAG_CMDTMOUT BIT(2) /*!< command response timeout flag */ +#define SDIO_FLAG_DTTMOUT BIT(3) /*!< data timeout flag */ +#define SDIO_FLAG_TXURE BIT(4) /*!< transmit FIFO underrun error occurs flag */ +#define SDIO_FLAG_RXORE BIT(5) /*!< received FIFO overrun error occurs flag */ +#define SDIO_FLAG_CMDRECV BIT(6) /*!< command response received (CRC check passed) flag */ +#define SDIO_FLAG_CMDSEND BIT(7) /*!< command sent (no response required) flag */ +#define SDIO_FLAG_DTEND BIT(8) /*!< data end (data counter, SDIO_DATACNT, is zero) flag */ +#define SDIO_FLAG_STBITE BIT(9) /*!< start bit error in the bus flag */ +#define SDIO_FLAG_DTBLKEND BIT(10) /*!< data block sent/received (CRC check passed) flag */ +#define SDIO_FLAG_CMDRUN BIT(11) /*!< command transmission in progress flag */ +#define SDIO_FLAG_TXRUN BIT(12) /*!< data transmission in progress flag */ +#define SDIO_FLAG_RXRUN BIT(13) /*!< data reception in progress flag */ +#define SDIO_FLAG_TFH BIT(14) /*!< transmit FIFO is half empty flag: at least 8 words can be written into the FIFO */ +#define SDIO_FLAG_RFH BIT(15) /*!< receive FIFO is half full flag: at least 8 words can be read in the FIFO */ +#define SDIO_FLAG_TFF BIT(16) /*!< transmit FIFO is full flag */ +#define SDIO_FLAG_RFF BIT(17) /*!< receive FIFO is full flag */ +#define SDIO_FLAG_TFE BIT(18) /*!< transmit FIFO is empty flag */ +#define SDIO_FLAG_RFE BIT(19) /*!< receive FIFO is empty flag */ +#define SDIO_FLAG_TXDTVAL BIT(20) /*!< data is valid in transmit FIFO flag */ +#define SDIO_FLAG_RXDTVAL BIT(21) /*!< data is valid in receive FIFO flag */ +#define SDIO_FLAG_SDIOINT BIT(22) /*!< SD I/O interrupt received flag */ +#define SDIO_FLAG_ATAEND BIT(23) /*!< CE-ATA command completion signal received (only for CMD61) flag */ + +/* SDIO interrupt enable or disable */ +#define SDIO_INT_CCRCERR BIT(0) /*!< SDIO CCRCERR interrupt */ +#define SDIO_INT_DTCRCERR BIT(1) /*!< SDIO DTCRCERR interrupt */ +#define SDIO_INT_CMDTMOUT BIT(2) /*!< SDIO CMDTMOUT interrupt */ +#define SDIO_INT_DTTMOUT BIT(3) /*!< SDIO DTTMOUT interrupt */ +#define SDIO_INT_TXURE BIT(4) /*!< SDIO TXURE interrupt */ +#define SDIO_INT_RXORE BIT(5) /*!< SDIO RXORE interrupt */ +#define SDIO_INT_CMDRECV BIT(6) /*!< SDIO CMDRECV interrupt */ +#define SDIO_INT_CMDSEND BIT(7) /*!< SDIO CMDSEND interrupt */ +#define SDIO_INT_DTEND BIT(8) /*!< SDIO DTEND interrupt */ +#define SDIO_INT_STBITE BIT(9) /*!< SDIO STBITE interrupt */ +#define SDIO_INT_DTBLKEND BIT(10) /*!< SDIO DTBLKEND interrupt */ +#define SDIO_INT_CMDRUN BIT(11) /*!< SDIO CMDRUN interrupt */ +#define SDIO_INT_TXRUN BIT(12) /*!< SDIO TXRUN interrupt */ +#define SDIO_INT_RXRUN BIT(13) /*!< SDIO RXRUN interrupt */ +#define SDIO_INT_TFH BIT(14) /*!< SDIO TFH interrupt */ +#define SDIO_INT_RFH BIT(15) /*!< SDIO RFH interrupt */ +#define SDIO_INT_TFF BIT(16) /*!< SDIO TFF interrupt */ +#define SDIO_INT_RFF BIT(17) /*!< SDIO RFF interrupt */ +#define SDIO_INT_TFE BIT(18) /*!< SDIO TFE interrupt */ +#define SDIO_INT_RFE BIT(19) /*!< SDIO RFE interrupt */ +#define SDIO_INT_TXDTVAL BIT(20) /*!< SDIO TXDTVAL interrupt */ +#define SDIO_INT_RXDTVAL BIT(21) /*!< SDIO RXDTVAL interrupt */ +#define SDIO_INT_SDIOINT BIT(22) /*!< SDIO SDIOINT interrupt */ +#define SDIO_INT_ATAEND BIT(23) /*!< SDIO ATAEND interrupt */ + +/* SDIO interrupt flags */ +#define SDIO_INT_FLAG_CCRCERR BIT(0) /*!< SDIO CCRCERR interrupt flag */ +#define SDIO_INT_FLAG_DTCRCERR BIT(1) /*!< SDIO DTCRCERR interrupt flag */ +#define SDIO_INT_FLAG_CMDTMOUT BIT(2) /*!< SDIO CMDTMOUT interrupt flag */ +#define SDIO_INT_FLAG_DTTMOUT BIT(3) /*!< SDIO DTTMOUT interrupt flag */ +#define SDIO_INT_FLAG_TXURE BIT(4) /*!< SDIO TXURE interrupt flag */ +#define SDIO_INT_FLAG_RXORE BIT(5) /*!< SDIO RXORE interrupt flag */ +#define SDIO_INT_FLAG_CMDRECV BIT(6) /*!< SDIO CMDRECV interrupt flag */ +#define SDIO_INT_FLAG_CMDSEND BIT(7) /*!< SDIO CMDSEND interrupt flag */ +#define SDIO_INT_FLAG_DTEND BIT(8) /*!< SDIO DTEND interrupt flag */ +#define SDIO_INT_FLAG_STBITE BIT(9) /*!< SDIO STBITE interrupt flag */ +#define SDIO_INT_FLAG_DTBLKEND BIT(10) /*!< SDIO DTBLKEND interrupt flag */ +#define SDIO_INT_FLAG_CMDRUN BIT(11) /*!< SDIO CMDRUN interrupt flag */ +#define SDIO_INT_FLAG_TXRUN BIT(12) /*!< SDIO TXRUN interrupt flag */ +#define SDIO_INT_FLAG_RXRUN BIT(13) /*!< SDIO RXRUN interrupt flag */ +#define SDIO_INT_FLAG_TFH BIT(14) /*!< SDIO TFH interrupt flag */ +#define SDIO_INT_FLAG_RFH BIT(15) /*!< SDIO RFH interrupt flag */ +#define SDIO_INT_FLAG_TFF BIT(16) /*!< SDIO TFF interrupt flag */ +#define SDIO_INT_FLAG_RFF BIT(17) /*!< SDIO RFF interrupt flag */ +#define SDIO_INT_FLAG_TFE BIT(18) /*!< SDIO TFE interrupt flag */ +#define SDIO_INT_FLAG_RFE BIT(19) /*!< SDIO RFE interrupt flag */ +#define SDIO_INT_FLAG_TXDTVAL BIT(20) /*!< SDIO TXDTVAL interrupt flag */ +#define SDIO_INT_FLAG_RXDTVAL BIT(21) /*!< SDIO RXDTVAL interrupt flag */ +#define SDIO_INT_FLAG_SDIOINT BIT(22) /*!< SDIO SDIOINT interrupt flag */ +#define SDIO_INT_FLAG_ATAEND BIT(23) /*!< SDIO ATAEND interrupt flag */ + +/* SDIO power control */ +#define PWRCTL_PWRCTL(regval) (BITS(0,1) & ((uint32_t)(regval) << 0)) +#define SDIO_POWER_OFF PWRCTL_PWRCTL(0) /*!< SDIO power off */ +#define SDIO_POWER_ON PWRCTL_PWRCTL(3) /*!< SDIO power on */ + +/* SDIO card bus mode control */ +#define CLKCTL_BUSMODE(regval) (BITS(11,12) & ((uint32_t)(regval) << 11)) +#define SDIO_BUSMODE_1BIT CLKCTL_BUSMODE(0) /*!< 1-bit SDIO card bus mode */ +#define SDIO_BUSMODE_4BIT CLKCTL_BUSMODE(1) /*!< 4-bit SDIO card bus mode */ +#define SDIO_BUSMODE_8BIT CLKCTL_BUSMODE(2) /*!< 8-bit SDIO card bus mode */ + +/* SDIO_CLK clock edge selection */ +#define SDIO_SDIOCLKEDGE_RISING (uint32_t)0x00000000U /*!< select the rising edge of the SDIOCLK to generate SDIO_CLK */ +#define SDIO_SDIOCLKEDGE_FALLING SDIO_CLKCTL_CLKEDGE /*!< select the falling edge of the SDIOCLK to generate SDIO_CLK */ + +/* clock bypass enable or disable */ +#define SDIO_CLOCKBYPASS_DISABLE (uint32_t)0x00000000U /*!< no bypass */ +#define SDIO_CLOCKBYPASS_ENABLE SDIO_CLKCTL_CLKBYP /*!< clock bypass */ + +/* SDIO_CLK clock dynamic switch on/off for power saving */ +#define SDIO_CLOCKPWRSAVE_DISABLE (uint32_t)0x00000000U /*!< SDIO_CLK clock is always on */ +#define SDIO_CLOCKPWRSAVE_ENABLE SDIO_CLKCTL_CLKPWRSAV /*!< SDIO_CLK closed when bus is idle */ + +/* SDIO command response type */ +#define CMDCTL_CMDRESP(regval) (BITS(6,7) & ((uint32_t)(regval) << 6)) +#define SDIO_RESPONSETYPE_NO CMDCTL_CMDRESP(0) /*!< no response */ +#define SDIO_RESPONSETYPE_SHORT CMDCTL_CMDRESP(1) /*!< short response */ +#define SDIO_RESPONSETYPE_LONG CMDCTL_CMDRESP(3) /*!< long response */ + +/* command state machine wait type */ +#define SDIO_WAITTYPE_NO (uint32_t)0x00000000U /*!< not wait interrupt */ +#define SDIO_WAITTYPE_INTERRUPT SDIO_CMDCTL_INTWAIT /*!< wait interrupt */ +#define SDIO_WAITTYPE_DATAEND SDIO_CMDCTL_WAITDEND /*!< wait the end of data transfer */ + +#define SDIO_RESPONSE0 (uint32_t)0x00000000U /*!< card response[31:0]/card response[127:96] */ +#define SDIO_RESPONSE1 (uint32_t)0x00000001U /*!< card response[95:64] */ +#define SDIO_RESPONSE2 (uint32_t)0x00000002U /*!< card response[63:32] */ +#define SDIO_RESPONSE3 (uint32_t)0x00000003U /*!< card response[31:1], plus bit 0 */ + +/* SDIO data block size */ +#define DATACTL_BLKSZ(regval) (BITS(4,7) & ((uint32_t)(regval) << 4)) +#define SDIO_DATABLOCKSIZE_1BYTE DATACTL_BLKSZ(0) /*!< block size = 1 byte */ +#define SDIO_DATABLOCKSIZE_2BYTES DATACTL_BLKSZ(1) /*!< block size = 2 bytes */ +#define SDIO_DATABLOCKSIZE_4BYTES DATACTL_BLKSZ(2) /*!< block size = 4 bytes */ +#define SDIO_DATABLOCKSIZE_8BYTES DATACTL_BLKSZ(3) /*!< block size = 8 bytes */ +#define SDIO_DATABLOCKSIZE_16BYTES DATACTL_BLKSZ(4) /*!< block size = 16 bytes */ +#define SDIO_DATABLOCKSIZE_32BYTES DATACTL_BLKSZ(5) /*!< block size = 32 bytes */ +#define SDIO_DATABLOCKSIZE_64BYTES DATACTL_BLKSZ(6) /*!< block size = 64 bytes */ +#define SDIO_DATABLOCKSIZE_128BYTES DATACTL_BLKSZ(7) /*!< block size = 128 bytes */ +#define SDIO_DATABLOCKSIZE_256BYTES DATACTL_BLKSZ(8) /*!< block size = 256 bytes */ +#define SDIO_DATABLOCKSIZE_512BYTES DATACTL_BLKSZ(9) /*!< block size = 512 bytes */ +#define SDIO_DATABLOCKSIZE_1024BYTES DATACTL_BLKSZ(10) /*!< block size = 1024 bytes */ +#define SDIO_DATABLOCKSIZE_2048BYTES DATACTL_BLKSZ(11) /*!< block size = 2048 bytes */ +#define SDIO_DATABLOCKSIZE_4096BYTES DATACTL_BLKSZ(12) /*!< block size = 4096 bytes */ +#define SDIO_DATABLOCKSIZE_8192BYTES DATACTL_BLKSZ(13) /*!< block size = 8192 bytes */ +#define SDIO_DATABLOCKSIZE_16384BYTES DATACTL_BLKSZ(14) /*!< block size = 16384 bytes */ + +/* SDIO data transfer mode */ +#define SDIO_TRANSMODE_BLOCK (uint32_t)0x00000000U /*!< block transfer */ +#define SDIO_TRANSMODE_STREAM SDIO_DATACTL_TRANSMOD /*!< stream transfer or SDIO multibyte transfer */ + +/* SDIO data transfer direction */ +#define SDIO_TRANSDIRECTION_TOCARD (uint32_t)0x00000000U /*!< write data to card */ +#define SDIO_TRANSDIRECTION_TOSDIO SDIO_DATACTL_DATADIR /*!< read data from card */ + +/* SDIO read wait type */ +#define SDIO_READWAITTYPE_DAT2 (uint32_t)0x00000000U /*!< read wait control using SDIO_DAT[2] */ +#define SDIO_READWAITTYPE_CLK SDIO_DATACTL_RWTYPE /*!< read wait control by stopping SDIO_CLK */ + +/* function declarations */ +/* de/initialization functions, hardware clock, bus mode, power_state and SDIO clock configuration */ +/* deinitialize the SDIO */ +void sdio_deinit(void); +/* configure the SDIO clock */ +void sdio_clock_config(uint32_t clock_edge, uint32_t clock_bypass, uint32_t clock_powersave, uint16_t clock_division); +/* enable hardware clock control */ +void sdio_hardware_clock_enable(void); +/* disable hardware clock control */ +void sdio_hardware_clock_disable(void); +/* set different SDIO card bus mode */ +void sdio_bus_mode_set(uint32_t bus_mode); +/* set the SDIO power state */ +void sdio_power_state_set(uint32_t power_state); +/* get the SDIO power state */ +uint32_t sdio_power_state_get(void); +/* enable SDIO_CLK clock output */ +void sdio_clock_enable(void); +/* disable SDIO_CLK clock output */ +void sdio_clock_disable(void); + +/* configure the command index, argument, response type, wait type and CSM to send command functions */ +/* configure the command and response */ +void sdio_command_response_config(uint32_t cmd_index, uint32_t cmd_argument, uint32_t response_type); +/* set the command state machine wait type */ +void sdio_wait_type_set(uint32_t wait_type); +/* enable the CSM(command state machine) */ +void sdio_csm_enable(void); +/* disable the CSM(command state machine) */ +void sdio_csm_disable(void); +/* get the last response command index */ +uint8_t sdio_command_index_get(void); +/* get the response for the last received command */ +uint32_t sdio_response_get(uint32_t sdio_responsex); + +/* configure the data timeout, length, block size, transfer mode, direction and DSM for data transfer functions */ +/* configure the data timeout, data length and data block size */ +void sdio_data_config(uint32_t data_timeout, uint32_t data_length, uint32_t data_blocksize); +/* configure the data transfer mode and direction */ +void sdio_data_transfer_config(uint32_t transfer_mode, uint32_t transfer_direction); +/* enable the DSM(data state machine) for data transfer */ +void sdio_dsm_enable(void); +/* disable the DSM(data state machine) */ +void sdio_dsm_disable(void); +/* write data(one word) to the transmit FIFO */ +void sdio_data_write(uint32_t data); +/* read data(one word) from the receive FIFO */ +uint32_t sdio_data_read(void); +/* get the number of remaining data bytes to be transferred to card */ +uint32_t sdio_data_counter_get(void); +/* get the number of words remaining to be written or read from FIFO */ +uint32_t sdio_fifo_counter_get(void); +/* enable the DMA request for SDIO */ +void sdio_dma_enable(void); +/* disable the DMA request for SDIO */ +void sdio_dma_disable(void); + +/* flag and interrupt functions */ +/* get the flags state of SDIO */ +FlagStatus sdio_flag_get(uint32_t flag); +/* clear the pending flags of SDIO */ +void sdio_flag_clear(uint32_t flag); +/* enable the SDIO interrupt */ +void sdio_interrupt_enable(uint32_t int_flag); +/* disable the SDIO interrupt */ +void sdio_interrupt_disable(uint32_t int_flag); +/* get the interrupt flags state of SDIO */ +FlagStatus sdio_interrupt_flag_get(uint32_t int_flag); +/* clear the interrupt pending flags of SDIO */ +void sdio_interrupt_flag_clear(uint32_t int_flag); + +/* SD I/O card functions */ +/* enable the read wait mode(SD I/O only) */ +void sdio_readwait_enable(void); +/* disable the read wait mode(SD I/O only) */ +void sdio_readwait_disable(void); +/* enable the function that stop the read wait process(SD I/O only) */ +void sdio_stop_readwait_enable(void); +/* disable the function that stop the read wait process(SD I/O only) */ +void sdio_stop_readwait_disable(void); +/* set the read wait type(SD I/O only) */ +void sdio_readwait_type_set(uint32_t readwait_type); +/* enable the SD I/O mode specific operation(SD I/O only) */ +void sdio_operation_enable(void); +/* disable the SD I/O mode specific operation(SD I/O only) */ +void sdio_operation_disable(void); +/* enable the SD I/O suspend operation(SD I/O only) */ +void sdio_suspend_enable(void); +/* disable the SD I/O suspend operation(SD I/O only) */ +void sdio_suspend_disable(void); + +/* CE-ATA functions */ +/* enable the CE-ATA command(CE-ATA only) */ +void sdio_ceata_command_enable(void); +/* disable the CE-ATA command(CE-ATA only) */ +void sdio_ceata_command_disable(void); +/* enable the CE-ATA interrupt(CE-ATA only) */ +void sdio_ceata_interrupt_enable(void); +/* disable the CE-ATA interrupt(CE-ATA only) */ +void sdio_ceata_interrupt_disable(void); +/* enable the CE-ATA command completion signal(CE-ATA only) */ +void sdio_ceata_command_completion_enable(void); +/* disable the CE-ATA command completion signal(CE-ATA only) */ +void sdio_ceata_command_completion_disable(void); + +#endif /* GD32F5XX_SDIO_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_spi.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_spi.h new file mode 100644 index 0000000..41f17e7 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_spi.h @@ -0,0 +1,376 @@ +/*! + \file gd32f5xx_spi.h + \brief definitions for the SPI + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_SPI_H +#define GD32F5XX_SPI_H + +#include "gd32f5xx.h" + +/* SPIx(x=0,1,2,3,4,5) definitions */ +#define SPI0 (SPI_BASE + 0x0000F800U) +#define SPI1 SPI_BASE +#define SPI2 (SPI_BASE + 0x00000400U) +#define SPI3 (SPI_BASE + 0x0000FC00U) +#define SPI4 (SPI_BASE + 0x00011800U) +#define SPI5 (SPI_BASE + 0x00011C00U) + +/* I2Sx_ADD(x=1,2) definitions */ +#define I2S1_ADD I2S_ADD_BASE +#define I2S2_ADD (I2S_ADD_BASE + 0x00000C00U) + +/* SPI registers definitions */ +#define SPI_CTL0(spix) REG32((spix) + 0x00U) /*!< SPI control register 0 */ +#define SPI_CTL1(spix) REG32((spix) + 0x04U) /*!< SPI control register 1*/ +#define SPI_STAT(spix) REG32((spix) + 0x08U) /*!< SPI status register */ +#define SPI_DATA(spix) REG32((spix) + 0x0CU) /*!< SPI data register */ +#define SPI_CRCPOLY(spix) REG32((spix) + 0x10U) /*!< SPI CRC polynomial register */ +#define SPI_RCRC(spix) REG32((spix) + 0x14U) /*!< SPI receive CRC register */ +#define SPI_TCRC(spix) REG32((spix) + 0x18U) /*!< SPI transmit CRC register */ +#define SPI_I2SCTL(spix) REG32((spix) + 0x1CU) /*!< SPI I2S control register */ +#define SPI_I2SPSC(spix) REG32((spix) + 0x20U) /*!< SPI I2S clock prescaler register */ +#define SPI_QCTL(spix) REG32((spix) + 0x80U) /*!< SPI quad mode control register */ + +/* I2S_ADD registers definitions */ +#define I2S_ADD_CTL0(i2sx_add) REG32((i2sx_add) + 0x00U) /*!< I2S_ADD control register 0 */ +#define I2S_ADD_CTL1(i2sx_add) REG32((i2sx_add) + 0x04U) /*!< I2S_ADD control register 1*/ +#define I2S_ADD_STAT(i2sx_add) REG32((i2sx_add) + 0x08U) /*!< I2S_ADD status register */ +#define I2S_ADD_DATA(i2sx_add) REG32((i2sx_add) + 0x0CU) /*!< I2S_ADD data register */ +#define I2S_ADD_CRCPOLY(i2sx_add) REG32((i2sx_add) + 0x10U) /*!< I2S_ADD CRC polynomial register */ +#define I2S_ADD_RCRC(i2sx_add) REG32((i2sx_add) + 0x14U) /*!< I2S_ADD receive CRC register */ +#define I2S_ADD_TCRC(i2sx_add) REG32((i2sx_add) + 0x18U) /*!< I2S_ADD transmit CRC register */ +#define I2S_ADD_I2SCTL(i2sx_add) REG32((i2sx_add) + 0x1CU) /*!< I2S_ADD I2S control register */ +#define I2S_ADD_I2SPSC(i2sx_add) REG32((i2sx_add) + 0x20U) /*!< I2S_ADD I2S clock prescaler register */ + +/* bits definitions */ +/* SPI_CTL0 */ +#define SPI_CTL0_CKPH BIT(0) /*!< clock phase selection*/ +#define SPI_CTL0_CKPL BIT(1) /*!< clock polarity selection */ +#define SPI_CTL0_MSTMOD BIT(2) /*!< master mode enable */ +#define SPI_CTL0_PSC BITS(3,5) /*!< master clock prescaler selection */ +#define SPI_CTL0_SPIEN BIT(6) /*!< SPI enable*/ +#define SPI_CTL0_LF BIT(7) /*!< lsb first mode */ +#define SPI_CTL0_SWNSS BIT(8) /*!< nss pin selection in nss software mode */ +#define SPI_CTL0_SWNSSEN BIT(9) /*!< nss software mode selection */ +#define SPI_CTL0_RO BIT(10) /*!< receive only */ +#define SPI_CTL0_FF16 BIT(11) /*!< data frame size */ +#define SPI_CTL0_CRCNT BIT(12) /*!< CRC next transfer */ +#define SPI_CTL0_CRCEN BIT(13) /*!< CRC calculation enable */ +#define SPI_CTL0_BDOEN BIT(14) /*!< bidirectional transmit output enable*/ +#define SPI_CTL0_BDEN BIT(15) /*!< bidirectional enable */ + +/* SPI_CTL1 */ +#define SPI_CTL1_DMAREN BIT(0) /*!< receive buffer dma enable */ +#define SPI_CTL1_DMATEN BIT(1) /*!< transmit buffer dma enable */ +#define SPI_CTL1_NSSDRV BIT(2) /*!< drive nss output */ +#define SPI_CTL1_TMOD BIT(4) /*!< SPI TI mode enable */ +#define SPI_CTL1_ERRIE BIT(5) /*!< errors interrupt enable */ +#define SPI_CTL1_RBNEIE BIT(6) /*!< receive buffer not empty interrupt enable */ +#define SPI_CTL1_TBEIE BIT(7) /*!< transmit buffer empty interrupt enable */ + +/* SPI_STAT */ +#define SPI_STAT_RBNE BIT(0) /*!< receive buffer not empty */ +#define SPI_STAT_TBE BIT(1) /*!< transmit buffer empty */ +#define SPI_STAT_I2SCH BIT(2) /*!< I2S channel side */ +#define SPI_STAT_TXURERR BIT(3) /*!< I2S transmission underrun error bit */ +#define SPI_STAT_CRCERR BIT(4) /*!< SPI CRC error bit */ +#define SPI_STAT_CONFERR BIT(5) /*!< SPI configuration error bit */ +#define SPI_STAT_RXORERR BIT(6) /*!< SPI reception overrun error bit */ +#define SPI_STAT_TRANS BIT(7) /*!< transmitting on-going bit */ +#define SPI_STAT_FERR BIT(8) /*!< format error bit */ + +/* SPI_DATA */ +#define SPI_DATA_DATA BITS(0,15) /*!< data transfer register */ + +/* SPI_CRCPOLY */ +#define SPI_CRCPOLY_CPR BITS(0,15) /*!< CRC polynomial register */ + +/* SPI_RCRC */ +#define SPI_RCRC_RCR BITS(0,15) /*!< RX CRC register */ + +/* SPI_TCRC */ +#define SPI_TCRC_TCR BITS(0,15) /*!< TX CRC register */ + +/* SPI_I2SCTL */ +#define SPI_I2SCTL_CHLEN BIT(0) /*!< channel length */ +#define SPI_I2SCTL_DTLEN BITS(1,2) /*!< data length */ +#define SPI_I2SCTL_CKPL BIT(3) /*!< idle state clock polarity */ +#define SPI_I2SCTL_I2SSTD BITS(4,5) /*!< I2S standard selection */ +#define SPI_I2SCTL_PCMSMOD BIT(7) /*!< PCM frame synchronization mode */ +#define SPI_I2SCTL_I2SOPMOD BITS(8,9) /*!< I2S operation mode */ +#define SPI_I2SCTL_I2SEN BIT(10) /*!< I2S enable */ +#define SPI_I2SCTL_I2SSEL BIT(11) /*!< I2S mode selection */ + +/* SPI_I2S_PSC */ +#define SPI_I2SPSC_DIV BITS(0,7) /*!< dividing factor for the prescaler */ +#define SPI_I2SPSC_OF BIT(8) /*!< odd factor for the prescaler */ +#define SPI_I2SPSC_MCKOEN BIT(9) /*!< I2S MCK output enable */ + +/* SPI_SPI_QCTL(only SPI5) */ +#define SPI_QCTL_QMOD BIT(0) /*!< quad-SPI mode enable */ +#define SPI_QCTL_QRD BIT(1) /*!< quad-SPI mode read select */ +#define SPI_QCTL_IO23_DRV BIT(2) /*!< drive SPI_IO2 and SPI_IO3 enable */ + +/* constants definitions */ +/* SPI and I2S parameter struct definitions */ +typedef struct { + uint32_t device_mode; /*!< SPI master or slave */ + uint32_t trans_mode; /*!< SPI transtype */ + uint32_t frame_size; /*!< SPI frame size */ + uint32_t nss; /*!< SPI nss control by handware or software */ + uint32_t endian; /*!< SPI big endian or little endian */ + uint32_t clock_polarity_phase; /*!< SPI clock phase and polarity */ + uint32_t prescale; /*!< SPI prescale factor */ +} spi_parameter_struct; + +/* SPI mode definitions */ +#define SPI_MASTER (SPI_CTL0_MSTMOD | SPI_CTL0_SWNSS) /*!< SPI as master */ +#define SPI_SLAVE ((uint32_t)0x00000000U) /*!< SPI as slave */ + +/* SPI bidirectional transfer direction */ +#define SPI_BIDIRECTIONAL_TRANSMIT SPI_CTL0_BDOEN /*!< SPI work in transmit-only mode */ +#define SPI_BIDIRECTIONAL_RECEIVE (~SPI_CTL0_BDOEN) /*!< SPI work in receive-only mode */ + +/* SPI transmit type */ +#define SPI_TRANSMODE_FULLDUPLEX ((uint32_t)0x00000000U) /*!< SPI receive and send data at fullduplex communication */ +#define SPI_TRANSMODE_RECEIVEONLY SPI_CTL0_RO /*!< SPI only receive data */ +#define SPI_TRANSMODE_BDRECEIVE SPI_CTL0_BDEN /*!< bidirectional receive data */ +#define SPI_TRANSMODE_BDTRANSMIT (SPI_CTL0_BDEN | SPI_CTL0_BDOEN) /*!< bidirectional transmit data*/ + +/* SPI frame size */ +#define SPI_FRAMESIZE_16BIT SPI_CTL0_FF16 /*!< SPI frame size is 16 bits */ +#define SPI_FRAMESIZE_8BIT ((uint32_t)0x00000000U) /*!< SPI frame size is 8 bits */ + +/* SPI NSS control mode */ +#define SPI_NSS_SOFT SPI_CTL0_SWNSSEN /*!< SPI nss control by sofrware */ +#define SPI_NSS_HARD ((uint32_t)0x00000000U) /*!< SPI nss control by hardware */ + +/* SPI transmit way */ +#define SPI_ENDIAN_MSB ((uint32_t)0x00000000U) /*!< SPI transmit way is big endian: transmit MSB first */ +#define SPI_ENDIAN_LSB SPI_CTL0_LF /*!< SPI transmit way is little endian: transmit LSB first */ + +/* SPI clock polarity and phase */ +#define SPI_CK_PL_LOW_PH_1EDGE ((uint32_t)0x00000000U) /*!< SPI clock polarity is low level and phase is first edge */ +#define SPI_CK_PL_HIGH_PH_1EDGE SPI_CTL0_CKPL /*!< SPI clock polarity is high level and phase is first edge */ +#define SPI_CK_PL_LOW_PH_2EDGE SPI_CTL0_CKPH /*!< SPI clock polarity is low level and phase is second edge */ +#define SPI_CK_PL_HIGH_PH_2EDGE (SPI_CTL0_CKPL|SPI_CTL0_CKPH) /*!< SPI clock polarity is high level and phase is second edge */ + +/* SPI clock prescale factor */ +#define CTL0_PSC(regval) (BITS(3,5)&((uint32_t)(regval)<<3)) +#define SPI_PSC_2 CTL0_PSC(0) /*!< SPI clock prescale factor is 2 */ +#define SPI_PSC_4 CTL0_PSC(1) /*!< SPI clock prescale factor is 4 */ +#define SPI_PSC_8 CTL0_PSC(2) /*!< SPI clock prescale factor is 8 */ +#define SPI_PSC_16 CTL0_PSC(3) /*!< SPI clock prescale factor is 16 */ +#define SPI_PSC_32 CTL0_PSC(4) /*!< SPI clock prescale factor is 32 */ +#define SPI_PSC_64 CTL0_PSC(5) /*!< SPI clock prescale factor is 64 */ +#define SPI_PSC_128 CTL0_PSC(6) /*!< SPI clock prescale factor is 128 */ +#define SPI_PSC_256 CTL0_PSC(7) /*!< SPI clock prescale factor is 256 */ + +/* I2S audio sample rate */ +#define I2S_AUDIOSAMPLE_8K ((uint32_t)8000U) /*!< I2S audio sample rate is 8KHz */ +#define I2S_AUDIOSAMPLE_11K ((uint32_t)11025U) /*!< I2S audio sample rate is 11KHz */ +#define I2S_AUDIOSAMPLE_16K ((uint32_t)16000U) /*!< I2S audio sample rate is 16KHz */ +#define I2S_AUDIOSAMPLE_22K ((uint32_t)22050U) /*!< I2S audio sample rate is 22KHz */ +#define I2S_AUDIOSAMPLE_32K ((uint32_t)32000U) /*!< I2S audio sample rate is 32KHz */ +#define I2S_AUDIOSAMPLE_44K ((uint32_t)44100U) /*!< I2S audio sample rate is 44KHz */ +#define I2S_AUDIOSAMPLE_48K ((uint32_t)48000U) /*!< I2S audio sample rate is 48KHz */ +#define I2S_AUDIOSAMPLE_96K ((uint32_t)96000U) /*!< I2S audio sample rate is 96KHz */ +#define I2S_AUDIOSAMPLE_192K ((uint32_t)192000U) /*!< I2S audio sample rate is 192KHz */ + +/* I2S frame format */ +#define I2SCTL_DTLEN(regval) (BITS(1,2)&((uint32_t)(regval)<<1)) +#define I2S_FRAMEFORMAT_DT16B_CH16B I2SCTL_DTLEN(0) /*!< I2S data length is 16 bit and channel length is 16 bit */ +#define I2S_FRAMEFORMAT_DT16B_CH32B (I2SCTL_DTLEN(0)|SPI_I2SCTL_CHLEN) /*!< I2S data length is 16 bit and channel length is 32 bit */ +#define I2S_FRAMEFORMAT_DT24B_CH32B (I2SCTL_DTLEN(1)|SPI_I2SCTL_CHLEN) /*!< I2S data length is 24 bit and channel length is 32 bit */ +#define I2S_FRAMEFORMAT_DT32B_CH32B (I2SCTL_DTLEN(2)|SPI_I2SCTL_CHLEN) /*!< I2S data length is 32 bit and channel length is 32 bit */ + +/* I2S master clock output */ +#define I2S_MCKOUT_DISABLE ((uint32_t)0x00000000U) /*!< I2S master clock output disable */ +#define I2S_MCKOUT_ENABLE SPI_I2SPSC_MCKOEN /*!< I2S master clock output enable */ + +/* I2S operation mode */ +#define I2SCTL_I2SOPMOD(regval) (BITS(8,9)&((uint32_t)(regval)<<8)) +#define I2S_MODE_SLAVETX I2SCTL_I2SOPMOD(0) /*!< I2S slave transmit mode */ +#define I2S_MODE_SLAVERX I2SCTL_I2SOPMOD(1) /*!< I2S slave receive mode */ +#define I2S_MODE_MASTERTX I2SCTL_I2SOPMOD(2) /*!< I2S master transmit mode */ +#define I2S_MODE_MASTERRX I2SCTL_I2SOPMOD(3) /*!< I2S master receive mode */ + +/* I2S standard */ +#define I2SCTL_I2SSTD(regval) (BITS(4,5)&((uint32_t)(regval)<<4)) +#define I2S_STD_PHILLIPS I2SCTL_I2SSTD(0) /*!< I2S phillips standard */ +#define I2S_STD_MSB I2SCTL_I2SSTD(1) /*!< I2S MSB standard */ +#define I2S_STD_LSB I2SCTL_I2SSTD(2) /*!< I2S LSB standard */ +#define I2S_STD_PCMSHORT I2SCTL_I2SSTD(3) /*!< I2S PCM short standard */ +#define I2S_STD_PCMLONG (I2SCTL_I2SSTD(3) | SPI_I2SCTL_PCMSMOD) /*!< I2S PCM long standard */ + +/* I2S clock polarity */ +#define I2S_CKPL_LOW ((uint32_t)0x00000000U) /*!< I2S clock polarity low level */ +#define I2S_CKPL_HIGH SPI_I2SCTL_CKPL /*!< I2S clock polarity high level */ + +/* SPI DMA constants definitions */ +#define SPI_DMA_TRANSMIT ((uint8_t)0x00U) /*!< SPI transmit data use DMA */ +#define SPI_DMA_RECEIVE ((uint8_t)0x01U) /*!< SPI receive data use DMA */ + +/* SPI CRC constants definitions */ +#define SPI_CRC_TX ((uint8_t)0x00U) /*!< SPI transmit CRC value */ +#define SPI_CRC_RX ((uint8_t)0x01U) /*!< SPI receive CRC value */ + +/* SPI/I2S interrupt enable/disable constants definitions */ +#define SPI_I2S_INT_TBE ((uint8_t)0x00U) /*!< transmit buffer empty interrupt */ +#define SPI_I2S_INT_RBNE ((uint8_t)0x01U) /*!< receive buffer not empty interrupt */ +#define SPI_I2S_INT_ERR ((uint8_t)0x02U) /*!< error interrupt */ + +/* SPI/I2S interrupt flag constants definitions */ +#define SPI_I2S_INT_FLAG_TBE ((uint8_t)0x00U) /*!< transmit buffer empty interrupt flag */ +#define SPI_I2S_INT_FLAG_RBNE ((uint8_t)0x01U) /*!< receive buffer not empty interrupt flag */ +#define SPI_I2S_INT_FLAG_RXORERR ((uint8_t)0x02U) /*!< overrun interrupt flag */ +#define SPI_INT_FLAG_CONFERR ((uint8_t)0x03U) /*!< config error interrupt flag */ +#define SPI_INT_FLAG_CRCERR ((uint8_t)0x04U) /*!< CRC error interrupt flag */ +#define I2S_INT_FLAG_TXURERR ((uint8_t)0x05U) /*!< underrun error interrupt flag */ +#define SPI_I2S_INT_FLAG_FERR ((uint8_t)0x06U) /*!< format error interrupt flag */ + +/* SPI/I2S flag definitions */ +#define SPI_FLAG_RBNE SPI_STAT_RBNE /*!< receive buffer not empty flag */ +#define SPI_FLAG_TBE SPI_STAT_TBE /*!< transmit buffer empty flag */ +#define SPI_FLAG_CRCERR SPI_STAT_CRCERR /*!< CRC error flag */ +#define SPI_FLAG_CONFERR SPI_STAT_CONFERR /*!< mode config error flag */ +#define SPI_FLAG_RXORERR SPI_STAT_RXORERR /*!< receive overrun error flag */ +#define SPI_FLAG_TRANS SPI_STAT_TRANS /*!< transmit on-going flag */ +#define SPI_FLAG_FERR SPI_STAT_FERR /*!< format error flag */ +#define I2S_FLAG_RBNE SPI_STAT_RBNE /*!< receive buffer not empty flag */ +#define I2S_FLAG_TBE SPI_STAT_TBE /*!< transmit buffer empty flag */ +#define I2S_FLAG_CH SPI_STAT_I2SCH /*!< channel side flag */ +#define I2S_FLAG_TXURERR SPI_STAT_TXURERR /*!< underrun error flag */ +#define I2S_FLAG_RXORERR SPI_STAT_RXORERR /*!< overrun error flag */ +#define I2S_FLAG_TRANS SPI_STAT_TRANS /*!< transmit on-going flag */ +#define I2S_FLAG_FERR SPI_STAT_FERR /*!< format error flag */ + +/* function declarations */ +/* initialization functions */ +/* deinitialize SPI and I2S */ +void spi_i2s_deinit(uint32_t spi_periph); +/* initialize the parameters of SPI struct with default values */ +void spi_struct_para_init(spi_parameter_struct *spi_struct); +/* initialize SPI parameter */ +void spi_init(uint32_t spi_periph, spi_parameter_struct *spi_struct); +/* enable SPI */ +void spi_enable(uint32_t spi_periph); +/* disable SPI */ +void spi_disable(uint32_t spi_periph); + +/* initialize I2S parameter */ +void i2s_init(uint32_t spi_periph, uint32_t i2s_mode, uint32_t i2s_standard, uint32_t i2s_ckpl); +/* configure I2S prescale */ +void i2s_psc_config(uint32_t spi_periph, uint32_t i2s_audiosample, uint32_t i2s_frameformat, uint32_t i2s_mckout); +/* enable I2S */ +void i2s_enable(uint32_t spi_periph); +/* disable I2S */ +void i2s_disable(uint32_t spi_periph); + +/* NSS functions */ +/* enable SPI nss output */ +void spi_nss_output_enable(uint32_t spi_periph); +/* disable SPI nss output */ +void spi_nss_output_disable(uint32_t spi_periph); +/* SPI nss pin high level in software mode */ +void spi_nss_internal_high(uint32_t spi_periph); +/* SPI nss pin low level in software mode */ +void spi_nss_internal_low(uint32_t spi_periph); + +/* SPI DMA functions */ +/* enable SPI DMA send or receive */ +void spi_dma_enable(uint32_t spi_periph, uint8_t spi_dma); +/* diable SPI DMA send or receive */ +void spi_dma_disable(uint32_t spi_periph, uint8_t spi_dma); + +/* SPI/I2S transfer configure functions */ +/* configure SPI/I2S data frame format */ +void spi_i2s_data_frame_format_config(uint32_t spi_periph, uint16_t frame_format); +/* SPI transmit data */ +void spi_i2s_data_transmit(uint32_t spi_periph, uint16_t data); +/* SPI receive data */ +uint16_t spi_i2s_data_receive(uint32_t spi_periph); +/* configure SPI bidirectional transfer direction */ +void spi_bidirectional_transfer_config(uint32_t spi_periph, uint32_t transfer_direction); + +/* SPI CRC functions */ +/* set SPI CRC polynomial */ +void spi_crc_polynomial_set(uint32_t spi_periph, uint16_t crc_poly); +/* get SPI CRC polynomial */ +uint16_t spi_crc_polynomial_get(uint32_t spi_periph); +/* turn on SPI CRC function */ +void spi_crc_on(uint32_t spi_periph); +/* turn off SPI CRC function */ +void spi_crc_off(uint32_t spi_periph); +/* SPI next data is CRC value */ +void spi_crc_next(uint32_t spi_periph); +/* get SPI CRC send value or receive value */ +uint16_t spi_crc_get(uint32_t spi_periph, uint8_t spi_crc); + +/* SPI TI mode functions */ +/* enable SPI TI mode */ +void spi_ti_mode_enable(uint32_t spi_periph); +/* disable SPI TI mode */ +void spi_ti_mode_disable(uint32_t spi_periph); + +/* configure i2s full duplex mode */ +void i2s_full_duplex_mode_config(uint32_t i2s_add_periph, uint32_t i2s_mode, uint32_t i2s_standard, uint32_t i2s_ckpl, uint32_t i2s_frameformat); + +/* quad wire SPI functions */ +/* enable quad wire SPI */ +void spi_quad_enable(uint32_t spi_periph); +/* disable quad wire SPI */ +void spi_quad_disable(uint32_t spi_periph); +/* enable quad wire SPI write */ +void spi_quad_write_enable(uint32_t spi_periph); +/* enable quad wire SPI read */ +void spi_quad_read_enable(uint32_t spi_periph); +/* enable SPI_IO2 and SPI_IO3 pin output */ +void spi_quad_io23_output_enable(uint32_t spi_periph); +/* disable SPI_IO2 and SPI_IO3 pin output */ +void spi_quad_io23_output_disable(uint32_t spi_periph); + +/* flag & interrupt functions */ +/* enable SPI and I2S interrupt */ +void spi_i2s_interrupt_enable(uint32_t spi_periph, uint8_t spi_i2s_int); +/* disable SPI and I2S interrupt */ +void spi_i2s_interrupt_disable(uint32_t spi_periph, uint8_t spi_i2s_int); +/* get SPI and I2S interrupt status*/ +FlagStatus spi_i2s_interrupt_flag_get(uint32_t spi_periph, uint8_t spi_i2s_int); +/* get SPI and I2S flag status */ +FlagStatus spi_i2s_flag_get(uint32_t spi_periph, uint32_t spi_i2s_flag); +/* clear SPI CRC error flag status */ +void spi_crc_error_clear(uint32_t spi_periph); + +#endif /* GD32F5XX_SPI_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_syscfg.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_syscfg.h new file mode 100644 index 0000000..a364942 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_syscfg.h @@ -0,0 +1,356 @@ +/*! + \file gd32f5xx_syscfg.h + \brief definitions for the SYSCFG + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_SYSCFG_H +#define GD32F5XX_SYSCFG_H + +#include "gd32f5xx.h" + +/* SYSCFG definitions */ +#define SYSCFG SYSCFG_BASE + +/* registers definitions */ +#define SYSCFG_CFG0 REG32(SYSCFG + 0x00U) /*!< system configuration register 0 */ +#define SYSCFG_CFG1 REG32(SYSCFG + 0x04U) /*!< system configuration register 1 */ +#define SYSCFG_EXTISS0 REG32(SYSCFG + 0x08U) /*!< EXTI sources selection register 0 */ +#define SYSCFG_EXTISS1 REG32(SYSCFG + 0x0CU) /*!< EXTI sources selection register 1 */ +#define SYSCFG_EXTISS2 REG32(SYSCFG + 0x10U) /*!< EXTI sources selection register 2 */ +#define SYSCFG_EXTISS3 REG32(SYSCFG + 0x14U) /*!< EXTI sources selection register 3 */ +#define SYSCFG_CPSCTL REG32(SYSCFG + 0x20U) /*!< system I/O compensation control register */ +#define SYSCFG_STAT REG32(SYSCFG + 0x24U) /*!< system status register 0 */ +#define SYSCFG_SRAM0ECC REG32(SYSCFG + 0x28U) /*!< SRAM0 ECC status register */ +#define SYSCFG_SRAM1ECC REG32(SYSCFG + 0x2CU) /*!< SRAM1 ECC status register */ +#define SYSCFG_SRAM2ECC REG32(SYSCFG + 0x30U) /*!< SRAM2 ECC status register */ +#define SYSCFG_ADDSRAMECC REG32(SYSCFG + 0x34U) /*!< ADDSRAM ECC status register */ +#define SYSCFG_TCMSRAMECC REG32(SYSCFG + 0x38U) /*!< TCMSRAM ECC status register */ +#define SYSCFG_BKPSRAMECC REG32(SYSCFG + 0x3CU) /*!< BKPSRAM ECC status register */ +#define SYSCFG_FLASHECC_ADDR REG32(SYSCFG + 0x40U) /*!< FLASH ECC address register */ +#define SYSCFG_FLASHECC REG32(SYSCFG + 0x44U) /*!< FLASH ECC register */ +#define USER_CFG REG32(SYSCFG + 0x300U) /*!< user configuration register */ + +/* SYSCFG_CFG0 bits definitions */ +#define SYSCFG_CFG0_BOOT_MODE BITS(0,2) /*!< SYSCFG memory remap config */ +#define SYSCFG_CFG0_FMC_SWP BIT(8) /*!< FMC memory swap config */ +#define SYSCFG_CFG0_EXMC_SWP BITS(10,11) /*!< EXMC memory swap config */ + +/* SYSCFG_CFG1 bits definitions */ +#define SYSCFG_CFG1_I2C3FMP BIT(0) /*!< enable fast mode+ on I2C3 */ +#define SYSCFG_CFG1_I2C4FMP BIT(1) /*!< enable fast mode+ on I2C4 */ +#define SYSCFG_CFG1_I2C5FMP BIT(2) /*!< enable fast mode+ on I2C5 */ +#define SYSCFG_CFG1_ENET_PHY_SEL BIT(23) /*!< Ethernet PHY selection config */ + +/* SYSCFG_EXTISS0 bits definitions */ +#define SYSCFG_EXTISS0_EXTI0_SS BITS(0,3) /*!< EXTI 0 configuration */ +#define SYSCFG_EXTISS0_EXTI1_SS BITS(4,7) /*!< EXTI 1 configuration */ +#define SYSCFG_EXTISS0_EXTI2_SS BITS(8,11) /*!< EXTI 2 configuration */ +#define SYSCFG_EXTISS0_EXTI3_SS BITS(12,15) /*!< EXTI 3 configuration */ + +/* SYSCFG_EXTISS1 bits definitions */ +#define SYSCFG_EXTISS1_EXTI4_SS BITS(0,3) /*!< EXTI 4 configuration */ +#define SYSCFG_EXTISS1_EXTI5_SS BITS(4,7) /*!< EXTI 5 configuration */ +#define SYSCFG_EXTISS1_EXTI6_SS BITS(8,11) /*!< EXTI 6 configuration */ +#define SYSCFG_EXTISS1_EXTI7_SS BITS(12,15) /*!< EXTI 7 configuration */ + +/* SYSCFG_EXTISS2 bits definitions */ +#define SYSCFG_EXTISS2_EXTI8_SS BITS(0,3) /*!< EXTI 8 configuration */ +#define SYSCFG_EXTISS2_EXTI9_SS BITS(4,7) /*!< EXTI 9 configuration */ +#define SYSCFG_EXTISS2_EXTI10_SS BITS(8,11) /*!< EXTI 10 configuration */ +#define SYSCFG_EXTISS2_EXTI11_SS BITS(12,15) /*!< EXTI 11 configuration */ + +/* SYSCFG_EXTISS3 bits definitions */ +#define SYSCFG_EXTISS3_EXTI12_SS BITS(0,3) /*!< EXTI 12 configuration */ +#define SYSCFG_EXTISS3_EXTI13_SS BITS(4,7) /*!< EXTI 13 configuration */ +#define SYSCFG_EXTISS3_EXTI14_SS BITS(8,11) /*!< EXTI 14 configuration */ +#define SYSCFG_EXTISS3_EXTI15_SS BITS(12,15) /*!< EXTI 15 configuration */ + +/* SYSCFG_CPSCTL bits definitions */ +#define SYSCFG_CPSCTL_CPS_EN BIT(0) /*!< I/O compensation cell enable */ +#define SYSCFG_CPSCTL_CPS_RDY BIT(8) /*!< I/O compensation cell is ready or not */ + +/* SYSCFG_STAT bits definitions */ +#define SYSCFG_STAT_ECCMEIF0 BIT(0) /*!< SRAM0 two bits no-correction event flag */ +#define SYSCFG_STAT_ECCSEIF0 BIT(1) /*!< SRAM0 single bit correction event flag */ +#define SYSCFG_STAT_ECCMEIF1 BIT(2) /*!< SRAM1 two bits no-correction event flag */ +#define SYSCFG_STAT_ECCSEIF1 BIT(3) /*!< SRAM1 single bit correction event flag */ +#define SYSCFG_STAT_ECCMEIF2 BIT(4) /*!< SRAM2 two bits no-correction event flag */ +#define SYSCFG_STAT_ECCSEIF2 BIT(5) /*!< SRAM2 single bit correction event flag */ +#define SYSCFG_STAT_ECCMEIF3 BIT(6) /*!< ADDSRAM two bits no-correction event flag */ +#define SYSCFG_STAT_ECCSEIF3 BIT(7) /*!< ADDSRAM single bit correction event flag */ +#define SYSCFG_STAT_ECCMEIF4 BIT(8) /*!< TCMSRAM two bits no-correction event flag */ +#define SYSCFG_STAT_ECCSEIF4 BIT(9) /*!< TCMSRAM single bit correction event flag */ +#define SYSCFG_STAT_ECCMEIF5 BIT(10) /*!< BKPSRAM two bits no-correction event flag */ +#define SYSCFG_STAT_ECCSEIF5 BIT(11) /*!< BKPSRAM single bit correction event flag */ +#define SYSCFG_STAT_ECCMEIF6 BIT(12) /*!< FLASH two bits no-correction event flag */ +#define SYSCFG_STAT_ECCSEIF6 BIT(13) /*!< FLASH single bit correction event flag */ +#define SYSCFG_STAT_CKMNMIIF BIT(14) /*!< HXTAL clock moniotor NMI interrupt flag */ + +/* SYSCFG_SRAM0ECC bits definitions */ +#define SYSCFG_SRAM0ECC_ECCMEIE0 BIT(0) /*!< SRAM0 two bits non-correction interrupt enable */ +#define SYSCFG_SRAM0ECC_ECCSEIE0 BIT(1) /*!< SRAM0 single bit correction interrupt enable */ +#define SYSCFG_SRAM0ECC_CKMNMIIE BIT(2) /*!< HXTAL clock moniotor NMI interrupt enable */ +#define SYSCFG_SRAM0ECC_ECCSERRBITS0 BITS(10,15) /*!< indicates the error bit */ +#define SYSCFG_SRAM0ECC_ECCEADDR0 BITS(16,31) /*!< indicates the last address ECC event on SRAM0 occurred */ + +/* SYSCFG_SRAM1ECC bits definitions */ +#define SYSCFG_SRAM1ECC_ECCMEIE1 BIT(0) /*!< SRAM1 two bits non-correction interrupt enable */ +#define SYSCFG_SRAM1ECC_ECCSEIE1 BIT(1) /*!< SRAM1 single bit correction interrupt enable */ +#define SYSCFG_SRAM1ECC_ECCSERRBITS1 BITS(12,17) /*!< indicates the error bit */ +#define SYSCFG_SRAM1ECC_ECCEADDR1 BITS(18,31) /*!< indicates the last address ECC event on SRAM1 occurred */ + +/* SYSCFG_SRAM2ECC bits definitions */ +#define SYSCFG_SRAM2ECC_ECCMEIE2 BIT(0) /*!< SRAM2 two bits non-correction interrupt enable */ +#define SYSCFG_SRAM2ECC_ECCSEIE2 BIT(1) /*!< SRAM2 single bit correction interrupt enable */ +#define SYSCFG_SRAM2ECC_ECCSERRBITS2 BITS(10,15) /*!< indicates the error bit */ +#define SYSCFG_SRAM2ECC_ECCEADDR2 BITS(16,31) /*!< indicates the last address ECC event on SRAM2 occurred */ + +/* SYSCFG_ADDSRAMECC bits definitions */ +#define SYSCFG_ADDSRAMECC_ECCMEIE3 BIT(0) /*!< ADDSRAM two bits non-correction interrupt enable */ +#define SYSCFG_ADDSRAMECC_ECCSEIE3 BIT(1) /*!< ADDSRAM single bit correction interrupt enable */ +#define SYSCFG_ADDSRAMECC_ECCSERRBITS3 BITS(8,13) /*!< indicates the error bit */ +#define SYSCFG_ADDSRAMECC_ECCEADDR3 BITS(14,31) /*!< indicates the last address ECC event on ADDSRAM occurred */ + +/* SYSCFG_TCMSRAMECC bits definitions */ +#define SYSCFG_TCMSRAMECC_ECCMEIE4 BIT(0) /*!< TCMSRAM two bits non-correction interrupt enable */ +#define SYSCFG_TCMSRAMECC_ECCSEIE4 BIT(1) /*!< TCMSRAM single bit correction interrupt enable */ +#define SYSCFG_TCMSRAMECC_ECCSERRBITS4 BITS(12,17) /*!< indicates the error bit */ +#define SYSCFG_TCMSRAMECC_ECCEADDR4 BITS(18,31) /*!< indicates the last address ECC event on TCMSRAM occurred */ + +/* SYSCFG_BKPSRAMECC bits definitions */ +#define SYSCFG_BKPSRAMECC_ECCMEIE5 BIT(0) /*!< BKPSRAM two bits non-correction interrupt enable */ +#define SYSCFG_BKPSRAMECC_ECCSEIE5 BIT(1) /*!< BKPSRAM single bit correction interrupt enable */ +#define SYSCFG_BKPSRAMECC_ECCSERRBITS5 BITS(16,21) /*!< indicates the error bit */ +#define SYSCFG_BKPSRAMECC_ECCEADDR5 BITS(22,31) /*!< indicates the last address ECC event on BKPSRAM occurred */ + +/* SYSCFG_FLASHECC_ADDR */ +#define SYSCFG_FLASHECC_ADDR_ECCEADDR6 BITS(0,31) /*!< indicates the last address of ECC event on FLASH occurred */ + +/* SYSCFG_FLASHECC bits definitions */ +#define SYSCFG_FLASHECC_ECCMEIE6 BIT(0) /*!< FLASH two bits non-correction interrupt enable */ +#define SYSCFG_FLASHECC_ECCSEIE6 BIT(1) /*!< FLASH single bit correction interrupt enable */ +#define SYSCFG_FLASHECC_ECCSERRBITS6 BITS(2,7) /*!< indicates the error bit */ + +/* USER_CFG bits definitions */ +#define USER_CFG_ANA_VERSION BITS(24,31) /*!< analog version information */ + +/* constants definitions */ +/* boot mode definitions */ +#define SYSCFG_BOOTMODE_FLASH ((uint8_t)0x00U) /*!< main flash memory remap */ +#define SYSCFG_BOOTMODE_BOOTLOADER ((uint8_t)0x01U) /*!< boot loader remap */ +#define SYSCFG_BOOTMODE_SRAM ((uint8_t)0x03U) /*!< SRAM0 of on-chip SRAM remap */ +#define SYSCFG_BOOTMODE_OTP ((uint8_t)0x05U) /*!< OTP remap */ + +/* FMC swap definitions */ +#define SYSCFG_FMC_SWP_BANK0 ((uint32_t)0x00000000U) /*!< main flash Bank 0 is mapped at address 0x08000000 */ +#define SYSCFG_FMC_SWP_BANK1 ((uint32_t)0x00000100U) /*!< main flash Bank 1 is mapped at address 0x08000000 */ + +/* EXMC swap enable/disable */ +#define SYSCFG_EXMC_SWP_ENABLE ((uint32_t)0x00000400U) /*!< SDRAM bank 0 and bank 1 are swapped with NAND bank 1 and PC card */ +#define SYSCFG_EXMC_SWP_DISABLE ((uint32_t)0x00000000U) /*!< no memory mapping swap */ + +/* EXTI source select definition */ +#define EXTISS0 ((uint8_t)0x00U) /*!< EXTI source select GPIOx pin 0~3 */ +#define EXTISS1 ((uint8_t)0x01U) /*!< EXTI source select GPIOx pin 4~7 */ +#define EXTISS2 ((uint8_t)0x02U) /*!< EXTI source select GPIOx pin 8~11 */ +#define EXTISS3 ((uint8_t)0x03U) /*!< EXTI source select GPIOx pin 12~15 */ + +/* EXTI source select mask bits definition */ +#define EXTI_SS_MASK BITS(0,3) /*!< EXTI source select mask */ + +/* EXTI source select jumping step definition */ +#define EXTI_SS_JSTEP ((uint8_t)(0x04U)) /*!< EXTI source select jumping step */ + +/* EXTI source select moving step definition */ +#define EXTI_SS_MSTEP(pin) (EXTI_SS_JSTEP*((pin)%EXTI_SS_JSTEP)) /*!< EXTI source select moving step */ + +/* EXTI source port definitions */ +#define EXTI_SOURCE_GPIOA ((uint8_t)0x00U) /*!< EXTI GPIOA configuration */ +#define EXTI_SOURCE_GPIOB ((uint8_t)0x01U) /*!< EXTI GPIOB configuration */ +#define EXTI_SOURCE_GPIOC ((uint8_t)0x02U) /*!< EXTI GPIOC configuration */ +#define EXTI_SOURCE_GPIOD ((uint8_t)0x03U) /*!< EXTI GPIOD configuration */ +#define EXTI_SOURCE_GPIOE ((uint8_t)0x04U) /*!< EXTI GPIOE configuration */ +#define EXTI_SOURCE_GPIOF ((uint8_t)0x05U) /*!< EXTI GPIOF configuration */ +#define EXTI_SOURCE_GPIOG ((uint8_t)0x06U) /*!< EXTI GPIOG configuration */ +#define EXTI_SOURCE_GPIOH ((uint8_t)0x07U) /*!< EXTI GPIOH configuration */ +#define EXTI_SOURCE_GPIOI ((uint8_t)0x08U) /*!< EXTI GPIOI configuration */ + +/* EXTI source pin definitions */ +#define EXTI_SOURCE_PIN0 ((uint8_t)0x00U) /*!< EXTI GPIO pin0 configuration */ +#define EXTI_SOURCE_PIN1 ((uint8_t)0x01U) /*!< EXTI GPIO pin1 configuration */ +#define EXTI_SOURCE_PIN2 ((uint8_t)0x02U) /*!< EXTI GPIO pin2 configuration */ +#define EXTI_SOURCE_PIN3 ((uint8_t)0x03U) /*!< EXTI GPIO pin3 configuration */ +#define EXTI_SOURCE_PIN4 ((uint8_t)0x04U) /*!< EXTI GPIO pin4 configuration */ +#define EXTI_SOURCE_PIN5 ((uint8_t)0x05U) /*!< EXTI GPIO pin5 configuration */ +#define EXTI_SOURCE_PIN6 ((uint8_t)0x06U) /*!< EXTI GPIO pin6 configuration */ +#define EXTI_SOURCE_PIN7 ((uint8_t)0x07U) /*!< EXTI GPIO pin7 configuration */ +#define EXTI_SOURCE_PIN8 ((uint8_t)0x08U) /*!< EXTI GPIO pin8 configuration */ +#define EXTI_SOURCE_PIN9 ((uint8_t)0x09U) /*!< EXTI GPIO pin9 configuration */ +#define EXTI_SOURCE_PIN10 ((uint8_t)0x0AU) /*!< EXTI GPIO pin10 configuration */ +#define EXTI_SOURCE_PIN11 ((uint8_t)0x0BU) /*!< EXTI GPIO pin11 configuration */ +#define EXTI_SOURCE_PIN12 ((uint8_t)0x0CU) /*!< EXTI GPIO pin12 configuration */ +#define EXTI_SOURCE_PIN13 ((uint8_t)0x0DU) /*!< EXTI GPIO pin13 configuration */ +#define EXTI_SOURCE_PIN14 ((uint8_t)0x0EU) /*!< EXTI GPIO pin14 configuration */ +#define EXTI_SOURCE_PIN15 ((uint8_t)0x0FU) /*!< EXTI GPIO pin15 configuration */ + +/* ethernet PHY selection */ +#define SYSCFG_ENET_PHY_MII ((uint32_t)0x00000000U) /*!< MII is selected for the Ethernet MAC */ +#define SYSCFG_ENET_PHY_RMII ((uint32_t)0x00800000U) /*!< RMII is selected for the Ethernet MAC */ + +/* I/O compensation cell enable/disable */ +#define SYSCFG_COMPENSATION_ENABLE ((uint32_t)0x00000001U) /*!< I/O compensation cell enable */ +#define SYSCFG_COMPENSATION_DISABLE ((uint32_t)0x00000000U) /*!< I/O compensation cell disable */ + +/* define ECC type */ +typedef enum +{ + SYSCFG_SRAM0_ECC = 0, /*!< SRAM0 ECC event */ + SYSCFG_SRAM1_ECC, /*!< SRAM1 ECC event */ + SYSCFG_SRAM2_ECC, /*!< SRAM2 ECC event */ + SYSCFG_ADDSRAM_ECC, /*!< ADDSRAM ECC event */ + SYSCFG_TCMSRAM_ECC, /*!< TCMSRAM ECC event */ + SYSCFG_BKPSRAM_ECC, /*!< BKPSRAM ECC event */ + SYSCFG_FLASH_ECC /*!< FLASH ECC event */ +} syscfg_ecc_enum; + +/* define the EXTI bit position and its register group index offset */ +#define SYSCFG_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6U) | (uint32_t)(bitpos)) +#define SYSCFG_REG_VAL(offset) (REG32(SYSCFG + ((uint32_t)(offset) >> 6U))) +#define SYSCFG_BIT_POS(val) ((uint32_t)(val) & 0x0000001FU) + +/* register offset */ +#define SRAM0ECC_REG_OFFSET ((uint32_t)0x00000028U) /*!< SRAM0ECC register offset */ +#define SRAM1ECC_REG_OFFSET ((uint32_t)0x0000002CU) /*!< SRAM1ECC register offset */ +#define SRAM2ECC_REG_OFFSET ((uint32_t)0x00000030U) /*!< SRAM2ECC register offset */ +#define ADDSRAMECC_REG_OFFSET ((uint32_t)0x00000034U) /*!< ADDSRAMECC register offset */ +#define TCMSRAMECC_REG_OFFSET ((uint32_t)0x00000038U) /*!< TCMSRAMECC register offset */ +#define BKPSRAMECC_REG_OFFSET ((uint32_t)0x0000003CU) /*!< BKPSRAMECC register offset */ +#define FLASHECC_REG_OFFSET ((uint32_t)0x00000044U) /*!< FLASHECC register offset */ + +/* SYSCFG interrupt enable or disable */ +typedef enum +{ + SYSCFG_INT_ECCME0 = SYSCFG_REGIDX_BIT(SRAM0ECC_REG_OFFSET, 0U), /*!< SRAM0 two bits non-correction interrupt */ + SYSCFG_INT_ECCSE0 = SYSCFG_REGIDX_BIT(SRAM0ECC_REG_OFFSET, 1U), /*!< SRAM0 single bit correction interrupt */ + SYSCFG_INT_CKMNMI = SYSCFG_REGIDX_BIT(SRAM0ECC_REG_OFFSET, 2U), /*!< HXTAL clock moniotor NMI interrupt */ + SYSCFG_INT_ECCME1 = SYSCFG_REGIDX_BIT(SRAM1ECC_REG_OFFSET, 0U), /*!< SRAM1 two bits non-correction interrupt */ + SYSCFG_INT_ECCSE1 = SYSCFG_REGIDX_BIT(SRAM1ECC_REG_OFFSET, 1U), /*!< SRAM1 single bit correction interrupt */ + SYSCFG_INT_ECCME2 = SYSCFG_REGIDX_BIT(SRAM2ECC_REG_OFFSET, 0U), /*!< SRAM2 two bits non-correction interrupt */ + SYSCFG_INT_ECCSE2 = SYSCFG_REGIDX_BIT(SRAM2ECC_REG_OFFSET, 1U), /*!< SRAM2 single bit correction interrupt */ + SYSCFG_INT_ECCME3 = SYSCFG_REGIDX_BIT(ADDSRAMECC_REG_OFFSET, 0U), /*!< ADDSRAM two bits non-correction interrupt */ + SYSCFG_INT_ECCSE3 = SYSCFG_REGIDX_BIT(ADDSRAMECC_REG_OFFSET, 1U), /*!< ADDSRAM single bit correction interrupt */ + SYSCFG_INT_ECCME4 = SYSCFG_REGIDX_BIT(TCMSRAMECC_REG_OFFSET, 0U), /*!< TCMSRAM two bits non-correction interrupt */ + SYSCFG_INT_ECCSE4 = SYSCFG_REGIDX_BIT(TCMSRAMECC_REG_OFFSET, 1U), /*!< TCMSRAM single bit correction interrupt */ + SYSCFG_INT_ECCME5 = SYSCFG_REGIDX_BIT(BKPSRAMECC_REG_OFFSET, 0U), /*!< BKPSRAM two bits non-correction interrupt */ + SYSCFG_INT_ECCSE5 = SYSCFG_REGIDX_BIT(BKPSRAMECC_REG_OFFSET, 1U), /*!< BKPSRAM single bit correction interrupt */ + SYSCFG_INT_ECCME6 = SYSCFG_REGIDX_BIT(FLASHECC_REG_OFFSET, 0U), /*!< FLASH two bits non-correction interrupt */ + SYSCFG_INT_ECCSE6 = SYSCFG_REGIDX_BIT(FLASHECC_REG_OFFSET, 1U) /*!< FLASH single bit correction interrupt */ +} syscfg_interrupt_enum; + +/* SYSCFG flags */ +typedef enum +{ + SYSCFG_FLAG_ECCME0 = SYSCFG_STAT_ECCMEIF0, /*!< SRAM0 two bits non-correction event flag */ + SYSCFG_FLAG_ECCSE0 = SYSCFG_STAT_ECCSEIF0, /*!< SRAM0 single bit correction event flag */ + SYSCFG_FLAG_ECCME1 = SYSCFG_STAT_ECCMEIF1, /*!< SRAM1 two bits non-correction event flag */ + SYSCFG_FLAG_ECCSE1 = SYSCFG_STAT_ECCSEIF1, /*!< SRAM1 single bit correction event flag */ + SYSCFG_FLAG_ECCME2 = SYSCFG_STAT_ECCMEIF2, /*!< SRAM2 two bits non-correction event flag */ + SYSCFG_FLAG_ECCSE2 = SYSCFG_STAT_ECCSEIF2, /*!< SRAM2 single bit correction event flag */ + SYSCFG_FLAG_ECCME3 = SYSCFG_STAT_ECCMEIF3, /*!< ADDSRAM two bits non-correction event flag */ + SYSCFG_FLAG_ECCSE3 = SYSCFG_STAT_ECCSEIF3, /*!< ADDSRAM single bit correction event flag */ + SYSCFG_FLAG_ECCME4 = SYSCFG_STAT_ECCMEIF4, /*!< TCMSRAM two bits non-correction event flag */ + SYSCFG_FLAG_ECCSE4 = SYSCFG_STAT_ECCSEIF4, /*!< TCMSRAM single bit correction event flag */ + SYSCFG_FLAG_ECCME5 = SYSCFG_STAT_ECCMEIF5, /*!< BKPSRAM two bits non-correction event flag */ + SYSCFG_FLAG_ECCSE5 = SYSCFG_STAT_ECCSEIF5, /*!< BKPSRAM single bit correction event flag */ + SYSCFG_FLAG_ECCME6 = SYSCFG_STAT_ECCMEIF6, /*!< FLASH two bits non-correction event flag */ + SYSCFG_FLAG_ECCSE6 = SYSCFG_STAT_ECCSEIF6, /*!< FLASH single bit correction event flag */ + SYSCFG_FLAG_CKMNMI = SYSCFG_STAT_CKMNMIIF /*!< HXTAL clock moniotor NMI flag */ +} syscfg_flag_enum; + +/* SYSCFG interrupt flags */ +typedef enum +{ + SYSCFG_INT_FLAG_ECCME0 = SYSCFG_STAT_ECCMEIF0, /*!< SRAM0 two bits non-correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCSE0 = SYSCFG_STAT_ECCSEIF0, /*!< SRAM0 single bit correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCME1 = SYSCFG_STAT_ECCMEIF1, /*!< SRAM1 two bits non-correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCSE1 = SYSCFG_STAT_ECCSEIF1, /*!< SRAM1 single bit correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCME2 = SYSCFG_STAT_ECCMEIF2, /*!< SRAM2 two bits non-correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCSE2 = SYSCFG_STAT_ECCSEIF2, /*!< SRAM2 single bit correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCME3 = SYSCFG_STAT_ECCMEIF3, /*!< ADDSRAM two bits non-correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCSE3 = SYSCFG_STAT_ECCSEIF3, /*!< ADDSRAM single bit correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCME4 = SYSCFG_STAT_ECCMEIF4, /*!< TCMSRAM two bits non-correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCSE4 = SYSCFG_STAT_ECCSEIF4, /*!< TCMSRAM single bit correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCME5 = SYSCFG_STAT_ECCMEIF5, /*!< BKPSRAM two bits non-correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCSE5 = SYSCFG_STAT_ECCSEIF5, /*!< BKPSRAM single bit correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCME6 = SYSCFG_STAT_ECCMEIF6, /*!< FLASH two bits non-correction event interrupt flag */ + SYSCFG_INT_FLAG_ECCSE6 = SYSCFG_STAT_ECCSEIF6, /*!< FLASH single bit correction event interrupt flag */ + SYSCFG_INT_FLAG_CKMNMI = SYSCFG_STAT_CKMNMIIF /*!< HXTAL clock moniotor NMI interrupt flag */ +} syscfg_interrupt_flag_enum; + +/* function declarations */ +/* initialization functions */ +/* deinit syscfg module */ +void syscfg_deinit(void); + +/* function configuration */ +/* configure the boot mode */ +void syscfg_bootmode_config(uint8_t syscfg_bootmode); +/* configure FMC memory mapping swap */ +void syscfg_fmc_swap_config(uint32_t syscfg_fmc_swap); +/* configure the EXMC swap */ +void syscfg_exmc_swap_config(uint32_t syscfg_exmc_swap); +/* configure the GPIO pin as EXTI Line */ +void syscfg_exti_line_config(uint8_t exti_port, uint8_t exti_pin); +/* configure the PHY interface for the ethernet MAC */ +void syscfg_enet_phy_interface_config(uint32_t syscfg_enet_phy_interface); +/* configure the I/O compensation cell */ +void syscfg_compensation_config(uint32_t syscfg_compensation); +/* get Compensation cell ready flag */ +FlagStatus syscfg_cps_cell_ready_get(void); +uint32_t syscfg_ecc_err_bits_get(syscfg_ecc_enum ecc_type); +uint32_t syscfg_ecc_address_get(syscfg_ecc_enum ecc_type); + +/* interrupt & flag functions */ +/* get SYSCFG flag state */ +FlagStatus syscfg_flag_get(syscfg_flag_enum flag); +/* clear SYSCFG flag state */ +void syscfg_flag_clear(syscfg_flag_enum flag); +/* enable SYSCFG interrupt */ +void syscfg_interrupt_enable(syscfg_interrupt_enum interrupt); +/* disable SYSCFG interrupt */ +void syscfg_interrupt_disable(syscfg_interrupt_enum interrupt); +/* get SYSCFG interrupt flag state */ +FlagStatus syscfg_interrupt_flag_get(syscfg_interrupt_flag_enum flag); +/* clear SYSCFG interrupt flag state */ +void syscfg_interrupt_flag_clear(syscfg_interrupt_flag_enum flag); + +#endif /* GD32F5XX_SYSCFG_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_timer.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_timer.h new file mode 100644 index 0000000..a66a598 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_timer.h @@ -0,0 +1,869 @@ +/*! + \file gd32f5xx_timer.h + \brief definitions for the TIMER + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_TIMER_H +#define GD32F5XX_TIMER_H + +#include "gd32f5xx.h" + +/* TIMERx(x=0..13) definitions */ +#define TIMER0 (TIMER_BASE + 0x00010000U) +#define TIMER1 (TIMER_BASE + 0x00000000U) +#define TIMER2 (TIMER_BASE + 0x00000400U) +#define TIMER3 (TIMER_BASE + 0x00000800U) +#define TIMER4 (TIMER_BASE + 0x00000C00U) +#define TIMER5 (TIMER_BASE + 0x00001000U) +#define TIMER6 (TIMER_BASE + 0x00001400U) +#define TIMER7 (TIMER_BASE + 0x00010400U) +#define TIMER8 (TIMER_BASE + 0x00014000U) +#define TIMER9 (TIMER_BASE + 0x00014400U) +#define TIMER10 (TIMER_BASE + 0x00014800U) +#define TIMER11 (TIMER_BASE + 0x00001800U) +#define TIMER12 (TIMER_BASE + 0x00001C00U) +#define TIMER13 (TIMER_BASE + 0x00002000U) + +/* registers definitions */ +#define TIMER_CTL0(timerx) REG32((timerx) + 0x00000000U) /*!< TIMER control register 0 */ +#define TIMER_CTL1(timerx) REG32((timerx) + 0x00000004U) /*!< TIMER control register 1 */ +#define TIMER_SMCFG(timerx) REG32((timerx) + 0x00000008U) /*!< TIMER slave mode configuration register */ +#define TIMER_DMAINTEN(timerx) REG32((timerx) + 0x0000000CU) /*!< TIMER DMA and interrupt enable register */ +#define TIMER_INTF(timerx) REG32((timerx) + 0x00000010U) /*!< TIMER interrupt flag register */ +#define TIMER_SWEVG(timerx) REG32((timerx) + 0x00000014U) /*!< TIMER software event generation register */ +#define TIMER_CHCTL0(timerx) REG32((timerx) + 0x00000018U) /*!< TIMER channel control register 0 */ +#define TIMER_CHCTL1(timerx) REG32((timerx) + 0x0000001CU) /*!< TIMER channel control register 1 */ +#define TIMER_CHCTL2(timerx) REG32((timerx) + 0x00000020U) /*!< TIMER channel control register 2 */ +#define TIMER_CNT(timerx) REG32((timerx) + 0x00000024U) /*!< TIMER counter register */ +#define TIMER_PSC(timerx) REG32((timerx) + 0x00000028U) /*!< TIMER prescaler register */ +#define TIMER_CAR(timerx) REG32((timerx) + 0x0000002CU) /*!< TIMER counter auto reload register */ +#define TIMER_CREP(timerx) REG32((timerx) + 0x00000030U) /*!< TIMER counter repetition register */ +#define TIMER_CH0CV(timerx) REG32((timerx) + 0x00000034U) /*!< TIMER channel 0 capture/compare value register */ +#define TIMER_CH1CV(timerx) REG32((timerx) + 0x00000038U) /*!< TIMER channel 1 capture/compare value register */ +#define TIMER_CH2CV(timerx) REG32((timerx) + 0x0000003CU) /*!< TIMER channel 2 capture/compare value register */ +#define TIMER_CH3CV(timerx) REG32((timerx) + 0x00000040U) /*!< TIMER channel 3 capture/compare value register */ +#define TIMER_CCHP(timerx) REG32((timerx) + 0x00000044U) /*!< TIMER complementary channel protection register */ +#define TIMER_DMACFG(timerx) REG32((timerx) + 0x00000048U) /*!< TIMER DMA configuration register */ +#define TIMER_DMATB(timerx) REG32((timerx) + 0x0000004CU) /*!< TIMER DMA transfer buffer register */ +#define TIMER_IRMP(timerx) REG32((timerx) + 0x00000050U) /*!< TIMER channel input remap register */ +#define TIMER_CH0COMV_ADD(timerx) REG32((timerx) + 0x00000064U) /*!< TIMER channel 0 additional compare value register */ +#define TIMER_CH1COMV_ADD(timerx) REG32((timerx) + 0x00000068U) /*!< TIMER channel 1 additional compare value register */ +#define TIMER_CH2COMV_ADD(timerx) REG32((timerx) + 0x0000006CU) /*!< TIMER channel 2 additional compare value register */ +#define TIMER_CH3COMV_ADD(timerx) REG32((timerx) + 0x00000070U) /*!< TIMER channel 3 additional compare value register */ +#define TIMER_CTL2(timerx) REG32((timerx) + 0x00000074U) /*!< TIMER control register 2 */ + +#define TIMER_CFG(timerx) REG32((timerx) + 0x000000FCU) /*!< TIMER configuration register */ + +/* bits definitions */ +/* TIMER_CTL0 */ +#define TIMER_CTL0_CEN BIT(0) /*!< TIMER counter enable */ +#define TIMER_CTL0_UPDIS BIT(1) /*!< update disable */ +#define TIMER_CTL0_UPS BIT(2) /*!< update source */ +#define TIMER_CTL0_SPM BIT(3) /*!< single pulse mode */ +#define TIMER_CTL0_DIR BIT(4) /*!< timer counter direction */ +#define TIMER_CTL0_CAM BITS(5,6) /*!< center-aligned mode selection */ +#define TIMER_CTL0_ARSE BIT(7) /*!< auto-reload shadow enable */ +#define TIMER_CTL0_CKDIV BITS(8,9) /*!< clock division */ + +/* TIMER_CTL1 */ +#define TIMER_CTL1_CCSE BIT(0) /*!< commutation control shadow enable */ +#define TIMER_CTL1_CCUC BIT(2) /*!< commutation control shadow register update control */ +#define TIMER_CTL1_DMAS BIT(3) /*!< DMA request source selection */ +#define TIMER_CTL1_MMC BITS(4,6) /*!< master mode control */ +#define TIMER_CTL1_TI0S BIT(7) /*!< channel 0 trigger input selection(hall mode selection) */ +#define TIMER_CTL1_ISO0 BIT(8) /*!< idle state of channel 0 output */ +#define TIMER_CTL1_ISO0N BIT(9) /*!< idle state of channel 0 complementary output */ +#define TIMER_CTL1_ISO1 BIT(10) /*!< idle state of channel 1 output */ +#define TIMER_CTL1_ISO1N BIT(11) /*!< idle state of channel 1 complementary output */ +#define TIMER_CTL1_ISO2 BIT(12) /*!< idle state of channel 2 output */ +#define TIMER_CTL1_ISO2N BIT(13) /*!< idle state of channel 2 complementary output */ +#define TIMER_CTL1_ISO3 BIT(14) /*!< idle state of channel 3 output */ +#define TIMER_CTL1_ISO3N BIT(15) /*!< idle state of channel 3 complementary output */ + +/* TIMER_SMCFG */ +#define TIMER_SMCFG_SMC BITS(0,2) /*!< slave mode control */ +#define TIMER_SMCFG_TRGS BITS(4,6) /*!< trigger selection */ +#define TIMER_SMCFG_MSM BIT(7) /*!< master-slave mode */ +#define TIMER_SMCFG_ETFC BITS(8,11) /*!< external trigger filter control */ +#define TIMER_SMCFG_ETPSC BITS(12,13) /*!< external trigger prescaler */ +#define TIMER_SMCFG_SMC1 BIT(14) /*!< part of SMC for enable external clock mode 1 */ +#define TIMER_SMCFG_ETP BIT(15) /*!< external trigger polarity */ + +/* TIMER_DMAINTEN */ +#define TIMER_DMAINTEN_UPIE BIT(0) /*!< update interrupt enable */ +#define TIMER_DMAINTEN_CH0IE BIT(1) /*!< channel 0 capture/compare interrupt enable */ +#define TIMER_DMAINTEN_CH1IE BIT(2) /*!< channel 1 capture/compare interrupt enable */ +#define TIMER_DMAINTEN_CH2IE BIT(3) /*!< channel 2 capture/compare interrupt enable */ +#define TIMER_DMAINTEN_CH3IE BIT(4) /*!< channel 3 capture/compare interrupt enable */ +#define TIMER_DMAINTEN_CMTIE BIT(5) /*!< commutation interrupt request enable */ +#define TIMER_DMAINTEN_TRGIE BIT(6) /*!< trigger interrupt enable */ +#define TIMER_DMAINTEN_BRKIE BIT(7) /*!< break interrupt enable */ +#define TIMER_DMAINTEN_UPDEN BIT(8) /*!< update DMA request enable */ +#define TIMER_DMAINTEN_CH0DEN BIT(9) /*!< channel 0 DMA request enable */ +#define TIMER_DMAINTEN_CH1DEN BIT(10) /*!< channel 1 DMA request enable */ +#define TIMER_DMAINTEN_CH2DEN BIT(11) /*!< channel 2 DMA request enable */ +#define TIMER_DMAINTEN_CH3DEN BIT(12) /*!< channel 3 DMA request enable */ +#define TIMER_DMAINTEN_CMTDEN BIT(13) /*!< commutation DMA request enable */ +#define TIMER_DMAINTEN_TRGDEN BIT(14) /*!< trigger DMA request enable */ +#define TIMER_DMAINTEN_CH0COMADDIE BIT(28) /*!< channel 0 additional compare interrupt enable */ +#define TIMER_DMAINTEN_CH1COMADDIE BIT(29) /*!< channel 1 additional compare interrupt enable */ +#define TIMER_DMAINTEN_CH2COMADDIE BIT(30) /*!< channel 2 additional compare interrupt enable */ +#define TIMER_DMAINTEN_CH3COMADDIE BIT(31) /*!< channel 3 additional compare interrupt enable */ + +/* TIMER_INTF */ +#define TIMER_INTF_UPIF BIT(0) /*!< update interrupt flag */ +#define TIMER_INTF_CH0IF BIT(1) /*!< channel 0 capture/compare interrupt flag */ +#define TIMER_INTF_CH1IF BIT(2) /*!< channel 1 capture/compare interrupt flag */ +#define TIMER_INTF_CH2IF BIT(3) /*!< channel 2 capture/compare interrupt flag */ +#define TIMER_INTF_CH3IF BIT(4) /*!< channel 3 capture/compare interrupt flag */ +#define TIMER_INTF_CMTIF BIT(5) /*!< channel commutation interrupt flag */ +#define TIMER_INTF_TRGIF BIT(6) /*!< trigger interrupt flag */ +#define TIMER_INTF_BRKIF BIT(7) /*!< break interrupt flag */ +#define TIMER_INTF_CH0OF BIT(9) /*!< channel 0 overcapture flag */ +#define TIMER_INTF_CH1OF BIT(10) /*!< channel 1 overcapture flag */ +#define TIMER_INTF_CH2OF BIT(11) /*!< channel 2 overcapture flag */ +#define TIMER_INTF_CH3OF BIT(12) /*!< channel 3 overcapture flag */ +#define TIMER_INTF_CH0COMADDIF BIT(28) /*!< channel 0 additional compare interrupt flag */ +#define TIMER_INTF_CH1COMADDIF BIT(29) /*!< channel 1 additional compare interrupt flag */ +#define TIMER_INTF_CH2COMADDIF BIT(30) /*!< channel 2 additional compare interrupt flag */ +#define TIMER_INTF_CH3COMADDIF BIT(31) /*!< channel 3 additional compare interrupt flag */ + +/* TIMER_SWEVG */ +#define TIMER_SWEVG_UPG BIT(0) /*!< update event generate */ +#define TIMER_SWEVG_CH0G BIT(1) /*!< channel 0 capture or compare event generation */ +#define TIMER_SWEVG_CH1G BIT(2) /*!< channel 1 capture or compare event generation */ +#define TIMER_SWEVG_CH2G BIT(3) /*!< channel 2 capture or compare event generation */ +#define TIMER_SWEVG_CH3G BIT(4) /*!< channel 3 capture or compare event generation */ +#define TIMER_SWEVG_CMTG BIT(5) /*!< channel commutation event generation */ +#define TIMER_SWEVG_TRGG BIT(6) /*!< trigger event generation */ +#define TIMER_SWEVG_BRKG BIT(7) /*!< break event generation */ +#define TIMER_SWEVG_CH0COMADDG BIT(28) /*!< channel 0 additional compare event generation */ +#define TIMER_SWEVG_CH1COMADDG BIT(29) /*!< channel 1 additional compare event generation */ +#define TIMER_SWEVG_CH2COMADDG BIT(30) /*!< channel 2 additional compare event generation */ +#define TIMER_SWEVG_CH3COMADDG BIT(31) /*!< channel 3 additional compare event generation */ + +/* TIMER_CHCTL0 */ +/* output compare mode */ +#define TIMER_CHCTL0_CH0MS BITS(0,1) /*!< channel 0 mode selection */ +#define TIMER_CHCTL0_CH0COMFEN BIT(2) /*!< channel 0 output compare fast enable */ +#define TIMER_CHCTL0_CH0COMSEN BIT(3) /*!< channel 0 output compare shadow enable */ +#define TIMER_CHCTL0_CH0COMCTL BITS(4,6) /*!< channel 0 output compare mode */ +#define TIMER_CHCTL0_CH0COMCEN BIT(7) /*!< channel 0 output compare clear enable */ +#define TIMER_CHCTL0_CH1MS BITS(8,9) /*!< channel 1 mode selection */ +#define TIMER_CHCTL0_CH1COMFEN BIT(10) /*!< channel 1 output compare fast enable */ +#define TIMER_CHCTL0_CH1COMSEN BIT(11) /*!< channel 1 output compare shadow enable */ +#define TIMER_CHCTL0_CH1COMCTL BITS(12,14) /*!< channel 1 output compare mode */ +#define TIMER_CHCTL0_CH1COMCEN BIT(15) /*!< channel 1 output compare clear enable */ +#define TIMER_CHCTL0_CH0COMADDSEN BIT(28) /*!< channel 0 additional compare output shadow enable */ +#define TIMER_CHCTL0_CH1COMADDSEN BIT(29) /*!< channel 1 additional compare output shadow enable */ +/* input capture mode */ +#define TIMER_CHCTL0_CH0CAPPSC BITS(2,3) /*!< channel 0 input capture prescaler */ +#define TIMER_CHCTL0_CH0CAPFLT BITS(4,7) /*!< channel 0 input capture filter control */ +#define TIMER_CHCTL0_CH1CAPPSC BITS(10,11) /*!< channel 1 input capture prescaler */ +#define TIMER_CHCTL0_CH1CAPFLT BITS(12,15) /*!< channel 1 input capture filter control */ + +/* TIMER_CHCTL1 */ +/* output compare mode */ +#define TIMER_CHCTL1_CH2MS BITS(0,1) /*!< channel 2 mode selection */ +#define TIMER_CHCTL1_CH2COMFEN BIT(2) /*!< channel 2 output compare fast enable */ +#define TIMER_CHCTL1_CH2COMSEN BIT(3) /*!< channel 2 output compare shadow enable */ +#define TIMER_CHCTL1_CH2COMCTL BITS(4,6) /*!< channel 2 output compare mode */ +#define TIMER_CHCTL1_CH2COMCEN BIT(7) /*!< channel 2 output compare clear enable */ +#define TIMER_CHCTL1_CH3MS BITS(8,9) /*!< channel 3 mode selection */ +#define TIMER_CHCTL1_CH3COMFEN BIT(10) /*!< channel 3 output compare fast enable */ +#define TIMER_CHCTL1_CH3COMSEN BIT(11) /*!< channel 3 output compare shadow enable */ +#define TIMER_CHCTL1_CH3COMCTL BITS(12,14) /*!< channel 3 output compare mode */ +#define TIMER_CHCTL1_CH3COMCEN BIT(15) /*!< channel 3 output compare clear enable */ +#define TIMER_CHCTL1_CH2COMADDSEN BIT(28) /*!< channel 2 additional compare output shadow enable */ +#define TIMER_CHCTL1_CH3COMADDSEN BIT(29) /*!< channel 3 additional compare output shadow enable */ +/* input capture mode */ +#define TIMER_CHCTL1_CH2CAPPSC BITS(2,3) /*!< channel 2 input capture prescaler */ +#define TIMER_CHCTL1_CH2CAPFLT BITS(4,7) /*!< channel 2 input capture filter control */ +#define TIMER_CHCTL1_CH3CAPPSC BITS(10,11) /*!< channel 3 input capture prescaler */ +#define TIMER_CHCTL1_CH3CAPFLT BITS(12,15) /*!< channel 3 input capture filter control */ + +/* TIMER_CHCTL2 */ +#define TIMER_CHCTL2_CH0EN BIT(0) /*!< channel 0 capture/compare function enable */ +#define TIMER_CHCTL2_CH0P BIT(1) /*!< channel 0 capture/compare function polarity */ +#define TIMER_CHCTL2_CH0NEN BIT(2) /*!< channel 0 complementary output enable */ +#define TIMER_CHCTL2_CH0NP BIT(3) /*!< channel 0 complementary output polarity */ +#define TIMER_CHCTL2_CH1EN BIT(4) /*!< channel 1 capture/compare function enable */ +#define TIMER_CHCTL2_CH1P BIT(5) /*!< channel 1 capture/compare function polarity */ +#define TIMER_CHCTL2_CH1NEN BIT(6) /*!< channel 1 complementary output enable */ +#define TIMER_CHCTL2_CH1NP BIT(7) /*!< channel 1 complementary output polarity */ +#define TIMER_CHCTL2_CH2EN BIT(8) /*!< channel 2 capture/compare function enable */ +#define TIMER_CHCTL2_CH2P BIT(9) /*!< channel 2 capture/compare function polarity */ +#define TIMER_CHCTL2_CH2NEN BIT(10) /*!< channel 2 complementary output enable */ +#define TIMER_CHCTL2_CH2NP BIT(11) /*!< channel 2 complementary output polarity */ +#define TIMER_CHCTL2_CH3EN BIT(12) /*!< channel 3 capture/compare function enable */ +#define TIMER_CHCTL2_CH3P BIT(13) /*!< channel 3 capture/compare function polarity */ +#define TIMER_CHCTL2_CH3NEN BIT(14) /*!< channel 3 complementary output enable */ +#define TIMER_CHCTL2_CH3NP BIT(15) /*!< channel 3 complementary output polarity */ + +/* TIMER_CNT */ +#define TIMER_CNT_CNT16 BITS(0,15) /*!< 16 bit timer counter */ +#define TIMER_CNT_CNT32 BITS(0,31) /*!< 32 bit(TIMER1,TIMER4) timer counter */ + +/* TIMER_PSC */ +#define TIMER_PSC_PSC BITS(0,15) /*!< prescaler value of the counter clock */ + +/* TIMER_CAR */ +#define TIMER_CAR_CARL16 BITS(0,15) /*!< 16 bit counter auto reload value */ +#define TIMER_CAR_CARL32 BITS(0,31) /*!< 32 bit(TIMER1,TIMER4) counter auto reload value */ + +/* TIMER_CREP */ +#define TIMER_CREP_CREP BITS(0,7) /*!< counter repetition value */ + +/* TIMER_CH0CV */ +#define TIMER_CH0CV_CH0VAL16 BITS(0,15) /*!< 16 bit capture/compare value of channel 0 */ +#define TIMER_CH0CV_CH0VAL32 BITS(0,31) /*!< 32 bit(TIMER1,TIMER4) capture/compare value of channel 0 */ + +/* TIMER_CH1CV */ +#define TIMER_CH1CV_CH1VAL16 BITS(0,15) /*!< 16 bit capture/compare value of channel 1 */ +#define TIMER_CH1CV_CH1VAL32 BITS(0,31) /*!< 32 bit(TIMER1,TIMER4) capture/compare value of channel 1 */ + +/* TIMER_CH2CV */ +#define TIMER_CH2CV_CH2VAL16 BITS(0,15) /*!< 16 bit capture/compare value of channel 2 */ +#define TIMER_CH2CV_CH2VAL32 BITS(0,31) /*!< 32 bit(TIMER1,TIMER4) capture/compare value of channel 2 */ + +/* TIMER_CH3CV */ +#define TIMER_CH3CV_CH3VAL16 BITS(0,15) /*!< 16 bit capture/compare value of channel 3 */ +#define TIMER_CH3CV_CH3VAL32 BITS(0,31) /*!< 32 bit(TIMER1,TIMER4) capture/compare value of channel 3 */ + +/* TIMER_CCHP */ +#define TIMER_CCHP_DTCFG BITS(0,7) /*!< dead time configure */ +#define TIMER_CCHP_PROT BITS(8,9) /*!< complementary register protect control */ +#define TIMER_CCHP_IOS BIT(10) /*!< idle mode off-state configure */ +#define TIMER_CCHP_ROS BIT(11) /*!< run mode off-state configure */ +#define TIMER_CCHP_BRKEN BIT(12) /*!< break enable */ +#define TIMER_CCHP_BRKP BIT(13) /*!< break polarity */ +#define TIMER_CCHP_OAEN BIT(14) /*!< output automatic enable */ +#define TIMER_CCHP_POEN BIT(15) /*!< primary output enable */ + +/* TIMER_DMACFG */ +#define TIMER_DMACFG_DMATA BITS(0,4) /*!< DMA transfer access start address */ +#define TIMER_DMACFG_DMATC BITS(8,12) /*!< DMA transfer count */ + +/* TIMER_DMATB */ +#define TIMER_DMATB_DMATB BITS(0,15) /*!< DMA transfer buffer address */ + +/* TIMER_IRMP */ +#define TIMER1_IRMP_ITI1_RMP BITS(10,11) /*!< TIMER1 internal trigger input 1 remap */ +#define TIMER4_IRMP_CI3_RMP BITS(6,7) /*!< TIMER4 channel 3 input remap */ +#define TIMER10_IRMP_ITI1_RMP BITS(0,1) /*!< TIMER10 internal trigger input 1 remap */ + +/* TIMER_CFG */ +#define TIMER_CFG_OUTSEL BIT(0) /*!< the output value selection */ +#define TIMER_CFG_CHVSEL BIT(1) /*!< write CHxVAL register selection */ + +/* TIMER_CH0COMV_ADD */ +#define TIMER_CH0COMV_ADD_CH0COMVAL BITS(0,15) /*!< Additional compare value of channel 0 */ + +/* TIMER_CH1COMV_ADD */ +#define TIMER_CH1COMV_ADD_CH0COMVAL BITS(0,15) /*!< Additional compare value of channel 1 */ + +/* TIMER_CH2COMV_ADD */ +#define TIMER_CH2COMV_ADD_CH0COMVAL BITS(0,15) /*!< Additional compare value of channel 2 */ + +/* TIMER_CH3COMV_ADD */ +#define TIMER_CH3COMV_ADD_CH0COMVAL BITS(0,15) /*!< Additional compare value of channel 3 */ + +/* TIMER_CTL2 */ +#define TIMER_CTL2_CH0CPWMEN BIT(28) /*!< Channel 0 composite PWM mode enable */ +#define TIMER_CTL2_CH1CPWMEN BIT(29) /*!< Channel 1 composite PWM mode enable */ +#define TIMER_CTL2_CH2CPWMEN BIT(30) /*!< Channel 2 composite PWM mode enable */ +#define TIMER_CTL2_CH3CPWMEN BIT(31) /*!< Channel 3 composite PWM mode enable */ + +/* constants definitions */ +/* TIMER init parameter struct definitions*/ +typedef struct { + uint16_t prescaler; /*!< prescaler value */ + uint16_t alignedmode; /*!< aligned mode */ + uint16_t counterdirection; /*!< counter direction */ + uint16_t clockdivision; /*!< clock division value */ + uint32_t period; /*!< period value */ + uint8_t repetitioncounter; /*!< the counter repetition value */ +} timer_parameter_struct; + +/* break parameter struct definitions*/ +typedef struct { + uint16_t runoffstate; /*!< run mode off-state */ + uint16_t ideloffstate; /*!< idle mode off-state */ + uint16_t deadtime; /*!< dead time */ + uint16_t breakpolarity; /*!< break polarity */ + uint16_t outputautostate; /*!< output automatic enable */ + uint16_t protectmode; /*!< complementary register protect control */ + uint16_t breakstate; /*!< break enable */ +} timer_break_parameter_struct; + +/* channel output parameter struct definitions */ +typedef struct { + uint16_t outputstate; /*!< channel output state */ + uint16_t outputnstate; /*!< channel complementary output state */ + uint16_t ocpolarity; /*!< channel output polarity */ + uint16_t ocnpolarity; /*!< channel complementary output polarity */ + uint16_t ocidlestate; /*!< idle state of channel output */ + uint16_t ocnidlestate; /*!< idle state of channel complementary output */ +} timer_oc_parameter_struct; + +/* channel input parameter struct definitions */ +typedef struct { + uint16_t icpolarity; /*!< channel input polarity */ + uint16_t icselection; /*!< channel input mode selection */ + uint16_t icprescaler; /*!< channel input capture prescaler */ + uint16_t icfilter; /*!< channel input capture filter control */ +} timer_ic_parameter_struct; + +/* TIMER interrupt enable or disable */ +#define TIMER_INT_UP TIMER_DMAINTEN_UPIE /*!< update interrupt */ +#define TIMER_INT_CH0 TIMER_DMAINTEN_CH0IE /*!< channel 0 interrupt */ +#define TIMER_INT_CH1 TIMER_DMAINTEN_CH1IE /*!< channel 1 interrupt */ +#define TIMER_INT_CH2 TIMER_DMAINTEN_CH2IE /*!< channel 2 interrupt */ +#define TIMER_INT_CH3 TIMER_DMAINTEN_CH3IE /*!< channel 3 interrupt */ +#define TIMER_INT_CMT TIMER_DMAINTEN_CMTIE /*!< channel commutation interrupt flag */ +#define TIMER_INT_TRG TIMER_DMAINTEN_TRGIE /*!< trigger interrupt */ +#define TIMER_INT_BRK TIMER_DMAINTEN_BRKIE /*!< break interrupt */ +#define TIMER_INT_CH0COMADD TIMER_DMAINTEN_CH0COMADDIE /*!< Channel 0 additional compare interrupt */ +#define TIMER_INT_CH1COMADD TIMER_DMAINTEN_CH1COMADDIE /*!< Channel 1 additional compare interrupt */ +#define TIMER_INT_CH2COMADD TIMER_DMAINTEN_CH2COMADDIE /*!< Channel 2 additional compare interrupt */ +#define TIMER_INT_CH3COMADD TIMER_DMAINTEN_CH3COMADDIE /*!< Channel 3 additional compare interrupt */ + +/* TIMER flag */ +#define TIMER_FLAG_UP TIMER_INTF_UPIF /*!< update flag */ +#define TIMER_FLAG_CH0 TIMER_INTF_CH0IF /*!< channel 0 flag */ +#define TIMER_FLAG_CH1 TIMER_INTF_CH1IF /*!< channel 1 flag */ +#define TIMER_FLAG_CH2 TIMER_INTF_CH2IF /*!< channel 2 flag */ +#define TIMER_FLAG_CH3 TIMER_INTF_CH3IF /*!< channel 3 flag */ +#define TIMER_FLAG_CMT TIMER_INTF_CMTIF /*!< channel commutation flag */ +#define TIMER_FLAG_TRG TIMER_INTF_TRGIF /*!< trigger flag */ +#define TIMER_FLAG_BRK TIMER_INTF_BRKIF /*!< break flag */ +#define TIMER_FLAG_CH0O TIMER_INTF_CH0OF /*!< channel 0 overcapture flag */ +#define TIMER_FLAG_CH1O TIMER_INTF_CH1OF /*!< channel 1 overcapture flag */ +#define TIMER_FLAG_CH2O TIMER_INTF_CH2OF /*!< channel 2 overcapture flag */ +#define TIMER_FLAG_CH3O TIMER_INTF_CH3OF /*!< channel 3 overcapture flag */ +#define TIMER_FLAG_CH0COMADD TIMER_INTF_CH0COMADDIF /*!< Channel 0 additional compare interrupt flag */ +#define TIMER_FLAG_CH1COMADD TIMER_INTF_CH1COMADDIF /*!< Channel 1 additional compare interrupt flag */ +#define TIMER_FLAG_CH2COMADD TIMER_INTF_CH2COMADDIF /*!< Channel 2 additional compare interrupt flag */ +#define TIMER_FLAG_CH3COMADD TIMER_INTF_CH3COMADDIF /*!< Channel 3 additional compare interrupt flag */ + +/* TIMER interrupt flag */ +#define TIMER_INT_FLAG_UP TIMER_INTF_UPIF /*!< update interrupt flag */ +#define TIMER_INT_FLAG_CH0 TIMER_INTF_CH0IF /*!< channel 0 interrupt flag */ +#define TIMER_INT_FLAG_CH1 TIMER_INTF_CH1IF /*!< channel 1 interrupt flag */ +#define TIMER_INT_FLAG_CH2 TIMER_INTF_CH2IF /*!< channel 2 interrupt flag */ +#define TIMER_INT_FLAG_CH3 TIMER_INTF_CH3IF /*!< channel 3 interrupt flag */ +#define TIMER_INT_FLAG_CMT TIMER_INTF_CMTIF /*!< channel commutation interrupt flag */ +#define TIMER_INT_FLAG_TRG TIMER_INTF_TRGIF /*!< trigger interrupt flag */ +#define TIMER_INT_FLAG_BRK TIMER_INTF_BRKIF /*!< break interrupt */ +#define TIMER_INT_FLAG_CH0COMADD TIMER_INT_CH0COMADD /*!< Channel 0 additional compare interrupt */ +#define TIMER_INT_FLAG_CH1COMADD TIMER_INT_CH1COMADD /*!< Channel 1 additional compare interrupt */ +#define TIMER_INT_FLAG_CH2COMADD TIMER_INT_CH2COMADD /*!< Channel 2 additional compare interrupt */ +#define TIMER_INT_FLAG_CH3COMADD TIMER_INT_CH3COMADD /*!< Channel 3 additional compare interrupt */ + +/* TIMER DMA source enable */ +#define TIMER_DMA_UPD ((uint16_t)TIMER_DMAINTEN_UPDEN) /*!< update DMA enable */ +#define TIMER_DMA_CH0D ((uint16_t)TIMER_DMAINTEN_CH0DEN) /*!< channel 0 DMA enable */ +#define TIMER_DMA_CH1D ((uint16_t)TIMER_DMAINTEN_CH1DEN) /*!< channel 1 DMA enable */ +#define TIMER_DMA_CH2D ((uint16_t)TIMER_DMAINTEN_CH2DEN) /*!< channel 2 DMA enable */ +#define TIMER_DMA_CH3D ((uint16_t)TIMER_DMAINTEN_CH3DEN) /*!< channel 3 DMA enable */ +#define TIMER_DMA_CMTD ((uint16_t)TIMER_DMAINTEN_CMTDEN) /*!< commutation DMA request enable */ +#define TIMER_DMA_TRGD ((uint16_t)TIMER_DMAINTEN_TRGDEN) /*!< trigger DMA enable */ + +/* channel DMA request source selection */ +#define TIMER_DMAREQUEST_UPDATEEVENT ((uint8_t)0x00U) /*!< DMA request of channel y is sent when update event occurs */ +#define TIMER_DMAREQUEST_CHANNELEVENT ((uint8_t)0x01U) /*!< DMA request of channel y is sent when channel y event occurs */ + +/* DMA access base address */ +#define DMACFG_DMATA(regval) (BITS(0, 4) & ((uint32_t)(regval) << 0U)) +#define TIMER_DMACFG_DMATA_CTL0 DMACFG_DMATA(0) /*!< DMA transfer address is TIMER_CTL0 */ +#define TIMER_DMACFG_DMATA_CTL1 DMACFG_DMATA(1) /*!< DMA transfer address is TIMER_CTL1 */ +#define TIMER_DMACFG_DMATA_SMCFG DMACFG_DMATA(2) /*!< DMA transfer address is TIMER_SMCFG */ +#define TIMER_DMACFG_DMATA_DMAINTEN DMACFG_DMATA(3) /*!< DMA transfer address is TIMER_DMAINTEN */ +#define TIMER_DMACFG_DMATA_INTF DMACFG_DMATA(4) /*!< DMA transfer address is TIMER_INTF */ +#define TIMER_DMACFG_DMATA_SWEVG DMACFG_DMATA(5) /*!< DMA transfer address is TIMER_SWEVG */ +#define TIMER_DMACFG_DMATA_CHCTL0 DMACFG_DMATA(6) /*!< DMA transfer address is TIMER_CHCTL0 */ +#define TIMER_DMACFG_DMATA_CHCTL1 DMACFG_DMATA(7) /*!< DMA transfer address is TIMER_CHCTL1 */ +#define TIMER_DMACFG_DMATA_CHCTL2 DMACFG_DMATA(8) /*!< DMA transfer address is TIMER_CHCTL2 */ +#define TIMER_DMACFG_DMATA_CNT DMACFG_DMATA(9) /*!< DMA transfer address is TIMER_CNT */ +#define TIMER_DMACFG_DMATA_PSC DMACFG_DMATA(10) /*!< DMA transfer address is TIMER_PSC */ +#define TIMER_DMACFG_DMATA_CAR DMACFG_DMATA(11) /*!< DMA transfer address is TIMER_CAR */ +#define TIMER_DMACFG_DMATA_CREP DMACFG_DMATA(12) /*!< DMA transfer address is TIMER_CREP */ +#define TIMER_DMACFG_DMATA_CH0CV DMACFG_DMATA(13) /*!< DMA transfer address is TIMER_CH0CV */ +#define TIMER_DMACFG_DMATA_CH1CV DMACFG_DMATA(14) /*!< DMA transfer address is TIMER_CH1CV */ +#define TIMER_DMACFG_DMATA_CH2CV DMACFG_DMATA(15) /*!< DMA transfer address is TIMER_CH2CV */ +#define TIMER_DMACFG_DMATA_CH3CV DMACFG_DMATA(16) /*!< DMA transfer address is TIMER_CH3CV */ +#define TIMER_DMACFG_DMATA_CCHP DMACFG_DMATA(17) /*!< DMA transfer address is TIMER_CCHP */ +#define TIMER_DMACFG_DMATA_DMACFG DMACFG_DMATA(18) /*!< DMA transfer address is TIMER_DMACFG */ +#define TIMER_DMACFG_DMATA_DMATB DMACFG_DMATA(19) /*!< DMA transfer address is TIMER_DMATB */ + +/* DMA access burst length */ +#define DMACFG_DMATC(regval) (BITS(8, 12) & ((uint32_t)(regval) << 8U)) +#define TIMER_DMACFG_DMATC_1TRANSFER DMACFG_DMATC(0) /*!< DMA transfer 1 time */ +#define TIMER_DMACFG_DMATC_2TRANSFER DMACFG_DMATC(1) /*!< DMA transfer 2 times */ +#define TIMER_DMACFG_DMATC_3TRANSFER DMACFG_DMATC(2) /*!< DMA transfer 3 times */ +#define TIMER_DMACFG_DMATC_4TRANSFER DMACFG_DMATC(3) /*!< DMA transfer 4 times */ +#define TIMER_DMACFG_DMATC_5TRANSFER DMACFG_DMATC(4) /*!< DMA transfer 5 times */ +#define TIMER_DMACFG_DMATC_6TRANSFER DMACFG_DMATC(5) /*!< DMA transfer 6 times */ +#define TIMER_DMACFG_DMATC_7TRANSFER DMACFG_DMATC(6) /*!< DMA transfer 7 times */ +#define TIMER_DMACFG_DMATC_8TRANSFER DMACFG_DMATC(7) /*!< DMA transfer 8 times */ +#define TIMER_DMACFG_DMATC_9TRANSFER DMACFG_DMATC(8) /*!< DMA transfer 9 times */ +#define TIMER_DMACFG_DMATC_10TRANSFER DMACFG_DMATC(9) /*!< DMA transfer 10 times */ +#define TIMER_DMACFG_DMATC_11TRANSFER DMACFG_DMATC(10) /*!< DMA transfer 11 times */ +#define TIMER_DMACFG_DMATC_12TRANSFER DMACFG_DMATC(11) /*!< DMA transfer 12 times */ +#define TIMER_DMACFG_DMATC_13TRANSFER DMACFG_DMATC(12) /*!< DMA transfer 13 times */ +#define TIMER_DMACFG_DMATC_14TRANSFER DMACFG_DMATC(13) /*!< DMA transfer 14 times */ +#define TIMER_DMACFG_DMATC_15TRANSFER DMACFG_DMATC(14) /*!< DMA transfer 15 times */ +#define TIMER_DMACFG_DMATC_16TRANSFER DMACFG_DMATC(15) /*!< DMA transfer 16 times */ +#define TIMER_DMACFG_DMATC_17TRANSFER DMACFG_DMATC(16) /*!< DMA transfer 17 times */ +#define TIMER_DMACFG_DMATC_18TRANSFER DMACFG_DMATC(17) /*!< DMA transfer 18 times */ + +/* TIMER software event generation source */ +#define TIMER_EVENT_SRC_UPG TIMER_SWEVG_UPG /*!< update event generation */ +#define TIMER_EVENT_SRC_CH0G TIMER_SWEVG_CH0G /*!< channel 0 capture or compare event generation */ +#define TIMER_EVENT_SRC_CH1G TIMER_SWEVG_CH1G /*!< channel 1 capture or compare event generation */ +#define TIMER_EVENT_SRC_CH2G TIMER_SWEVG_CH2G /*!< channel 2 capture or compare event generation */ +#define TIMER_EVENT_SRC_CH3G TIMER_SWEVG_CH3G /*!< channel 3 capture or compare event generation */ +#define TIMER_EVENT_SRC_CMTG TIMER_SWEVG_CMTG /*!< channel commutation event generation */ +#define TIMER_EVENT_SRC_TRGG TIMER_SWEVG_TRGG /*!< trigger event generation */ +#define TIMER_EVENT_SRC_BRKG ((uint16_t)0x0080U) /*!< break event generation */ +#define TIMER_EVENT_SRC_CH0COMADDG TIMER_SWEVG_CH0COMADDG /*!< Channel 0 additional compare event generation */ +#define TIMER_EVENT_SRC_CH1COMADDG TIMER_SWEVG_CH1COMADDG /*!< Channel 1 additional compare event generation */ +#define TIMER_EVENT_SRC_CH2COMADDG TIMER_SWEVG_CH2COMADDG /*!< Channel 2 additional compare event generation */ +#define TIMER_EVENT_SRC_CH3COMADDG TIMER_SWEVG_CH3COMADDG /*!< Channel 3 additional compare event generation */ + +/* center-aligned mode selection */ +#define CTL0_CAM(regval) ((uint16_t)(BITS(5, 6) & ((uint32_t)(regval) << 5U))) +#define TIMER_COUNTER_EDGE CTL0_CAM(0) /*!< edge-aligned mode */ +#define TIMER_COUNTER_CENTER_DOWN CTL0_CAM(1) /*!< center-aligned and counting down assert mode */ +#define TIMER_COUNTER_CENTER_UP CTL0_CAM(2) /*!< center-aligned and counting up assert mode */ +#define TIMER_COUNTER_CENTER_BOTH CTL0_CAM(3) /*!< center-aligned and counting up/down assert mode */ + +/* TIMER prescaler reload mode */ +#define TIMER_PSC_RELOAD_NOW ((uint32_t)0x00000000U) /*!< the prescaler is loaded right now */ +#define TIMER_PSC_RELOAD_UPDATE ((uint32_t)0x00000001U) /*!< the prescaler is loaded at the next update event */ + +/* count direction */ +#define TIMER_COUNTER_UP ((uint16_t)0x0000U) /*!< counter up direction */ +#define TIMER_COUNTER_DOWN ((uint16_t)TIMER_CTL0_DIR) /*!< counter down direction */ + +/* specify division ratio between TIMER clock and dead-time and sampling clock */ +#define CTL0_CKDIV(regval) ((uint16_t)(BITS(8, 9) & ((uint32_t)(regval) << 8U))) +#define TIMER_CKDIV_DIV1 CTL0_CKDIV(0) /*!< clock division value is 1,fDTS=fTIMER_CK */ +#define TIMER_CKDIV_DIV2 CTL0_CKDIV(1) /*!< clock division value is 2,fDTS= fTIMER_CK/2 */ +#define TIMER_CKDIV_DIV4 CTL0_CKDIV(2) /*!< clock division value is 4, fDTS= fTIMER_CK/4 */ + +/* single pulse mode */ +#define TIMER_SP_MODE_SINGLE ((uint32_t)0x00000000U) /*!< single pulse mode */ +#define TIMER_SP_MODE_REPETITIVE ((uint32_t)0x00000001U) /*!< repetitive pulse mode */ + +/* update source */ +#define TIMER_UPDATE_SRC_REGULAR ((uint32_t)0x00000000U) /*!< update generate only by counter overflow/underflow */ +#define TIMER_UPDATE_SRC_GLOBAL ((uint32_t)0x00000001U) /*!< update generate by setting of UPG bit or the counter overflow/underflow,or the slave mode controller trigger */ + +/* run mode off-state configure */ +#define TIMER_ROS_STATE_ENABLE ((uint16_t)TIMER_CCHP_ROS) /*!< when POEN bit is set, the channel output signals (CHx_O/CHx_ON) are enabled, with relationship to CHxEN/CHxNEN bits */ +#define TIMER_ROS_STATE_DISABLE ((uint16_t)0x0000U) /*!< when POEN bit is set, the channel output signals (CHx_O/CHx_ON) are disabled */ + +/* idle mode off-state configure */ +#define TIMER_IOS_STATE_ENABLE ((uint16_t)TIMER_CCHP_IOS) /*!< when POEN bit is reset, the channel output signals (CHx_O/CHx_ON) are enabled, with relationship to CHxEN/CHxNEN bits */ +#define TIMER_IOS_STATE_DISABLE ((uint16_t)0x0000U) /*!< when POEN bit is reset, the channel output signals (CHx_O/CHx_ON) are disabled */ + +/* break input polarity */ +#define TIMER_BREAK_POLARITY_LOW ((uint16_t)0x0000U) /*!< break input polarity is low */ +#define TIMER_BREAK_POLARITY_HIGH ((uint16_t)TIMER_CCHP_BRKP) /*!< break input polarity is high */ + +/* output automatic enable */ +#define TIMER_OUTAUTO_ENABLE ((uint16_t)TIMER_CCHP_OAEN) /*!< output automatic enable */ +#define TIMER_OUTAUTO_DISABLE ((uint16_t)0x0000U) /*!< output automatic disable */ + +/* complementary register protect control */ +#define CCHP_PROT(regval) ((uint16_t)(BITS(8, 9) & ((uint32_t)(regval) << 8U))) +#define TIMER_CCHP_PROT_OFF CCHP_PROT(0) /*!< protect disable */ +#define TIMER_CCHP_PROT_0 CCHP_PROT(1) /*!< PROT mode 0 */ +#define TIMER_CCHP_PROT_1 CCHP_PROT(2) /*!< PROT mode 1 */ +#define TIMER_CCHP_PROT_2 CCHP_PROT(3) /*!< PROT mode 2 */ + +/* break input enable */ +#define TIMER_BREAK_ENABLE ((uint16_t)TIMER_CCHP_BRKEN) /*!< break input enable */ +#define TIMER_BREAK_DISABLE ((uint16_t)0x0000U) /*!< break input disable */ + +/* TIMER channel n(n=0,1,2,3) */ +#define TIMER_CH_0 ((uint16_t)0x0000U) /*!< TIMER channel 0(TIMERx(x=0..4,7..13)) */ +#define TIMER_CH_1 ((uint16_t)0x0001U) /*!< TIMER channel 1(TIMERx(x=0..4,7,8,11)) */ +#define TIMER_CH_2 ((uint16_t)0x0002U) /*!< TIMER channel 2(TIMERx(x=0..4,7)) */ +#define TIMER_CH_3 ((uint16_t)0x0003U) /*!< TIMER channel 3(TIMERx(x=0..4,7)) */ + +/* channel enable state*/ +#define TIMER_CCX_ENABLE ((uint32_t)0x00000001U) /*!< channel enable */ +#define TIMER_CCX_DISABLE ((uint32_t)0x00000000U) /*!< channel disable */ + +/* channel complementary output enable state*/ +#define TIMER_CCXN_ENABLE ((uint16_t)0x0004U) /*!< channel complementary enable */ +#define TIMER_CCXN_DISABLE ((uint16_t)0x0000U) /*!< channel complementary disable */ + +/* channel output polarity */ +#define TIMER_OC_POLARITY_HIGH ((uint16_t)0x0000U) /*!< channel output polarity is high */ +#define TIMER_OC_POLARITY_LOW ((uint16_t)0x0002U) /*!< channel output polarity is low */ + +/* channel complementary output polarity */ +#define TIMER_OCN_POLARITY_HIGH ((uint16_t)0x0000U) /*!< channel complementary output polarity is high */ +#define TIMER_OCN_POLARITY_LOW ((uint16_t)0x0008U) /*!< channel complementary output polarity is low */ + +/* idle state of channel output */ +#define TIMER_OC_IDLE_STATE_HIGH ((uint16_t)0x0100) /*!< idle state of channel output is high */ +#define TIMER_OC_IDLE_STATE_LOW ((uint16_t)0x0000) /*!< idle state of channel output is low */ + +/* idle state of channel complementary output */ +#define TIMER_OCN_IDLE_STATE_HIGH ((uint16_t)0x0200U) /*!< idle state of channel complementary output is high */ +#define TIMER_OCN_IDLE_STATE_LOW ((uint16_t)0x0000U) /*!< idle state of channel complementary output is low */ + +/* channel output compare mode */ +#define TIMER_OC_MODE_TIMING ((uint16_t)0x0000U) /*!< timing mode */ +#define TIMER_OC_MODE_ACTIVE ((uint16_t)0x0010U) /*!< active mode */ +#define TIMER_OC_MODE_INACTIVE ((uint16_t)0x0020U) /*!< inactive mode */ +#define TIMER_OC_MODE_TOGGLE ((uint16_t)0x0030U) /*!< toggle mode */ +#define TIMER_OC_MODE_LOW ((uint16_t)0x0040U) /*!< force low mode */ +#define TIMER_OC_MODE_HIGH ((uint16_t)0x0050U) /*!< force high mode */ +#define TIMER_OC_MODE_PWM0 ((uint16_t)0x0060U) /*!< PWM0 mode */ +#define TIMER_OC_MODE_PWM1 ((uint16_t)0x0070U) /*!< PWM1 mode*/ + +/* channel output compare shadow enable */ +#define TIMER_OC_SHADOW_ENABLE ((uint16_t)0x0008U) /*!< channel output shadow state enable */ +#define TIMER_OC_SHADOW_DISABLE ((uint16_t)0x0000U) /*!< channel output shadow state disable */ + +/* channel output compare fast enable */ +#define TIMER_OC_FAST_ENABLE ((uint16_t)0x0004) /*!< channel output fast function enable */ +#define TIMER_OC_FAST_DISABLE ((uint16_t)0x0000) /*!< channel output fast function disable */ + +/* channel output compare clear enable */ +#define TIMER_OC_CLEAR_ENABLE ((uint16_t)0x0080U) /*!< channel output clear function enable */ +#define TIMER_OC_CLEAR_DISABLE ((uint16_t)0x0000U) /*!< channel output clear function disable */ + +/* channel control shadow register update control */ +#define TIMER_UPDATECTL_CCU ((uint32_t)0x00000000U) /*!< the shadow registers are updated when CMTG bit is set */ +#define TIMER_UPDATECTL_CCUTRI ((uint32_t)0x00000001U) /*!< the shadow registers update by when CMTG bit is set or an rising edge of TRGI occurs */ + +/* channel input capture polarity */ +#define TIMER_IC_POLARITY_RISING ((uint16_t)0x0000U) /*!< input capture rising edge */ +#define TIMER_IC_POLARITY_FALLING ((uint16_t)0x0002U) /*!< input capture falling edge */ +#define TIMER_IC_POLARITY_BOTH_EDGE ((uint16_t)0x000AU) /*!< input capture both edge */ + +/* TIMER input capture selection */ +#define TIMER_IC_SELECTION_DIRECTTI ((uint16_t)0x0001U) /*!< channel y is configured as input and icy is mapped on CIy */ +#define TIMER_IC_SELECTION_INDIRECTTI ((uint16_t)0x0002U) /*!< channel y is configured as input and icy is mapped on opposite input */ +#define TIMER_IC_SELECTION_ITS ((uint16_t)0x0003U) /*!< channel y is configured as input and icy is mapped on ITS */ + +/* channel input capture prescaler */ +#define TIMER_IC_PSC_DIV1 ((uint16_t)0x0000U) /*!< no prescaler */ +#define TIMER_IC_PSC_DIV2 ((uint16_t)0x0004U) /*!< divided by 2 */ +#define TIMER_IC_PSC_DIV4 ((uint16_t)0x0008U) /*!< divided by 4*/ +#define TIMER_IC_PSC_DIV8 ((uint16_t)0x000CU) /*!< divided by 8 */ + +/* trigger selection */ +#define SMCFG_TRGSEL(regval) (BITS(4, 6) & ((uint32_t)(regval) << 4U)) +#define TIMER_SMCFG_TRGSEL_ITI0 SMCFG_TRGSEL(0) /*!< internal trigger 0 */ +#define TIMER_SMCFG_TRGSEL_ITI1 SMCFG_TRGSEL(1) /*!< internal trigger 1 */ +#define TIMER_SMCFG_TRGSEL_ITI2 SMCFG_TRGSEL(2) /*!< internal trigger 2 */ +#define TIMER_SMCFG_TRGSEL_ITI3 SMCFG_TRGSEL(3) /*!< internal trigger 3 */ +#define TIMER_SMCFG_TRGSEL_CI0F_ED SMCFG_TRGSEL(4) /*!< TI0 Edge Detector */ +#define TIMER_SMCFG_TRGSEL_CI0FE0 SMCFG_TRGSEL(5) /*!< filtered TIMER input 0 */ +#define TIMER_SMCFG_TRGSEL_CI1FE1 SMCFG_TRGSEL(6) /*!< filtered TIMER input 1 */ +#define TIMER_SMCFG_TRGSEL_ETIFP SMCFG_TRGSEL(7) /*!< external trigger */ + +/* master mode control */ +#define CTL1_MMC(regval) (BITS(4, 6) & ((uint32_t)(regval) << 4U)) +#define TIMER_TRI_OUT_SRC_RESET CTL1_MMC(0) /*!< the UPG bit as trigger output */ +#define TIMER_TRI_OUT_SRC_ENABLE CTL1_MMC(1) /*!< the counter enable signal TIMER_CTL0_CEN as trigger output */ +#define TIMER_TRI_OUT_SRC_UPDATE CTL1_MMC(2) /*!< update event as trigger output */ +#define TIMER_TRI_OUT_SRC_CH0 CTL1_MMC(3) /*!< a capture or a compare match occurred in channal0 as trigger output TRGO */ +#define TIMER_TRI_OUT_SRC_O0CPRE CTL1_MMC(4) /*!< O0CPRE as trigger output */ +#define TIMER_TRI_OUT_SRC_O1CPRE CTL1_MMC(5) /*!< O1CPRE as trigger output */ +#define TIMER_TRI_OUT_SRC_O2CPRE CTL1_MMC(6) /*!< O2CPRE as trigger output */ +#define TIMER_TRI_OUT_SRC_O3CPRE CTL1_MMC(7) /*!< O3CPRE as trigger output */ + +/* slave mode control */ +#define SMCFG_SMC(regval) (BITS(0, 2) & ((uint32_t)(regval) << 0U)) +#define TIMER_SLAVE_MODE_DISABLE SMCFG_SMC(0) /*!< slave mode disable */ +#define TIMER_ENCODER_MODE0 SMCFG_SMC(1) /*!< encoder mode 0 */ +#define TIMER_ENCODER_MODE1 SMCFG_SMC(2) /*!< encoder mode 1 */ +#define TIMER_ENCODER_MODE2 SMCFG_SMC(3) /*!< encoder mode 2 */ +#define TIMER_SLAVE_MODE_RESTART SMCFG_SMC(4) /*!< restart mode */ +#define TIMER_SLAVE_MODE_PAUSE SMCFG_SMC(5) /*!< pause mode */ +#define TIMER_SLAVE_MODE_EVENT SMCFG_SMC(6) /*!< event mode */ +#define TIMER_SLAVE_MODE_EXTERNAL0 SMCFG_SMC(7) /*!< external clock mode 0 */ + +/* master slave mode selection */ +#define TIMER_MASTER_SLAVE_MODE_ENABLE ((uint32_t)0x00000000U) /*!< master slave mode enable */ +#define TIMER_MASTER_SLAVE_MODE_DISABLE ((uint32_t)0x00000001U) /*!< master slave mode disable */ + +/* external trigger prescaler */ +#define SMCFG_ETPSC(regval) (BITS(12, 13) & ((uint32_t)(regval) << 12U)) +#define TIMER_EXT_TRI_PSC_OFF SMCFG_ETPSC(0) /*!< no divided */ +#define TIMER_EXT_TRI_PSC_DIV2 SMCFG_ETPSC(1) /*!< divided by 2 */ +#define TIMER_EXT_TRI_PSC_DIV4 SMCFG_ETPSC(2) /*!< divided by 4 */ +#define TIMER_EXT_TRI_PSC_DIV8 SMCFG_ETPSC(3) /*!< divided by 8 */ + +/* external trigger polarity */ +#define TIMER_ETP_FALLING TIMER_SMCFG_ETP /*!< active low or falling edge active */ +#define TIMER_ETP_RISING ((uint32_t)0x00000000U) /*!< active high or rising edge active */ + +/* channel 0 trigger input selection */ +#define TIMER_HALLINTERFACE_ENABLE ((uint32_t)0x00000000U) /*!< TIMER hall sensor mode enable */ +#define TIMER_HALLINTERFACE_DISABLE ((uint32_t)0x00000001U) /*!< TIMER hall sensor mode disable */ + +/* timer1 internal trigger input1 remap */ +#define TIMER1_IRMP(regval) (BITS(10, 11) & ((uint32_t)(regval) << 10U)) +#define TIMER1_ITI1_RMP_TIMER7_TRGO TIMER1_IRMP(0) /*!< timer1 internal trigger input 1 remap to TIMER7_TRGO */ +#define TIMER1_ITI1_RMP_ETHERNET_PTP TIMER1_IRMP(1) /*!< timer1 internal trigger input 1 remap to ethernet PTP */ +#define TIMER1_ITI1_RMP_USB_FS_SOF TIMER1_IRMP(2) /*!< timer1 internal trigger input 1 remap to USB FS SOF */ +#define TIMER1_ITI1_RMP_USB_HS_SOF TIMER1_IRMP(3) /*!< timer1 internal trigger input 1 remap to USB HS SOF */ + +/* timer4 channel 3 input remap */ +#define TIMER4_IRMP(regval) (BITS(6, 7) & ((uint32_t)(regval) << 6U)) +#define TIMER4_CI3_RMP_GPIO TIMER4_IRMP(0) /*!< timer4 channel 3 input remap to GPIO pin */ +#define TIMER4_CI3_RMP_IRC32K TIMER4_IRMP(1) /*!< timer4 channel 3 input remap to IRC32K */ +#define TIMER4_CI3_RMP_LXTAL TIMER4_IRMP(2) /*!< timer4 channel 3 input remap to LXTAL */ +#define TIMER4_CI3_RMP_RTC_WAKEUP_INT TIMER4_IRMP(3) /*!< timer4 channel 3 input remap to RTC wakeup interrupt */ + +/* timer10 internal trigger input1 remap */ +#define TIMER10_IRMP(regval) (BITS(0, 1) & ((uint32_t)(regval) << 0U)) +#define TIMER10_ITI1_RMP_GPIO TIMER10_IRMP(0) /*!< timer10 internal trigger input1 remap based on GPIO setting */ +#define TIMER10_ITI1_RMP_RTC_HXTAL_DIV TIMER10_IRMP(2) /*!< timer10 internal trigger input1 remap HXTAL _DIV(clock used for RTC which is HXTAL clock divided by RTCDIV bits in RCU_CFG0 register) */ + +/* timerx(x=0,1,2,13,14,15,16) write cc register selection */ +#define TIMER_CHVSEL_ENABLE ((uint16_t)TIMER_CFG_CHVSEL) /*!< write CHxVAL register selection enable */ +#define TIMER_CHVSEL_DISABLE ((uint16_t)0x0000U) /*!< write CHxVAL register selection disable */ + +/* TIMER output value selection enable */ +#define TIMER_OUTSEL_ENABLE ((uint16_t)TIMER_CFG_OUTSEL) /*!< output value selection enable */ +#define TIMER_OUTSEL_DISABLE ((uint16_t)0x0000U) /*!< output value selection disable */ + +/* channel additional output compare shadow enable */ +#define TIMER_CH0_ADD_SHADOW_ENABLE ((uint32_t)0x10000000U) /*!< channel 0 additional output shadow state enable */ +#define TIMER_CH1_ADD_SHADOW_ENABLE ((uint32_t)0x20000000U) /*!< channel 1 additional output shadow state enable */ +#define TIMER_CH2_ADD_SHADOW_ENABLE ((uint32_t)0x10000000U) /*!< channel 2 additional output shadow state enable */ +#define TIMER_CH3_ADD_SHADOW_ENABLE ((uint32_t)0x20000000U) /*!< channel 3 additional output shadow state enable */ + +/* channel additional output compare shadow enable */ +#define TIMER_ADD_SHADOW_ENABLE ((uint16_t)0x0001U) /*!< channel additional output shadow state enable */ +#define TIMER_ADD_SHADOW_DISABLE ((uint16_t)0x0000U) /*!< channel additional output shadow state disable */ + +/* function declarations */ +/* TIMER timebase */ +/* deinit a TIMER */ +void timer_deinit(uint32_t timer_periph); +/* initialize TIMER init parameter struct */ +void timer_struct_para_init(timer_parameter_struct *initpara); +/* initialize TIMER counter */ +void timer_init(uint32_t timer_periph, timer_parameter_struct *initpara); +/* enable a TIMER */ +void timer_enable(uint32_t timer_periph); +/* disable a TIMER */ +void timer_disable(uint32_t timer_periph); +/* enable the auto reload shadow function */ +void timer_auto_reload_shadow_enable(uint32_t timer_periph); +/* disable the auto reload shadow function */ +void timer_auto_reload_shadow_disable(uint32_t timer_periph); +/* enable the update event */ +void timer_update_event_enable(uint32_t timer_periph); +/* disable the update event */ +void timer_update_event_disable(uint32_t timer_periph); +/* set TIMER counter alignment mode */ +void timer_counter_alignment(uint32_t timer_periph, uint16_t aligned); +/* set TIMER counter up direction */ +void timer_counter_up_direction(uint32_t timer_periph); +/* set TIMER counter down direction */ +void timer_counter_down_direction(uint32_t timer_periph); +/* configure TIMER prescaler */ +void timer_prescaler_config(uint32_t timer_periph, uint16_t prescaler, uint8_t pscreload); +/* configure TIMER repetition register value */ +void timer_repetition_value_config(uint32_t timer_periph, uint16_t repetition); +/* configure TIMER autoreload register value */ +void timer_autoreload_value_config(uint32_t timer_periph, uint32_t autoreload); +/* configure TIMER counter register value */ +void timer_counter_value_config(uint32_t timer_periph, uint32_t counter); +/* read TIMER counter value */ +uint32_t timer_counter_read(uint32_t timer_periph); +/* read TIMER prescaler value */ +uint16_t timer_prescaler_read(uint32_t timer_periph); +/* configure TIMER single pulse mode */ +void timer_single_pulse_mode_config(uint32_t timer_periph, uint32_t spmode); +/* configure TIMER update source */ +void timer_update_source_config(uint32_t timer_periph, uint32_t update); + +/* TIMER DMA and event */ +/* enable the TIMER DMA */ +void timer_dma_enable(uint32_t timer_periph, uint16_t dma); +/* disable the TIMER DMA */ +void timer_dma_disable(uint32_t timer_periph, uint16_t dma); +/* channel DMA request source selection */ +void timer_channel_dma_request_source_select(uint32_t timer_periph, uint8_t dma_request); +/* configure the TIMER DMA transfer */ +void timer_dma_transfer_config(uint32_t timer_periph, uint32_t dma_baseaddr, uint32_t dma_lenth); +/* software generate events */ +void timer_event_software_generate(uint32_t timer_periph, uint16_t event); + +/* TIMER channel complementary protection */ +/* initialize TIMER break parameter struct */ +void timer_break_struct_para_init(timer_break_parameter_struct *breakpara); +/* configure TIMER break function */ +void timer_break_config(uint32_t timer_periph, timer_break_parameter_struct *breakpara); +/* enable TIMER break function */ +void timer_break_enable(uint32_t timer_periph); +/* disable TIMER break function */ +void timer_break_disable(uint32_t timer_periph); +/* enable TIMER output automatic function */ +void timer_automatic_output_enable(uint32_t timer_periph); +/* disable TIMER output automatic function */ +void timer_automatic_output_disable(uint32_t timer_periph); +/* enable or disable TIMER primary output function */ +void timer_primary_output_config(uint32_t timer_periph, ControlStatus newvalue); +/* enable or disable channel capture/compare control shadow register */ +void timer_channel_control_shadow_config(uint32_t timer_periph, ControlStatus newvalue); +/* configure TIMER channel control shadow register update control */ +void timer_channel_control_shadow_update_config(uint32_t timer_periph, uint8_t ccuctl); + +/* TIMER channel output */ +/* initialize TIMER channel output parameter struct */ +void timer_channel_output_struct_para_init(timer_oc_parameter_struct *ocpara); +/* configure TIMER channel output function */ +void timer_channel_output_config(uint32_t timer_periph, uint16_t channel, + timer_oc_parameter_struct *ocpara); +/* configure TIMER channel output compare mode */ +void timer_channel_output_mode_config(uint32_t timer_periph, uint16_t channel, uint16_t ocmode); +/* configure TIMER channel output pulse value */ +void timer_channel_output_pulse_value_config(uint32_t timer_periph, uint16_t channel, + uint32_t pulse); +/* configure TIMER channel output shadow function */ +void timer_channel_output_shadow_config(uint32_t timer_periph, uint16_t channel, uint16_t ocshadow); +/* configure TIMER channel output fast function */ +void timer_channel_output_fast_config(uint32_t timer_periph, uint16_t channel, uint16_t ocfast); +/* configure TIMER channel output clear function */ +void timer_channel_output_clear_config(uint32_t timer_periph, uint16_t channel, uint16_t occlear); +/* configure TIMER channel output polarity */ +void timer_channel_output_polarity_config(uint32_t timer_periph, uint16_t channel, + uint16_t ocpolarity); +/* configure TIMER channel complementary output polarity */ +void timer_channel_complementary_output_polarity_config(uint32_t timer_periph, uint16_t channel, + uint16_t ocnpolarity); +/* configure TIMER channel enable state */ +void timer_channel_output_state_config(uint32_t timer_periph, uint16_t channel, uint32_t state); +/* configure TIMER channel complementary output enable state */ +void timer_channel_complementary_output_state_config(uint32_t timer_periph, uint16_t channel, + uint16_t ocnstate); + +/* TIMER channel input */ +/* initialize TIMER channel input parameter struct */ +void timer_channel_input_struct_para_init(timer_ic_parameter_struct *icpara); +/* configure TIMER input capture parameter */ +void timer_input_capture_config(uint32_t timer_periph, uint16_t channel, + timer_ic_parameter_struct *icpara); +/* configure TIMER channel input capture prescaler value */ +void timer_channel_input_capture_prescaler_config(uint32_t timer_periph, uint16_t channel, + uint16_t prescaler); +/* read TIMER channel capture compare register value */ +uint32_t timer_channel_capture_value_register_read(uint32_t timer_periph, uint16_t channel); +/* configure TIMER input pwm capture function */ +void timer_input_pwm_capture_config(uint32_t timer_periph, uint16_t channel, + timer_ic_parameter_struct *icpwm); +/* configure TIMER hall sensor mode */ +void timer_hall_mode_config(uint32_t timer_periph, uint32_t hallmode); + +/* TIMER master and slave */ +/* select TIMER input trigger source */ +void timer_input_trigger_source_select(uint32_t timer_periph, uint32_t intrigger); +/* select TIMER master mode output trigger source */ +void timer_master_output_trigger_source_select(uint32_t timer_periph, uint32_t outrigger); +/* select TIMER slave mode */ +void timer_slave_mode_select(uint32_t timer_periph, uint32_t slavemode); +/* configure TIMER master slave mode */ +void timer_master_slave_mode_config(uint32_t timer_periph, uint32_t masterslave); +/* configure TIMER external trigger input */ +void timer_external_trigger_config(uint32_t timer_periph, uint32_t extprescaler, + uint32_t extpolarity, uint32_t extfilter); +/* configure TIMER quadrature decoder mode */ +void timer_quadrature_decoder_mode_config(uint32_t timer_periph, uint32_t decomode, + uint16_t ic0polarity, uint16_t ic1polarity); +/* configure TIMER internal clock mode */ +void timer_internal_clock_config(uint32_t timer_periph); +/* configure TIMER the internal trigger as external clock input */ +void timer_internal_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t intrigger); +/* configure TIMER the external trigger as external clock input */ +void timer_external_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t extrigger, + uint16_t extpolarity, uint32_t extfilter); +/* configure TIMER the external clock mode 0 */ +void timer_external_clock_mode0_config(uint32_t timer_periph, uint32_t extprescaler, + uint32_t extpolarity, uint32_t extfilter); +/* configure TIMER the external clock mode 1 */ +void timer_external_clock_mode1_config(uint32_t timer_periph, uint32_t extprescaler, + uint32_t extpolarity, uint32_t extfilter); +/* disable TIMER the external clock mode 1 */ +void timer_external_clock_mode1_disable(uint32_t timer_periph); +/* configure TIMER channel remap function */ +void timer_channel_remap_config(uint32_t timer_periph, uint32_t remap); + +/* TIMER configure */ +/* configure TIMER write CHxVAL register selection */ +void timer_write_chxval_register_config(uint32_t timer_periph, uint16_t ccsel); +/* configure TIMER output value selection */ +void timer_output_value_selection_config(uint32_t timer_periph, uint16_t outsel); + +/* TIMER composite pwm */ +/* enable the TIMER composite pwm */ +void timer_channel_composite_pwm_enable(uint32_t timer_periph, uint32_t channel); +/* disable the TIMER composite pwm */ +void timer_channel_composite_pwm_disable(uint32_t timer_periph, uint32_t channel); + +/* configure TIMER channel additional compare value */ +void timer_channel_additional_compare_value_config(uint32_t timer_periph, uint16_t channel, + uint32_t value); +/* configure TIMER channel additional output shadow function */ +void timer_channel_additional_output_shadow_config(uint32_t timer_periph, uint16_t channel, + uint16_t ocshadow); +/* get TIMER channel additional compare value */ +uint32_t timer_channel_additional_compare_value_read(uint32_t timer_periph, uint16_t channel); + +/* TIMER interrupt and flag*/ +/* get TIMER flags */ +FlagStatus timer_flag_get(uint32_t timer_periph, uint32_t flag); +/* clear TIMER flags */ +void timer_flag_clear(uint32_t timer_periph, uint32_t flag); +/* enable the TIMER interrupt */ +void timer_interrupt_enable(uint32_t timer_periph, uint32_t interrupt); +/* disable the TIMER interrupt */ +void timer_interrupt_disable(uint32_t timer_periph, uint32_t interrupt); +/* get TIMER interrupt flag */ +FlagStatus timer_interrupt_flag_get(uint32_t timer_periph, uint32_t interrupt); +/* clear TIMER interrupt flag */ +void timer_interrupt_flag_clear(uint32_t timer_periph, uint32_t interrupt); + +#endif /* GD32F5XX_TIMER_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_tli.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_tli.h new file mode 100644 index 0000000..5eb4d43 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_tli.h @@ -0,0 +1,370 @@ +/*! + \file gd32f5xx_tli.h + \brief definitions for the TLI + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_TLI_H +#define GD32F5XX_TLI_H + +#include "gd32f5xx.h" + +/* TLI definitions */ +#define TLI TLI_BASE /*!< TLI base address */ +/* TLI layer definitions */ +#define LAYER0 TLI_BASE /*!< TLI layer0 base address */ +#define LAYER1 (TLI_BASE + 0x00000080U) /*!< TLI layer1 base address */ + +/* registers definitions */ +#define TLI_SPSZ REG32(TLI + 0x00000008U) /*!< TLI synchronous pulse size register */ +#define TLI_BPSZ REG32(TLI + 0x0000000CU) /*!< TLI back-porch size register */ +#define TLI_ASZ REG32(TLI + 0x00000010U) /*!< TLI active size register */ +#define TLI_TSZ REG32(TLI + 0x00000014U) /*!< TLI total size register */ +#define TLI_CTL REG32(TLI + 0x00000018U) /*!< TLI control register */ +#define TLI_RL REG32(TLI + 0x00000024U) /*!< TLI reload Layer register */ +#define TLI_BGC REG32(TLI + 0x0000002CU) /*!< TLI background color register */ +#define TLI_INTEN REG32(TLI + 0x00000034U) /*!< TLI interrupt enable register */ +#define TLI_INTF REG32(TLI + 0x00000038U) /*!< TLI interrupt flag register */ +#define TLI_INTC REG32(TLI + 0x0000003CU) /*!< TLI interrupt flag clear register */ +#define TLI_LM REG32(TLI + 0x00000040U) /*!< TLI line mark register */ +#define TLI_CPPOS REG32(TLI + 0x00000044U) /*!< TLI current pixel position register */ +#define TLI_STAT REG32(TLI + 0x00000048U) /*!< TLI status register */ +#define TLI_LxCTL(layerx) REG32((layerx) + 0x00000084U) /*!< TLI layer x control register */ +#define TLI_LxHPOS(layerx) REG32((layerx) + 0x00000088U) /*!< TLI layer x horizontal position parameters register */ +#define TLI_LxVPOS(layerx) REG32((layerx) + 0x0000008CU) /*!< TLI layer x vertical position parameters register */ +#define TLI_LxCKEY(layerx) REG32((layerx) + 0x00000090U) /*!< TLI layer x color key register */ +#define TLI_LxPPF(layerx) REG32((layerx) + 0x00000094U) /*!< TLI layer x packeted pixel format register */ +#define TLI_LxSA(layerx) REG32((layerx) + 0x00000098U) /*!< TLI layer x specified alpha register */ +#define TLI_LxDC(layerx) REG32((layerx) + 0x0000009CU) /*!< TLI layer x default color register */ +#define TLI_LxBLEND(layerx) REG32((layerx) + 0x000000A0U) /*!< TLI layer x blending register */ +#define TLI_LxFBADDR(layerx) REG32((layerx) + 0x000000ACU) /*!< TLI layer x frame base address register */ +#define TLI_LxFLLEN(layerx) REG32((layerx) + 0x000000B0U) /*!< TLI layer x frame line length register */ +#define TLI_LxFTLN(layerx) REG32((layerx) + 0x000000B4U) /*!< TLI layer x frame total line number register */ +#define TLI_LxLUT(layerx) REG32((layerx) + 0x000000C4U) /*!< TLI layer x look up table register */ + +/* bits definitions */ +/* TLI_SPSZ */ +#define TLI_SPSZ_VPSZ BITS(0,11) /*!< size of the vertical synchronous pulse */ +#define TLI_SPSZ_HPSZ BITS(16,27) /*!< size of the horizontal synchronous pulse */ + +/* TLI_BPSZ */ +#define TLI_BPSZ_VBPSZ BITS(0,11) /*!< size of the vertical back porch plus synchronous pulse */ +#define TLI_BPSZ_HBPSZ BITS(16,27) /*!< size of the horizontal back porch plus synchronous pulse */ + +/* TLI_ASZ */ +#define TLI_ASZ_VASZ BITS(0,11) /*!< size of the vertical active area width plus back porch and synchronous pulse */ +#define TLI_ASZ_HASZ BITS(16,27) /*!< size of the horizontal active area width plus back porch and synchronous pulse */ + +/* TLI_SPSZ */ +#define TLI_TSZ_VTSZ BITS(0,11) /*!< vertical total size of the display, including active area, back porch, synchronous pulse and front porch */ +#define TLI_TSZ_HTSZ BITS(16,27) /*!< horizontal total size of the display, including active area, back porch, synchronous pulse and front porch */ + +/* TLI_CTL */ +#define TLI_CTL_TLIEN BIT(0) /*!< TLI enable bit */ +#define TLI_CTL_BDB BITS(4,6) /*!< blue channel dither bits number */ +#define TLI_CTL_GDB BITS(8,10) /*!< green channel dither bits number */ +#define TLI_CTL_RDB BITS(12,14) /*!< red channel dither bits number */ +#define TLI_CTL_DFEN BIT(16) /*!< dither function enable */ +#define TLI_CTL_CLKPS BIT(28) /*!< pixel clock polarity selection */ +#define TLI_CTL_DEPS BIT(29) /*!< data enable polarity selection */ +#define TLI_CTL_VPPS BIT(30) /*!< vertical pulse polarity selection */ +#define TLI_CTL_HPPS BIT(31) /*!< horizontal pulse polarity selection */ + +/* TLI_RL */ +#define TLI_RL_RQR BIT(0) /*!< request reload */ +#define TLI_RL_FBR BIT(1) /*!< frame blank reload */ + +/* TLI_BGC */ +#define TLI_BGC_BVB BITS(0,7) /*!< background value blue */ +#define TLI_BGC_BVG BITS(8,15) /*!< background value green */ +#define TLI_BGC_BVR BITS(16,23) /*!< background value red */ + +/* TLI_INTEN */ +#define TLI_INTEN_LMIE BIT(0) /*!< line mark interrupt enable */ +#define TLI_INTEN_FEIE BIT(1) /*!< FIFO error interrupt enable */ +#define TLI_INTEN_TEIE BIT(2) /*!< transaction error interrupt enable */ +#define TLI_INTEN_LCRIE BIT(3) /*!< layer configuration reloaded interrupt enable */ + +/* TLI_INTF */ +#define TLI_INTF_LMF BIT(0) /*!< line mark flag */ +#define TLI_INTF_FEF BIT(1) /*!< FIFO error flag */ +#define TLI_INTF_TEF BIT(2) /*!< transaction error flag */ +#define TLI_INTF_LCRF BIT(3) /*!< layer configuration reloaded flag */ + +/* TLI_INTC */ +#define TLI_INTC_LMC BIT(0) /*!< line mark flag clear */ +#define TLI_INTC_FEC BIT(1) /*!< FIFO error flag clear */ +#define TLI_INTC_TEC BIT(2) /*!< transaction error flag clear */ +#define TLI_INTC_LCRC BIT(3) /*!< layer configuration reloaded flag clear */ + +/* TLI_LM */ +#define TLI_LM_LM BITS(0,10) /*!< line mark value */ + +/* TLI_CPPOS */ +#define TLI_CPPOS_VPOS BITS(0,15) /*!< vertical position */ +#define TLI_CPPOS_HPOS BITS(16,31) /*!< horizontal position */ + +/* TLI_STAT */ +#define TLI_STAT_VDE BIT(0) /*!< current VDE status */ +#define TLI_STAT_HDE BIT(1) /*!< current HDE status */ +#define TLI_STAT_VS BIT(2) /*!< current VS status of the TLI */ +#define TLI_STAT_HS BIT(3) /*!< current HS status of the TLI */ + +/* TLI_LxCTL */ +#define TLI_LxCTL_LEN BIT(0) /*!< layer enable */ +#define TLI_LxCTL_CKEYEN BIT(1) /*!< color keying enable */ +#define TLI_LxCTL_LUTEN BIT(4) /*!< LUT enable */ + +/* TLI_LxHPOS */ +#define TLI_LxHPOS_WLP BITS(0,11) /*!< window left position */ +#define TLI_LxHPOS_WRP BITS(16,27) /*!< window right position */ + +/* TLI_LxVPOS */ +#define TLI_LxVPOS_WTP BITS(0,11) /*!< window top position */ +#define TLI_LxVPOS_WBP BITS(16,27) /*!< window bottom position */ + +/* TLI_LxCKEY */ +#define TLI_LxCKEY_CKEYB BITS(0,7) /*!< color key blue */ +#define TLI_LxCKEY_CKEYG BITS(8,15) /*!< color key green */ +#define TLI_LxCKEY_CKEYR BITS(16,23) /*!< color key red */ + +/* TLI_LxPPF */ +#define TLI_LxPPF_PPF BITS(0,2) /*!< packeted pixel format */ + +/* TLI_LxSA */ +#define TLI_LxSA_SA BITS(0,7) /*!< specified alpha */ + +/* TLI_LxDC */ +#define TLI_LxDC_DCB BITS(0,7) /*!< the default color blue */ +#define TLI_LxDC_DCG BITS(8,15) /*!< the default color green */ +#define TLI_LxDC_DCR BITS(16,23) /*!< the default color red */ +#define TLI_LxDC_DCA BITS(24,31) /*!< the default color alpha */ + +/* TLI_LxBLEND */ +#define TLI_LxBLEND_ACF2 BITS(0,2) /*!< alpha calculation factor 2 of blending method */ +#define TLI_LxBLEND_ACF1 BITS(8,10) /*!< alpha calculation factor 1 of blending method */ + +/* TLI_LxFBADDR */ +#define TLI_LxFBADDR_FBADD BITS(0,31) /*!< frame buffer base address */ + +/* TLI_LxFLLEN */ +#define TLI_LxFLLEN_FLL BITS(0,13) /*!< frame line length */ +#define TLI_LxFLLEN_STDOFF BITS(16,29) /*!< frame buffer stride offset */ + +/* TLI_LxFTLN */ +#define TLI_LxFTLN_FTLN BITS(0,10) /*!< frame total line number */ + +/* TLI_LxLUT */ +#define TLI_LxLUT_TB BITS(0,7) /*!< blue channel of a LUT entry */ +#define TLI_LxLUT_TG BITS(8,15) /*!< green channel of a LUT entry */ +#define TLI_LxLUT_TR BITS(16,23) /*!< red channel of a LUT entry */ +#define TLI_LxLUT_TADD BITS(24,31) /*!< look up table write address */ + +/* constants definitions */ +/* TLI parameter struct definitions */ +typedef struct { + uint16_t synpsz_vpsz; /*!< size of the vertical synchronous pulse */ + uint16_t synpsz_hpsz; /*!< size of the horizontal synchronous pulse */ + uint16_t backpsz_vbpsz; /*!< size of the vertical back porch plus synchronous pulse */ + uint16_t backpsz_hbpsz; /*!< size of the horizontal back porch plus synchronous pulse */ + uint32_t activesz_vasz; /*!< size of the vertical active area width plus back porch and synchronous pulse */ + uint32_t activesz_hasz; /*!< size of the horizontal active area width plus back porch and synchronous pulse */ + uint32_t totalsz_vtsz; /*!< vertical total size of the display */ + uint32_t totalsz_htsz; /*!< horizontal total size of the display */ + uint32_t backcolor_red; /*!< background value red */ + uint32_t backcolor_green; /*!< background value green */ + uint32_t backcolor_blue; /*!< background value blue */ + uint32_t signalpolarity_hs; /*!< horizontal pulse polarity selection */ + uint32_t signalpolarity_vs; /*!< vertical pulse polarity selection */ + uint32_t signalpolarity_de; /*!< data enable polarity selection */ + uint32_t signalpolarity_pixelck; /*!< pixel clock polarity selection */ +} tli_parameter_struct; + +/* TLI layer parameter struct definitions */ +typedef struct { + uint16_t layer_window_rightpos; /*!< window right position */ + uint16_t layer_window_leftpos; /*!< window left position */ + uint16_t layer_window_bottompos; /*!< window bottom position */ + uint16_t layer_window_toppos; /*!< window top position */ + uint32_t layer_ppf; /*!< packeted pixel format */ + uint8_t layer_sa; /*!< specified alpha */ + uint8_t layer_default_alpha; /*!< the default color alpha */ + uint8_t layer_default_red; /*!< the default color red */ + uint8_t layer_default_green; /*!< the default color green */ + uint8_t layer_default_blue; /*!< the default color blue */ + uint32_t layer_acf1; /*!< alpha calculation factor 1 of blending method */ + uint32_t layer_acf2; /*!< alpha calculation factor 2 of blending method */ + uint32_t layer_frame_bufaddr; /*!< frame buffer base address */ + uint16_t layer_frame_buf_stride_offset; /*!< frame buffer stride offset */ + uint16_t layer_frame_line_length; /*!< frame line length */ + uint16_t layer_frame_total_line_number; /*!< frame total line number */ +} tli_layer_parameter_struct; + +/* TLI layer LUT parameter struct definitions */ +typedef struct { + uint32_t layer_table_addr; /*!< look up table write address */ + uint8_t layer_lut_channel_red; /*!< red channel of a LUT entry */ + uint8_t layer_lut_channel_green; /*!< green channel of a LUT entry */ + uint8_t layer_lut_channel_blue; /*!< blue channel of a LUT entry */ +} tli_layer_lut_parameter_struct; + +/* packeted pixel format */ +typedef enum { + LAYER_PPF_ARGB8888, /*!< layerx pixel format ARGB8888 */ + LAYER_PPF_RGB888, /*!< layerx pixel format RGB888 */ + LAYER_PPF_RGB565, /*!< layerx pixel format RGB565 */ + LAYER_PPF_ARGB1555, /*!< layerx pixel format ARGB1555 */ + LAYER_PPF_ARGB4444, /*!< layerx pixel format ARGB4444 */ + LAYER_PPF_L8, /*!< layerx pixel format L8 */ + LAYER_PPF_AL44, /*!< layerx pixel format AL44 */ + LAYER_PPF_AL88 /*!< layerx pixel format AL88 */ +} tli_layer_ppf_enum; + +/* TLI flags */ +#define TLI_FLAG_VDE TLI_STAT_VDE /*!< current VDE status */ +#define TLI_FLAG_HDE TLI_STAT_HDE /*!< current HDE status */ +#define TLI_FLAG_VS TLI_STAT_VS /*!< current VS status of the TLI */ +#define TLI_FLAG_HS TLI_STAT_HS /*!< current HS status of the TLI */ +#define TLI_FLAG_LM BIT(0) | BIT(31) /*!< line mark interrupt flag */ +#define TLI_FLAG_FE BIT(1) | BIT(31) /*!< FIFO error interrupt flag */ +#define TLI_FLAG_TE BIT(2) | BIT(31) /*!< transaction error interrupt flag */ +#define TLI_FLAG_LCR BIT(3) | BIT(31) /*!< layer configuration reloaded interrupt flag */ + +/* TLI interrupt enable or disable */ +#define TLI_INT_LM BIT(0) /*!< line mark interrupt */ +#define TLI_INT_FE BIT(1) /*!< FIFO error interrupt */ +#define TLI_INT_TE BIT(2) /*!< transaction error interrupt */ +#define TLI_INT_LCR BIT(3) /*!< layer configuration reloaded interrupt */ + +/* TLI interrupt flag */ +#define TLI_INT_FLAG_LM BIT(0) /*!< line mark interrupt flag */ +#define TLI_INT_FLAG_FE BIT(1) /*!< FIFO error interrupt flag */ +#define TLI_INT_FLAG_TE BIT(2) /*!< transaction error interrupt flag */ +#define TLI_INT_FLAG_LCR BIT(3) /*!< layer configuration reloaded interrupt flag */ + +/* layer reload configure */ +#define TLI_FRAME_BLANK_RELOAD_EN ((uint8_t)0x00U) /*!< the layer configuration will be reloaded at frame blank */ +#define TLI_REQUEST_RELOAD_EN ((uint8_t)0x01U) /*!< the layer configuration will be reloaded after this bit sets */ + +/* dither function */ +#define TLI_DITHER_DISABLE ((uint8_t)0x00U) /*!< dither function disable */ +#define TLI_DITHER_ENABLE ((uint8_t)0x01U) /*!< dither function enable */ + +/* horizontal pulse polarity selection */ +#define TLI_HSYN_ACTLIVE_LOW ((uint32_t)0x00000000U) /*!< horizontal synchronous pulse active low */ +#define TLI_HSYN_ACTLIVE_HIGHT TLI_CTL_HPPS /*!< horizontal synchronous pulse active high */ + +/* vertical pulse polarity selection */ +#define TLI_VSYN_ACTLIVE_LOW ((uint32_t)0x00000000U) /*!< vertical synchronous pulse active low */ +#define TLI_VSYN_ACTLIVE_HIGHT TLI_CTL_VPPS /*!< vertical synchronous pulse active high */ + +/* pixel clock polarity selection */ +#define TLI_PIXEL_CLOCK_TLI ((uint32_t)0x00000000U) /*!< pixel clock is TLI clock */ +#define TLI_PIXEL_CLOCK_INVERTEDTLI TLI_CTL_CLKPS /*!< pixel clock is inverted TLI clock */ + +/* data enable polarity selection */ +#define TLI_DE_ACTLIVE_LOW ((uint32_t)0x00000000U) /*!< data enable active low */ +#define TLI_DE_ACTLIVE_HIGHT TLI_CTL_DEPS /*!< data enable active high */ + +/* alpha calculation factor 1 of blending method */ +#define LxBLEND_ACF1(regval) (BITS(8,10) & ((uint32_t)(regval)<<8)) +#define LAYER_ACF1_SA LxBLEND_ACF1(4) /*!< normalization specified alpha */ +#define LAYER_ACF1_PASA LxBLEND_ACF1(6) /*!< normalization pixel alpha * normalization specified alpha */ + +/* alpha calculation factor 2 of blending method */ +#define LxBLEND_ACF2(regval) (BITS(0,2) & ((uint32_t)(regval))) +#define LAYER_ACF2_SA LxBLEND_ACF2(5) /*!< normalization specified alpha */ +#define LAYER_ACF2_PASA LxBLEND_ACF2(7) /*!< normalization pixel alpha * normalization specified alpha */ + +/* function declarations */ +/* initialization functions, TLI enable or disable, TLI reload mode configuration */ +/* deinitialize TLI registers */ +void tli_deinit(void); +/* initialize the parameters of TLI parameter structure with the default values, it is suggested + that call this function after a tli_parameter_struct structure is defined */ +void tli_struct_para_init(tli_parameter_struct *tli_struct); +/* initialize TLI */ +void tli_init(tli_parameter_struct *tli_struct); +/* configure TLI dither function */ +void tli_dither_config(uint8_t dither_stat); +/* enable TLI */ +void tli_enable(void); +/* disable TLI */ +void tli_disable(void); +/* configurate TLI reload mode */ +void tli_reload_config(uint8_t reload_mod); + +/* TLI layer configuration functions */ +/* initialize the parameters of TLI layer structure with the default values, it is suggested + that call this function after a tli_layer_parameter_struct structure is defined */ +void tli_layer_struct_para_init(tli_layer_parameter_struct *layer_struct); +/* initialize TLI layer */ +void tli_layer_init(uint32_t layerx, tli_layer_parameter_struct *layer_struct); +/* reconfigure window position */ +void tli_layer_window_offset_modify(uint32_t layerx, uint16_t offset_x, uint16_t offset_y); +/* initialize the parameters of TLI layer LUT structure with the default values, it is suggested + that call this function after a tli_layer_lut_parameter_struct structure is defined */ +void tli_lut_struct_para_init(tli_layer_lut_parameter_struct *lut_struct); +/* initialize TLI layer LUT */ +void tli_lut_init(uint32_t layerx, tli_layer_lut_parameter_struct *lut_struct); +/* initialize TLI layer color key */ +void tli_color_key_init(uint32_t layerx, uint8_t redkey, uint8_t greenkey, uint8_t bluekey); +/* enable TLI layer */ +void tli_layer_enable(uint32_t layerx); +/* disable TLI layer */ +void tli_layer_disable(uint32_t layerx); +/* enable TLI layer color keying */ +void tli_color_key_enable(uint32_t layerx); +/* disable TLI layer color keying */ +void tli_color_key_disable(uint32_t layerx); +/* enable TLI layer LUT */ +void tli_lut_enable(uint32_t layerx); +/* disable TLI layer LUT */ +void tli_lut_disable(uint32_t layerx); + +/* set line mark value */ +void tli_line_mark_set(uint16_t line_num); +/* get current displayed position */ +uint32_t tli_current_pos_get(void); + +/* flag and interrupt functions */ +/* enable TLI interrupt */ +void tli_interrupt_enable(uint32_t int_flag); +/* disable TLI interrupt */ +void tli_interrupt_disable(uint32_t int_flag); +/* get TLI interrupt flag */ +FlagStatus tli_interrupt_flag_get(uint32_t int_flag); +/* clear TLI interrupt flag */ +void tli_interrupt_flag_clear(uint32_t int_flag); +/* get TLI flag or state in TLI_INTF register or TLI_STAT register */ +FlagStatus tli_flag_get(uint32_t flag); + +#endif /* GD32F5XX_TLI_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_trng.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_trng.h new file mode 100644 index 0000000..d934e8f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_trng.h @@ -0,0 +1,100 @@ +/*! + \file gd32f5xx_trng.h + \brief definitions for the TRNG + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_TRNG_H +#define GD32F5XX_TRNG_H + +#include "gd32f5xx.h" + +/* TRNG definitions */ +#define TRNG TRNG_BASE + +/* registers definitions */ +#define TRNG_CTL REG32(TRNG + 0x00000000U) /*!< control register */ +#define TRNG_STAT REG32(TRNG + 0x00000004U) /*!< status register */ +#define TRNG_DATA REG32(TRNG + 0x00000008U) /*!< data register */ + +/* bits definitions */ +/* TRNG_CTL */ +#define TRNG_CTL_TRNGEN BIT(2) /*!< TRNG enable bit */ +#define TRNG_CTL_TRNGIE BIT(3) /*!< interrupt enable bit */ + +/* TRNG_STAT */ +#define TRNG_STAT_DRDY BIT(0) /*!< random data ready status bit */ +#define TRNG_STAT_CECS BIT(1) /*!< clock error current status */ +#define TRNG_STAT_SECS BIT(2) /*!< seed error current status */ +#define TRNG_STAT_CEIF BIT(5) /*!< clock error interrupt flag */ +#define TRNG_STAT_SEIF BIT(6) /*!< seed error interrupt flag */ + +/* TRNG_DATA */ +#define TRNG_DATA_TRNGDATA BITS(0,31) /*!< 32-Bit Random data */ + +/* constants definitions */ +/* TRNG status flag */ +typedef enum { + TRNG_FLAG_DRDY = TRNG_STAT_DRDY, /*!< random Data ready status */ + TRNG_FLAG_CECS = TRNG_STAT_CECS, /*!< clock error current status */ + TRNG_FLAG_SECS = TRNG_STAT_SECS /*!< seed error current status */ +} trng_flag_enum; + +/* TRNG inerrupt flag */ +typedef enum { + TRNG_INT_FLAG_CEIF = TRNG_STAT_CEIF, /*!< clock error interrupt flag */ + TRNG_INT_FLAG_SEIF = TRNG_STAT_SEIF /*!< seed error interrupt flag */ +} trng_int_flag_enum; + +/* function declarations */ +/* initialization functions */ +/* reset TRNG */ +void trng_deinit(void); +/* enable TRNG */ +void trng_enable(void); +/* disable TRNG */ +void trng_disable(void); +/* get the true random data */ +uint32_t trng_get_true_random_data(void); + +/* interrupt & flag functions */ +/* get TRNG flag status */ +FlagStatus trng_flag_get(trng_flag_enum flag); +/* enable TRNG interrupt */ +void trng_interrupt_enable(void); +/* disable TRNG interrupt */ +void trng_interrupt_disable(void); +/* get TRNG interrupt flag status */ +FlagStatus trng_interrupt_flag_get(trng_int_flag_enum int_flag); +/* clear TRNG interrupt flag status */ +void trng_interrupt_flag_clear(trng_int_flag_enum int_flag); + +#endif /* GD32F5XX_TRNG_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_usart.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_usart.h new file mode 100644 index 0000000..afa1e3b --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_usart.h @@ -0,0 +1,489 @@ +/*! + \file gd32f5xx_usart.h + \brief definitions for the USART + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_USART_H +#define GD32F5XX_USART_H + +#include "gd32f5xx.h" + +/* USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) definitions */ +#define USART1 USART_BASE /*!< USART1 base address */ +#define USART2 (USART_BASE+0x00000400U) /*!< USART2 base address */ +#define UART3 (USART_BASE+0x00000800U) /*!< UART3 base address */ +#define UART4 (USART_BASE+0x00000C00U) /*!< UART4 base address */ +#define UART6 (USART_BASE+0x00003400U) /*!< UART6 base address */ +#define UART7 (USART_BASE+0x00003800U) /*!< UART7 base address */ +#define USART0 (USART_BASE+0x0000CC00U) /*!< USART0 base address */ +#define USART5 (USART_BASE+0x0000D000U) /*!< USART5 base address */ + +/* registers definitions */ +#define USART_STAT0(usartx) REG32((usartx) + 0x00U) /*!< USART status register 0 */ +#define USART_DATA(usartx) REG32((usartx) + 0x04U) /*!< USART data register */ +#define USART_BAUD(usartx) REG32((usartx) + 0x08U) /*!< USART baud rate register */ +#define USART_CTL0(usartx) REG32((usartx) + 0x0CU) /*!< USART control register 0 */ +#define USART_CTL1(usartx) REG32((usartx) + 0x10U) /*!< USART control register 1 */ +#define USART_CTL2(usartx) REG32((usartx) + 0x14U) /*!< USART control register 2 */ +#define USART_GP(usartx) REG32((usartx) + 0x18U) /*!< USART guard time and prescaler register */ +#define USART_CTL3(usartx) REG32((usartx) + 0x80U) /*!< USART control register 3 */ +#define USART_RT(usartx) REG32((usartx) + 0x84U) /*!< USART receiver timeout register */ +#define USART_STAT1(usartx) REG32((usartx) + 0x88U) /*!< USART status register 1 */ +#define USART_CHC(usartx) REG32((usartx) + 0xC0U) /*!< USART coherence control register */ + +/* bits definitions */ +/* USARTx_STAT0 */ +#define USART_STAT0_PERR BIT(0) /*!< parity error flag */ +#define USART_STAT0_FERR BIT(1) /*!< frame error flag */ +#define USART_STAT0_NERR BIT(2) /*!< noise error flag */ +#define USART_STAT0_ORERR BIT(3) /*!< overrun error */ +#define USART_STAT0_IDLEF BIT(4) /*!< IDLE frame detected flag */ +#define USART_STAT0_RBNE BIT(5) /*!< read data buffer not empty */ +#define USART_STAT0_TC BIT(6) /*!< transmission complete */ +#define USART_STAT0_TBE BIT(7) /*!< transmit data buffer empty */ +#define USART_STAT0_LBDF BIT(8) /*!< LIN break detected flag */ +#define USART_STAT0_CTSF BIT(9) /*!< CTS change flag */ + +/* USARTx_DATA */ +#define USART_DATA_DATA BITS(0,8) /*!< transmit or read data value */ + +/* USARTx_BAUD */ +#define USART_BAUD_FRADIV BITS(0,3) /*!< fraction part of baud-rate divider */ +#define USART_BAUD_INTDIV BITS(4,15) /*!< integer part of baud-rate divider */ + +/* USARTx_CTL0 */ +#define USART_CTL0_SBKCMD BIT(0) /*!< send break command */ +#define USART_CTL0_RWU BIT(1) /*!< receiver wakeup from mute mode */ +#define USART_CTL0_REN BIT(2) /*!< receiver enable */ +#define USART_CTL0_TEN BIT(3) /*!< transmitter enable */ +#define USART_CTL0_IDLEIE BIT(4) /*!< idle line detected interrupt enable */ +#define USART_CTL0_RBNEIE BIT(5) /*!< read data buffer not empty interrupt and overrun error interrupt enable */ +#define USART_CTL0_TCIE BIT(6) /*!< transmission complete interrupt enable */ +#define USART_CTL0_TBEIE BIT(7) /*!< transmitter buffer empty interrupt enable */ +#define USART_CTL0_PERRIE BIT(8) /*!< parity error interrupt enable */ +#define USART_CTL0_PM BIT(9) /*!< parity mode */ +#define USART_CTL0_PCEN BIT(10) /*!< parity check function enable */ +#define USART_CTL0_WM BIT(11) /*!< wakeup method in mute mode */ +#define USART_CTL0_WL BIT(12) /*!< word length */ +#define USART_CTL0_UEN BIT(13) /*!< USART enable */ +#define USART_CTL0_OVSMOD BIT(15) /*!< oversample mode */ + +/* USARTx_CTL1 */ +#define USART_CTL1_ADDR BITS(0,3) /*!< address of USART */ +#define USART_CTL1_LBLEN BIT(5) /*!< LIN break frame length */ +#define USART_CTL1_LBDIE BIT(6) /*!< LIN break detected interrupt eanble */ +#define USART_CTL1_CLEN BIT(8) /*!< CK length */ +#define USART_CTL1_CPH BIT(9) /*!< CK phase */ +#define USART_CTL1_CPL BIT(10) /*!< CK polarity */ +#define USART_CTL1_CKEN BIT(11) /*!< CK pin enable */ +#define USART_CTL1_STB BITS(12,13) /*!< STOP bits length */ +#define USART_CTL1_LMEN BIT(14) /*!< LIN mode enable */ + +/* USARTx_CTL2 */ +#define USART_CTL2_ERRIE BIT(0) /*!< error interrupt enable */ +#define USART_CTL2_IREN BIT(1) /*!< IrDA mode enable */ +#define USART_CTL2_IRLP BIT(2) /*!< IrDA low-power */ +#define USART_CTL2_HDEN BIT(3) /*!< half-duplex enable */ +#define USART_CTL2_NKEN BIT(4) /*!< NACK enable in smartcard mode */ +#define USART_CTL2_SCEN BIT(5) /*!< smartcard mode enable */ +#define USART_CTL2_DENR BIT(6) /*!< DMA request enable for reception */ +#define USART_CTL2_DENT BIT(7) /*!< DMA request enable for transmission */ +#define USART_CTL2_RTSEN BIT(8) /*!< RTS enable */ +#define USART_CTL2_CTSEN BIT(9) /*!< CTS enable */ +#define USART_CTL2_CTSIE BIT(10) /*!< CTS interrupt enable */ +#define USART_CTL2_OSB BIT(11) /*!< one sample bit method */ + +/* USARTx_GP */ +#define USART_GP_PSC BITS(0,7) /*!< prescaler value for dividing the system clock */ +#define USART_GP_GUAT BITS(8,15) /*!< guard time value in smartcard mode */ + +/* USARTx_CTL3 */ +#define USART_CTL3_RTEN BIT(0) /*!< receiver timeout enable */ +#define USART_CTL3_SCRTNUM BITS(1,3) /*!< smartcard auto-retry number */ +#define USART_CTL3_RTIE BIT(4) /*!< interrupt enable bit of receive timeout event */ +#define USART_CTL3_EBIE BIT(5) /*!< interrupt enable bit of end of block event */ +#define USART_CTL3_RINV BIT(8) /*!< RX pin level inversion */ +#define USART_CTL3_TINV BIT(9) /*!< TX pin level inversion */ +#define USART_CTL3_DINV BIT(10) /*!< data bit level inversion */ +#define USART_CTL3_MSBF BIT(11) /*!< most significant bit first */ + +/* USARTx_RT */ +#define USART_RT_RT BITS(0,23) /*!< receiver timeout threshold */ +#define USART_RT_BL BITS(24,31) /*!< block length */ + +/* USARTx_STAT1 */ +#define USART_STAT1_RTF BIT(11) /*!< receiver timeout flag */ +#define USART_STAT1_EBF BIT(12) /*!< end of block flag */ +#define USART_STAT1_BSY BIT(16) /*!< busy flag */ + +/* USARTx_CHC */ +#define USART_CHC_HCM BIT(0) /*!< hardware flow control coherence mode */ +#define USART_CHC_PCM BIT(1) /*!< parity check coherence mode */ +#define USART_CHC_BCM BIT(2) /*!< break frame coherence mode */ +#define USART_CHC_EPERR BIT(8) /*!< early parity error flag */ + +/* constants definitions */ +/* define the USART bit position and its register index offset */ +#define USART_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)) +#define USART_REG_VAL(usartx, offset) (REG32((usartx) + (((uint32_t)(offset) & 0xFFFFU) >> 6))) +#define USART_BIT_POS(val) ((uint32_t)(val) & 0x1FU) +#define USART_REGIDX_BIT2(regidx, bitpos, regidx2, bitpos2) (((uint32_t)(regidx2) << 22) | (uint32_t)((bitpos2) << 16)\ + | (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))) +#define USART_REG_VAL2(usartx, offset) (REG32((usartx) + ((uint32_t)(offset) >> 22))) +#define USART_BIT_POS2(val) (((uint32_t)(val) & 0x1F0000U) >> 16) + +/* register offset */ +#define USART_STAT0_REG_OFFSET 0x00U /*!< STAT0 register offset */ +#define USART_STAT1_REG_OFFSET 0x88U /*!< STAT1 register offset */ +#define USART_CTL0_REG_OFFSET 0x0CU /*!< CTL0 register offset */ +#define USART_CTL1_REG_OFFSET 0x10U /*!< CTL1 register offset */ +#define USART_CTL2_REG_OFFSET 0x14U /*!< CTL2 register offset */ +#define USART_CTL3_REG_OFFSET 0x80U /*!< CTL3 register offset */ +#define USART_CHC_REG_OFFSET 0xC0U /*!< CHC register offset */ + +/* USART flags */ +typedef enum { + /* flags in STAT0 register */ + USART_FLAG_CTS = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 9U), /*!< CTS change flag */ + USART_FLAG_LBD = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 8U), /*!< LIN break detected flag */ + USART_FLAG_TBE = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 7U), /*!< transmit data buffer empty */ + USART_FLAG_TC = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 6U), /*!< transmission complete */ + USART_FLAG_RBNE = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 5U), /*!< read data buffer not empty */ + USART_FLAG_IDLE = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 4U), /*!< IDLE frame detected flag */ + USART_FLAG_ORERR = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 3U), /*!< overrun error */ + USART_FLAG_NERR = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 2U), /*!< noise error flag */ + USART_FLAG_FERR = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 1U), /*!< frame error flag */ + USART_FLAG_PERR = USART_REGIDX_BIT(USART_STAT0_REG_OFFSET, 0U), /*!< parity error flag */ + /* flags in STAT1 register */ + USART_FLAG_BSY = USART_REGIDX_BIT(USART_STAT1_REG_OFFSET, 16U), /*!< busy flag */ + USART_FLAG_EB = USART_REGIDX_BIT(USART_STAT1_REG_OFFSET, 12U), /*!< end of block flag */ + USART_FLAG_RT = USART_REGIDX_BIT(USART_STAT1_REG_OFFSET, 11U), /*!< receiver timeout flag */ + /* flags in CHC register */ + USART_FLAG_EPERR = USART_REGIDX_BIT(USART_CHC_REG_OFFSET, 8U) /*!< early parity error flag */ +} usart_flag_enum; + +/* USART interrupt flags */ +typedef enum { + /* interrupt flags in CTL0 register */ + USART_INT_FLAG_PERR = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 8U, USART_STAT0_REG_OFFSET, 0U), /*!< parity error interrupt and flag */ + USART_INT_FLAG_TBE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 7U, USART_STAT0_REG_OFFSET, 7U), /*!< transmitter buffer empty interrupt and flag */ + USART_INT_FLAG_TC = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 6U, USART_STAT0_REG_OFFSET, 6U), /*!< transmission complete interrupt and flag */ + USART_INT_FLAG_RBNE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 5U, USART_STAT0_REG_OFFSET, 5U), /*!< read data buffer not empty interrupt and flag */ + USART_INT_FLAG_RBNE_ORERR = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 5U, USART_STAT0_REG_OFFSET, 3U), /*!< read data buffer not empty interrupt and overrun error flag */ + USART_INT_FLAG_IDLE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 4U, USART_STAT0_REG_OFFSET, 4U), /*!< IDLE line detected interrupt and flag */ + /* interrupt flags in CTL1 register */ + USART_INT_FLAG_LBD = USART_REGIDX_BIT2(USART_CTL1_REG_OFFSET, 6U, USART_STAT0_REG_OFFSET, 8U), /*!< LIN break detected interrupt and flag */ + /* interrupt flags in CTL2 register */ + USART_INT_FLAG_CTS = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 10U, USART_STAT0_REG_OFFSET, 9U), /*!< CTS interrupt and flag */ + USART_INT_FLAG_ERR_ORERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT0_REG_OFFSET, 3U), /*!< error interrupt and overrun error */ + USART_INT_FLAG_ERR_NERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT0_REG_OFFSET, 2U), /*!< error interrupt and noise error flag */ + USART_INT_FLAG_ERR_FERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT0_REG_OFFSET, 1U), /*!< error interrupt and frame error flag */ + /* interrupt flags in CTL3 register */ + USART_INT_FLAG_EB = USART_REGIDX_BIT2(USART_CTL3_REG_OFFSET, 5U, USART_STAT1_REG_OFFSET, 12U), /*!< interrupt enable bit of end of block event and flag */ + USART_INT_FLAG_RT = USART_REGIDX_BIT2(USART_CTL3_REG_OFFSET, 4U, USART_STAT1_REG_OFFSET, 11U) /*!< interrupt enable bit of receive timeout event and flag */ +} usart_interrupt_flag_enum; + +/* USART interrupt flags */ +typedef enum { + /* interrupt in CTL0 register */ + USART_INT_PERR = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 8U), /*!< parity error interrupt */ + USART_INT_TBE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 7U), /*!< transmitter buffer empty interrupt */ + USART_INT_TC = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 6U), /*!< transmission complete interrupt */ + USART_INT_RBNE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 5U), /*!< read data buffer not empty interrupt and overrun error interrupt */ + USART_INT_IDLE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 4U), /*!< IDLE line detected interrupt */ + /* interrupt in CTL1 register */ + USART_INT_LBD = USART_REGIDX_BIT(USART_CTL1_REG_OFFSET, 6U), /*!< LIN break detected interrupt */ + /* interrupt in CTL2 register */ + USART_INT_CTS = USART_REGIDX_BIT(USART_CTL2_REG_OFFSET, 10U), /*!< CTS interrupt */ + USART_INT_ERR = USART_REGIDX_BIT(USART_CTL2_REG_OFFSET, 0U), /*!< error interrupt */ + /* interrupt in CTL3 register */ + USART_INT_EB = USART_REGIDX_BIT(USART_CTL3_REG_OFFSET, 5U), /*!< interrupt enable bit of end of block event */ + USART_INT_RT = USART_REGIDX_BIT(USART_CTL3_REG_OFFSET, 4U) /*!< interrupt enable bit of receive timeout event */ +} usart_interrupt_enum; + +/* USART invert configure */ +typedef enum { + /* data bit level inversion */ + USART_DINV_ENABLE, /*!< data bit level inversion */ + USART_DINV_DISABLE, /*!< data bit level not inversion */ + /* TX pin level inversion */ + USART_TXPIN_ENABLE, /*!< TX pin level inversion */ + USART_TXPIN_DISABLE, /*!< TX pin level not inversion */ + /* RX pin level inversion */ + USART_RXPIN_ENABLE, /*!< RX pin level inversion */ + USART_RXPIN_DISABLE /*!< RX pin level not inversion */ +} usart_invert_enum; + +/* USART receiver configure */ +#define CTL0_REN(regval) (BIT(2) & ((uint32_t)(regval) << 2)) +#define USART_RECEIVE_ENABLE CTL0_REN(1) /*!< enable receiver */ +#define USART_RECEIVE_DISABLE CTL0_REN(0) /*!< disable receiver */ + +/* USART transmitter configure */ +#define CTL0_TEN(regval) (BIT(3) & ((uint32_t)(regval) << 3)) +#define USART_TRANSMIT_ENABLE CTL0_TEN(1) /*!< enable transmitter */ +#define USART_TRANSMIT_DISABLE CTL0_TEN(0) /*!< disable transmitter */ + +/* USART parity bits definitions */ +#define CTL0_PM(regval) (BITS(9,10) & ((uint32_t)(regval) << 9)) +#define USART_PM_NONE CTL0_PM(0) /*!< no parity */ +#define USART_PM_EVEN CTL0_PM(2) /*!< even parity */ +#define USART_PM_ODD CTL0_PM(3) /*!< odd parity */ + +/* USART wakeup method in mute mode */ +#define CTL0_WM(regval) (BIT(11) & ((uint32_t)(regval) << 11)) +#define USART_WM_IDLE CTL0_WM(0) /*!< idle Line */ +#define USART_WM_ADDR CTL0_WM(1) /*!< address mask */ + +/* USART word length definitions */ +#define CTL0_WL(regval) (BIT(12) & ((uint32_t)(regval) << 12)) +#define USART_WL_8BIT CTL0_WL(0) /*!< 8 bits */ +#define USART_WL_9BIT CTL0_WL(1) /*!< 9 bits */ + +/* USART oversampling mode definitions */ +#define CTL0_OVSMOD(regval) (BIT(15) & ((uint32_t)(regval) << 15)) +#define USART_OVSMOD_16 CTL0_OVSMOD(0) /*!< 16 bits */ +#define USART_OVSMOD_8 CTL0_OVSMOD(1) /*!< 8 bits */ + +/* USART stop bits definitions */ +#define CTL1_STB(regval) (BITS(12,13) & ((uint32_t)(regval) << 12)) +#define USART_STB_1BIT CTL1_STB(0) /*!< 1 bit */ +#define USART_STB_0_5BIT CTL1_STB(1) /*!< 0.5 bit */ +#define USART_STB_2BIT CTL1_STB(2) /*!< 2 bits */ +#define USART_STB_1_5BIT CTL1_STB(3) /*!< 1.5 bits */ + +/* USART LIN break frame length */ +#define CTL1_LBLEN(regval) (BIT(5) & ((uint32_t)(regval) << 5)) +#define USART_LBLEN_10B CTL1_LBLEN(0) /*!< 10 bits */ +#define USART_LBLEN_11B CTL1_LBLEN(1) /*!< 11 bits */ + +/* USART CK length */ +#define CTL1_CLEN(regval) (BIT(8) & ((uint32_t)(regval) << 8)) +#define USART_CLEN_NONE CTL1_CLEN(0) /*!< there are 7 CK pulses for an 8 bit frame and 8 CK pulses for a 9 bit frame */ +#define USART_CLEN_EN CTL1_CLEN(1) /*!< there are 8 CK pulses for an 8 bit frame and 9 CK pulses for a 9 bit frame */ + +/* USART clock phase */ +#define CTL1_CPH(regval) (BIT(9) & ((uint32_t)(regval) << 9)) +#define USART_CPH_1CK CTL1_CPH(0) /*!< first clock transition is the first data capture edge */ +#define USART_CPH_2CK CTL1_CPH(1) /*!< second clock transition is the first data capture edge */ + +/* USART clock polarity */ +#define CTL1_CPL(regval) (BIT(10) & ((uint32_t)(regval) << 10)) +#define USART_CPL_LOW CTL1_CPL(0) /*!< steady low value on CK pin */ +#define USART_CPL_HIGH CTL1_CPL(1) /*!< steady high value on CK pin */ + +/* USART DMA request for receive configure */ +#define CLT2_DENR(regval) (BIT(6) & ((uint32_t)(regval) << 6)) +#define USART_DENR_ENABLE CLT2_DENR(1) /*!< DMA request enable for reception */ +#define USART_DENR_DISABLE CLT2_DENR(0) /*!< DMA request disable for reception */ + +/* USART DMA request for transmission configure */ +#define CLT2_DENT(regval) (BIT(7) & ((uint32_t)(regval) << 7)) +#define USART_DENT_ENABLE CLT2_DENT(1) /*!< DMA request enable for transmission */ +#define USART_DENT_DISABLE CLT2_DENT(0) /*!< DMA request disable for transmission */ + +/* USART RTS configure */ +#define CLT2_RTSEN(regval) (BIT(8) & ((uint32_t)(regval) << 8)) +#define USART_RTS_ENABLE CLT2_RTSEN(1) /*!< RTS enable */ +#define USART_RTS_DISABLE CLT2_RTSEN(0) /*!< RTS disable */ + +/* USART CTS configure */ +#define CLT2_CTSEN(regval) (BIT(9) & ((uint32_t)(regval) << 9)) +#define USART_CTS_ENABLE CLT2_CTSEN(1) /*!< CTS enable */ +#define USART_CTS_DISABLE CLT2_CTSEN(0) /*!< CTS disable */ + +/* USART one sample bit method configure */ +#define CTL2_OSB(regval) (BIT(11) & ((uint32_t)(regval) << 11)) +#define USART_OSB_1bit CTL2_OSB(1) /*!< 1 bit */ +#define USART_OSB_3bit CTL2_OSB(0) /*!< 3 bits */ + +/* USART IrDA low-power enable */ +#define CTL2_IRLP(regval) (BIT(2) & ((uint32_t)(regval) << 2)) +#define USART_IRLP_LOW CTL2_IRLP(1) /*!< low-power */ +#define USART_IRLP_NORMAL CTL2_IRLP(0) /*!< normal */ + +/* USART data is transmitted/received with the LSB/MSB first */ +#define CTL3_MSBF(regval) (BIT(11) & ((uint32_t)(regval) << 11)) +#define USART_MSBF_LSB CTL3_MSBF(0) /*!< LSB first */ +#define USART_MSBF_MSB CTL3_MSBF(1) /*!< MSB first */ + +/* break frame coherence mode */ +#define CHC_BCM(regval) (BIT(2) & ((uint32_t)(regval) << 2)) +#define USART_BCM_NONE CHC_BCM(0) /*!< no parity error is detected */ +#define USART_BCM_EN CHC_BCM(1) /*!< parity error is detected */ + +/* USART parity check coherence mode */ +#define CHC_PCM(regval) (BIT(1) & ((uint32_t)(regval) << 1)) +#define USART_PCM_NONE CHC_PCM(0) /*!< not check parity */ +#define USART_PCM_EN CHC_PCM(1) /*!< check the parity */ + +/* USART hardware flow control coherence mode */ +#define CHC_HCM(regval) (BIT(0) & ((uint32_t)(regval) << 0)) +#define USART_HCM_NONE CHC_HCM(0) /*!< nRTS signal equals to the rxne status register */ +#define USART_HCM_EN CHC_HCM(1) /*!< nRTS signal is set when the last data bit has been sampled */ + +/* function declarations */ +/* initialization functions */ +/* reset USART */ +void usart_deinit(uint32_t usart_periph); +/* configure usart baud rate value */ +void usart_baudrate_set(uint32_t usart_periph, uint32_t baudval); +/* configure usart parity function */ +void usart_parity_config(uint32_t usart_periph, uint32_t paritycfg); +/* configure usart word length */ +void usart_word_length_set(uint32_t usart_periph, uint32_t wlen); +/* configure usart stop bit length */ +void usart_stop_bit_set(uint32_t usart_periph, uint32_t stblen); +/* enable usart */ +void usart_enable(uint32_t usart_periph); +/* disable usart */ +void usart_disable(uint32_t usart_periph); +/* configure USART transmitter */ +void usart_transmit_config(uint32_t usart_periph, uint32_t txconfig); +/* configure USART receiver */ +void usart_receive_config(uint32_t usart_periph, uint32_t rxconfig); + +/* USART normal mode communication */ +/* transmit/receive ddata with the LSB/MSB first */ +void usart_data_first_config(uint32_t usart_periph, uint32_t msbf); +/* configure USART inversion */ +void usart_invert_config(uint32_t usart_periph, usart_invert_enum invertpara); +/* configure the USART oversample mode */ +void usart_oversample_config(uint32_t usart_periph, uint32_t oversamp); +/* configure sample bit method */ +void usart_sample_bit_config(uint32_t usart_periph, uint32_t obsm); +/* enable receiver timeout */ +void usart_receiver_timeout_enable(uint32_t usart_periph); +/* disable receiver timeout */ +void usart_receiver_timeout_disable(uint32_t usart_periph); +/* configure receiver timeout threshold */ +void usart_receiver_timeout_threshold_config(uint32_t usart_periph, uint32_t rtimeout); +/* USART transmit data function */ +void usart_data_transmit(uint32_t usart_periph, uint32_t data); +/* USART receive data function */ +uint16_t usart_data_receive(uint32_t usart_periph); + +/* multi-processor communication */ +/* configure address of the USART */ +void usart_address_config(uint32_t usart_periph, uint8_t addr); +/* enable mute mode */ +void usart_mute_mode_enable(uint32_t usart_periph); +/* disable mute mode */ +void usart_mute_mode_disable(uint32_t usart_periph); +/* configure wakeup method in mute mode */ +void usart_mute_mode_wakeup_config(uint32_t usart_periph, uint32_t wmehtod); + +/* LIN mode communication */ +/* enable LIN mode */ +void usart_lin_mode_enable(uint32_t usart_periph); +/* disable LIN mode */ +void usart_lin_mode_disable(uint32_t usart_periph); +/* configure lin break frame length */ +void usart_lin_break_detection_length_config(uint32_t usart_periph, uint32_t lblen); +/* send break frame */ +void usart_send_break(uint32_t usart_periph); + +/* half-duplex communication */ +/* enable half-duplex mode */ +void usart_halfduplex_enable(uint32_t usart_periph); +/* disable half-duplex mode */ +void usart_halfduplex_disable(uint32_t usart_periph); + +/* synchronous communication */ +/* enable CK pin in synchronous mode */ +void usart_synchronous_clock_enable(uint32_t usart_periph); +/* disable CK pin in synchronous mode */ +void usart_synchronous_clock_disable(uint32_t usart_periph); +/* configure usart synchronous mode parameters */ +void usart_synchronous_clock_config(uint32_t usart_periph, uint32_t clen, uint32_t cph, uint32_t cpl); + +/* smartcard communication */ +/* configure guard time value in smartcard mode */ +void usart_guard_time_config(uint32_t usart_periph, uint32_t guat); +/* enable smartcard mode */ +void usart_smartcard_mode_enable(uint32_t usart_periph); +/* disable smartcard mode */ +void usart_smartcard_mode_disable(uint32_t usart_periph); +/* enable NACK in smartcard mode */ +void usart_smartcard_mode_nack_enable(uint32_t usart_periph); +/* disable NACK in smartcard mode */ +void usart_smartcard_mode_nack_disable(uint32_t usart_periph); +/* configure smartcard auto-retry number */ +void usart_smartcard_autoretry_config(uint32_t usart_periph, uint32_t scrtnum); +/* configure block length */ +void usart_block_length_config(uint32_t usart_periph, uint32_t bl); + +/* IrDA communication */ +/* enable IrDA mode */ +void usart_irda_mode_enable(uint32_t usart_periph); +/* disable IrDA mode */ +void usart_irda_mode_disable(uint32_t usart_periph); +/* configure the peripheral clock prescaler */ +void usart_prescaler_config(uint32_t usart_periph, uint8_t psc); +/* configure IrDA low-power */ +void usart_irda_lowpower_config(uint32_t usart_periph, uint32_t irlp); + +/* hardware flow communication */ +/* configure hardware flow control RTS */ +void usart_hardware_flow_rts_config(uint32_t usart_periph, uint32_t rtsconfig); +/* configure hardware flow control CTS */ +void usart_hardware_flow_cts_config(uint32_t usart_periph, uint32_t ctsconfig); + +/* coherence control */ +/* configure break frame coherence mode */ +void usart_break_frame_coherence_config(uint32_t usart_periph, uint32_t bcm); +/* configure parity check coherence mode */ +void usart_parity_check_coherence_config(uint32_t usart_periph, uint32_t pcm); +/* configure hardware flow control coherence mode */ +void usart_hardware_flow_coherence_config(uint32_t usart_periph, uint32_t hcm); + +/* DMA communication */ +/* configure USART DMA for reception */ +void usart_dma_receive_config(uint32_t usart_periph, uint32_t dmacmd); +/* configure USART DMA for transmission */ +void usart_dma_transmit_config(uint32_t usart_periph, uint32_t dmacmd); + +/* flag & interrupt functions */ +/* get USART flag status */ +FlagStatus usart_flag_get(uint32_t usart_periph, usart_flag_enum flag); +/* clear USART flag status */ +void usart_flag_clear(uint32_t usart_periph, usart_flag_enum flag); +/* enable USART interrupt */ +void usart_interrupt_enable(uint32_t usart_periph, usart_interrupt_enum interrupt); +/* disable USART interrupt */ +void usart_interrupt_disable(uint32_t usart_periph, usart_interrupt_enum interrupt); +/* get USART interrupt and flag status */ +FlagStatus usart_interrupt_flag_get(uint32_t usart_periph, usart_interrupt_flag_enum int_flag); +/* clear interrupt flag and flag status */ +void usart_interrupt_flag_clear(uint32_t usart_periph, usart_interrupt_flag_enum int_flag); + +#endif /* GD32F5XX_USART_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_wwdgt.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_wwdgt.h new file mode 100644 index 0000000..3700d39 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Include/gd32f5xx_wwdgt.h @@ -0,0 +1,107 @@ +/*! + \file gd32f5xx_wwdgt.h + \brief definitions for the WWDGT + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 GD32F5XX_WWDGT_H +#define GD32F5XX_WWDGT_H + +#include "gd32f5xx.h" + +/* WWDGT definitions */ +#define WWDGT WWDGT_BASE /*!< WWDGT base address */ + +/* registers definitions */ +#define WWDGT_CTL REG32((WWDGT) + 0x00U) /*!< WWDGT control register */ +#define WWDGT_CFG REG32((WWDGT) + 0x04U) /*!< WWDGT configuration register */ +#define WWDGT_STAT REG32((WWDGT) + 0x08U) /*!< WWDGT status register */ + +/* bits definitions */ +/* WWDGT_CTL */ +#define WWDGT_CTL_CNT BITS(0,6) /*!< WWDGT counter value */ +#define WWDGT_CTL_WDGTEN BIT(7) /*!< WWDGT counter enable */ + +/* WWDGT_CFG */ +#define WWDGT_CFG_WIN BITS(0,6) /*!< WWDGT counter window value */ +#define WWDGT_CFG_PSC (BITS(7,8) | BITS(10,12)) /*!< WWDGT prescaler divider value */ +#define WWDGT_CFG_EWIE BIT(9) /*!< early wakeup interrupt enable */ + +/* WWDGT_STAT */ +#define WWDGT_STAT_EWIF BIT(0) /*!< early wakeup interrupt flag */ + +/* constants definitions */ +#define CFG_PSCL(regval) (BITS(7,8) & ((uint32_t)(regval) << 7)) /*!< write value to WWDGT_CFG_PSC bit field */ +#define CFG_PSCH(regval) (BITS(10,12) & ((uint32_t)(regval) << 10)) /*!< write value to WWDGT_CFG_PSC bit field */ +#define WWDGT_CFG_PSC_DIV1 CFG_PSCL(0) /*!< the time base of WWDGT = (PCLK1/4096)/1 */ +#define WWDGT_CFG_PSC_DIV2 CFG_PSCL(1) /*!< the time base of WWDGT = (PCLK1/4096)/2 */ +#define WWDGT_CFG_PSC_DIV4 CFG_PSCL(2) /*!< the time base of WWDGT = (PCLK1/4096)/4 */ +#define WWDGT_CFG_PSC_DIV8 CFG_PSCL(3) /*!< the time base of WWDGT = (PCLK1/4096)/8 */ +#define WWDGT_CFG_PSC_DIV16 (CFG_PSCH(1)|CFG_PSCL(0)) /*!< the time base of WWDGT = (PCLK1/4096)/16 */ +#define WWDGT_CFG_PSC_DIV32 (CFG_PSCH(1)|CFG_PSCL(1)) /*!< the time base of WWDGT = (PCLK1/4096)/32 */ +#define WWDGT_CFG_PSC_DIV64 (CFG_PSCH(1)|CFG_PSCL(2)) /*!< the time base of WWDGT = (PCLK1/4096)/64 */ +#define WWDGT_CFG_PSC_DIV128 (CFG_PSCH(1)|CFG_PSCL(3)) /*!< the time base of WWDGT = (PCLK1/4096)/128 */ +#define WWDGT_CFG_PSC_DIV256 (CFG_PSCH(2)|CFG_PSCL(0)) /*!< the time base of WWDGT = (PCLK1/4096)/256 */ +#define WWDGT_CFG_PSC_DIV512 (CFG_PSCH(2)|CFG_PSCL(1)) /*!< the time base of WWDGT = (PCLK1/4096)/512 */ +#define WWDGT_CFG_PSC_DIV1024 (CFG_PSCH(2)|CFG_PSCL(2)) /*!< the time base of WWDGT = (PCLK1/4096)/1024 */ +#define WWDGT_CFG_PSC_DIV2048 (CFG_PSCH(2)|CFG_PSCL(3)) /*!< the time base of WWDGT = (PCLK1/4096)/2048 */ +#define WWDGT_CFG_PSC_DIV4096 (CFG_PSCH(3)|CFG_PSCL(0)) /*!< the time base of WWDGT = (PCLK1/4096)/4096 */ +#define WWDGT_CFG_PSC_DIV8192 (CFG_PSCH(3)|CFG_PSCL(1)) /*!< the time base of WWDGT = (PCLK1/4096)/8192 */ +#define WWDGT_CFG_PSC_DIV16384 (CFG_PSCH(3)|CFG_PSCL(2)) /*!< the time base of WWDGT = (PCLK1/4096)/16384 */ +#define WWDGT_CFG_PSC_DIV32768 (CFG_PSCH(3)|CFG_PSCL(3)) /*!< the time base of WWDGT = (PCLK1/4096)/32768 */ +#define WWDGT_CFG_PSC_DIV65536 (CFG_PSCH(4)|CFG_PSCL(0)) /*!< the time base of WWDGT = (PCLK1/4096)/65536 */ +#define WWDGT_CFG_PSC_DIV131072 (CFG_PSCH(4)|CFG_PSCL(1)) /*!< the time base of WWDGT = (PCLK1/4096)/131072 */ +#define WWDGT_CFG_PSC_DIV262144 (CFG_PSCH(4)|CFG_PSCL(2)) /*!< the time base of WWDGT = (PCLK1/4096)/262144 */ + +/* write value to WWDGT_CTL_CNT bit field */ +#define CTL_CNT(regval) (BITS(0,6) & ((uint32_t)(regval) << 0)) +/* write value to WWDGT_CFG_WIN bit field */ +#define CFG_WIN(regval) (BITS(0,6) & ((uint32_t)(regval) << 0)) + +/* function declarations */ +/* reset the window watchdog timer configuration */ +void wwdgt_deinit(void); +/* start the window watchdog timer counter */ +void wwdgt_enable(void); + +/* configure the window watchdog timer counter value */ +void wwdgt_counter_update(uint16_t counter_value); +/* configure counter value, window value, and prescaler divider value */ +void wwdgt_config(uint16_t counter, uint16_t window, uint32_t prescaler); + +/* check early wakeup interrupt state of WWDGT */ +FlagStatus wwdgt_flag_get(void); +/* clear early wakeup interrupt state of WWDGT */ +void wwdgt_flag_clear(void); +/* enable early wakeup interrupt of WWDGT */ +void wwdgt_interrupt_enable(void); + +#endif /* GD32F5XX_WWDGT_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_adc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_adc.c new file mode 100644 index 0000000..8f7b862 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_adc.c @@ -0,0 +1,1200 @@ +/*! + \file gd32f5xx_adc.c + \brief ADC driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_adc.h" + +#define ROUTINE_TRIGGER_MODE ((uint32_t)28U) +#define INSERTED_TRIGGER_MODE ((uint32_t)20U) +/* discontinuous mode macro*/ +#define ADC_CHANNEL_LENGTH_SUBTRACT_ONE ((uint8_t)1U) + +/* ADC routine channel macro */ +#define ADC_ROUTINE_CHANNEL_RANK_SIX ((uint8_t)6U) +#define ADC_ROUTINE_CHANNEL_RANK_TWELVE ((uint8_t)12U) +#define ADC_ROUTINE_CHANNEL_RANK_SIXTEEN ((uint8_t)16U) +#define ADC_ROUTINE_CHANNEL_RANK_LENGTH ((uint8_t)5U) + +/* ADC sampling time macro */ +#define ADC_CHANNEL_SAMPLE_TEN ((uint8_t)10U) +#define ADC_CHANNEL_SAMPLE_EIGHTEEN ((uint8_t)18U) +#define ADC_CHANNEL_SAMPLE_LENGTH ((uint8_t)3U) + +/* ADC inserted channel macro */ +#define ADC_INSERTED_CHANNEL_RANK_LENGTH ((uint8_t)5U) +#define ADC_INSERTED_CHANNEL_SHIFT_LENGTH ((uint8_t)15U) + +/* ADC inserted channel offset macro */ +#define ADC_OFFSET_LENGTH ((uint8_t)3U) +#define ADC_OFFSET_SHIFT_LENGTH ((uint8_t)4U) + +/*! + \brief reset ADC + \param[in] none + \param[out] none + \retval none +*/ +void adc_deinit(void) +{ + rcu_periph_reset_enable(RCU_ADCRST); + rcu_periph_reset_disable(RCU_ADCRST); +} + +/*! + \brief configure the ADC clock for all the ADCs + \param[in] prescaler: configure ADCs prescaler ratio + only one parameter can be selected which is shown as below: + \arg ADC_ADCCK_PCLK2_DIV2: PCLK2 div2 + \arg ADC_ADCCK_PCLK2_DIV4: PCLK2 div4 + \arg ADC_ADCCK_PCLK2_DIV6: PCLK2 div6 + \arg ADC_ADCCK_PCLK2_DIV8: PCLK2 div8 + \arg ADC_ADCCK_HCLK_DIV5: HCLK div5 + \arg ADC_ADCCK_HCLK_DIV6: HCLK div6 + \arg ADC_ADCCK_HCLK_DIV10: HCLK div10 + \arg ADC_ADCCK_HCLK_DIV20: HCLK div20 + \param[out] none + \retval none +*/ +void adc_clock_config(uint32_t prescaler) +{ + ADC_SYNCCTL &= ~((uint32_t)ADC_SYNCCTL_ADCCK); + ADC_SYNCCTL |= (uint32_t) prescaler; +} + +/*! + \brief enable or disable ADC special function + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] function: the function to config + only one parameter can be selected which is shown as below: + \arg ADC_SCAN_MODE: scan mode select + \arg ADC_INSERTED_CHANNEL_AUTO: inserted sequence convert automatically + \arg ADC_CONTINUOUS_MODE: continuous mode select + \param[in] newvalue: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void adc_special_function_config(uint32_t adc_periph, uint32_t function, ControlStatus newvalue) +{ + if(newvalue) { + if(0U != (function & ADC_SCAN_MODE)) { + /* enable scan mode */ + ADC_CTL0(adc_periph) |= ADC_SCAN_MODE; + } + if(0U != (function & ADC_INSERTED_CHANNEL_AUTO)) { + /* enable inserted sequence convert automatically */ + ADC_CTL0(adc_periph) |= ADC_INSERTED_CHANNEL_AUTO; + } + if(0U != (function & ADC_CONTINUOUS_MODE)) { + /* enable continuous mode */ + ADC_CTL1(adc_periph) |= ADC_CONTINUOUS_MODE; + } + } else { + if(0U != (function & ADC_SCAN_MODE)) { + /* disable scan mode */ + ADC_CTL0(adc_periph) &= ~ADC_SCAN_MODE; + } + if(0U != (function & ADC_INSERTED_CHANNEL_AUTO)) { + /* disable inserted sequence convert automatically */ + ADC_CTL0(adc_periph) &= ~ADC_INSERTED_CHANNEL_AUTO; + } + if(0U != (function & ADC_CONTINUOUS_MODE)) { + /* disable continuous mode */ + ADC_CTL1(adc_periph) &= ~ADC_CONTINUOUS_MODE; + } + } +} + +/*! + \brief configure ADC data alignment + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] data_alignment: data alignment select + only one parameter can be selected which is shown as below: + \arg ADC_DATAALIGN_RIGHT: LSB alignment + \arg ADC_DATAALIGN_LEFT: MSB alignment + \param[out] none + \retval none +*/ +void adc_data_alignment_config(uint32_t adc_periph, uint32_t data_alignment) +{ + if(ADC_DATAALIGN_RIGHT != data_alignment) { + /* MSB alignment */ + ADC_CTL1(adc_periph) |= ADC_CTL1_DAL; + } else { + /* LSB alignment */ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_DAL); + } +} + +/*! + \brief enable ADC interface + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_enable(uint32_t adc_periph) +{ + if(RESET == (ADC_CTL1(adc_periph) & ADC_CTL1_ADCON)) { + /* enable ADC */ + ADC_CTL1(adc_periph) |= (uint32_t)ADC_CTL1_ADCON; + } +} + +/*! + \brief disable ADC interface + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_disable(uint32_t adc_periph) +{ + /* disable ADC */ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_ADCON); +} + +/*! + \brief ADC calibration and reset calibration + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_calibration_enable(uint32_t adc_periph) +{ + /* reset the selected ADC calibration registers */ + ADC_CTL1(adc_periph) |= (uint32_t) ADC_CTL1_RSTCLB; + /* check the RSTCLB bit state */ + while(RESET != (ADC_CTL1(adc_periph) & ADC_CTL1_RSTCLB)) { + } + /* enable ADC calibration process */ + ADC_CTL1(adc_periph) |= ADC_CTL1_CLB; + /* check the CLB bit state */ + while(RESET != (ADC_CTL1(adc_periph) & ADC_CTL1_CLB)) { + } +} + +/*! + \brief configure temperature sensor and internal reference voltage channel or VBAT channel function + \param[in] function: temperature sensor and internal reference voltage channel or VBAT channel + only one parameter can be selected which is shown as below: + \arg ADC_VBAT_CHANNEL_SWITCH: channel 18 (1/4 voltate of external battery) switch of ADC0 + \arg ADC_TEMP_VREF_CHANNEL_SWITCH: channel 16 (temperature sensor) and 17 (internal reference voltage) switch of ADC0 + \param[in] newvalue: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void adc_channel_16_to_18(uint32_t function, ControlStatus newvalue) +{ + if(newvalue) { + if(RESET != (function & ADC_VBAT_CHANNEL_SWITCH)) { + /* enable ADC0 Vbat channel */ + ADC_SYNCCTL |= ADC_VBAT_CHANNEL_SWITCH; + } + if(RESET != (function & ADC_TEMP_VREF_CHANNEL_SWITCH)) { + /* enable ADC0 Vref and Temperature channel */ + ADC_SYNCCTL |= ADC_TEMP_VREF_CHANNEL_SWITCH; + } + } else { + if(RESET != (function & ADC_VBAT_CHANNEL_SWITCH)) { + /* disable ADC0 Vbat channel */ + ADC_SYNCCTL &= ~ADC_VBAT_CHANNEL_SWITCH; + } + if(RESET != (function & ADC_TEMP_VREF_CHANNEL_SWITCH)) { + /* disable ADC0 Vref and Temperature channel */ + ADC_SYNCCTL &= ~ADC_TEMP_VREF_CHANNEL_SWITCH; + } + } +} + +/*! + \brief configure ADC resolution + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] resolution: ADC resolution + only one parameter can be selected which is shown as below: + \arg ADC_RESOLUTION_12B: 12-bit ADC resolution + \arg ADC_RESOLUTION_10B: 10-bit ADC resolution + \arg ADC_RESOLUTION_8B: 8-bit ADC resolution + \arg ADC_RESOLUTION_6B: 6-bit ADC resolution + \param[out] none + \retval none +*/ +void adc_resolution_config(uint32_t adc_periph, uint32_t resolution) +{ + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_DRES); + ADC_CTL0(adc_periph) |= (uint32_t)resolution; +} + +/*! + \brief configure ADC oversample mode + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] mode: ADC oversampling mode + only one parameter can be selected which is shown as below: + \arg ADC_OVERSAMPLING_ALL_CONVERT: all oversampled conversions for a channel are done consecutively after a trigger + \arg ADC_OVERSAMPLING_ONE_CONVERT: each oversampled conversion for a channel needs a trigger + \param[in] shift: ADC oversampling shift + only one parameter can be selected which is shown as below: + \arg ADC_OVERSAMPLING_SHIFT_NONE: no oversampling shift + \arg ADC_OVERSAMPLING_SHIFT_1B: 1-bit oversampling shift + \arg ADC_OVERSAMPLING_SHIFT_2B: 2-bit oversampling shift + \arg ADC_OVERSAMPLING_SHIFT_3B: 3-bit oversampling shift + \arg ADC_OVERSAMPLING_SHIFT_4B: 3-bit oversampling shift + \arg ADC_OVERSAMPLING_SHIFT_5B: 5-bit oversampling shift + \arg ADC_OVERSAMPLING_SHIFT_6B: 6-bit oversampling shift + \arg ADC_OVERSAMPLING_SHIFT_7B: 7-bit oversampling shift + \arg ADC_OVERSAMPLING_SHIFT_8B: 8-bit oversampling shift + \param[in] ratio: ADC oversampling ratio + only one parameter can be selected which is shown as below: + \arg ADC_OVERSAMPLING_RATIO_MUL2: oversampling ratio multiple 2 + \arg ADC_OVERSAMPLING_RATIO_MUL4: oversampling ratio multiple 4 + \arg ADC_OVERSAMPLING_RATIO_MUL8: oversampling ratio multiple 8 + \arg ADC_OVERSAMPLING_RATIO_MUL16: oversampling ratio multiple 16 + \arg ADC_OVERSAMPLING_RATIO_MUL32: oversampling ratio multiple 32 + \arg ADC_OVERSAMPLING_RATIO_MUL64: oversampling ratio multiple 64 + \arg ADC_OVERSAMPLING_RATIO_MUL128: oversampling ratio multiple 128 + \arg ADC_OVERSAMPLING_RATIO_MUL256: oversampling ratio multiple 256 + \param[out] none + \retval none +*/ +void adc_oversample_mode_config(uint32_t adc_periph, uint32_t mode, uint16_t shift, uint8_t ratio) +{ + if(ADC_OVERSAMPLING_ONE_CONVERT == mode) { + ADC_OVSAMPCTL(adc_periph) |= (uint32_t)ADC_OVSAMPCTL_TOVS; + } else { + ADC_OVSAMPCTL(adc_periph) &= ~((uint32_t)ADC_OVSAMPCTL_TOVS); + } + /* config the shift and ratio */ + ADC_OVSAMPCTL(adc_periph) &= ~((uint32_t)(ADC_OVSAMPCTL_OVSR | ADC_OVSAMPCTL_OVSS)); + ADC_OVSAMPCTL(adc_periph) |= ((uint32_t)shift | (uint32_t)ratio); +} + +/*! + \brief enable ADC oversample mode + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_oversample_mode_enable(uint32_t adc_periph) +{ + ADC_OVSAMPCTL(adc_periph) |= ADC_OVSAMPCTL_OVSEN; +} + +/*! + \brief disable ADC oversample mode + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_oversample_mode_disable(uint32_t adc_periph) +{ + ADC_OVSAMPCTL(adc_periph) &= ~((uint32_t)ADC_OVSAMPCTL_OVSEN); +} + +/*! + \brief enable DMA request + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_dma_mode_enable(uint32_t adc_periph) +{ + /* enable DMA request */ + ADC_CTL1(adc_periph) |= (uint32_t)(ADC_CTL1_DMA); +} + +/*! + \brief disable DMA request + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_dma_mode_disable(uint32_t adc_periph) +{ + /* disable DMA request */ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_DMA); +} + +/*! + \brief when DMA=1, the DMA engine issues a request at end of each routine conversion + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_dma_request_after_last_enable(uint32_t adc_periph) +{ + ADC_CTL1(adc_periph) |= (uint32_t)(ADC_CTL1_DDM); +} + +/*! + \brief the DMA engine is disabled after the end of transfer signal from DMA controller is detected + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_dma_request_after_last_disable(uint32_t adc_periph) +{ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_DDM); +} + +/*! + \brief configure ADC discontinuous mode + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_sequence: select the sequence + only one parameter can be selected which is shown as below: + \arg ADC_ROUTINE_CHANNEL: routine sequence + \arg ADC_INSERTED_CHANNEL: inserted sequence + \arg ADC_CHANNEL_DISCON_DISABLE: disable discontinuous mode of routine & inserted channel + \param[in] length: number of conversions in discontinuous mode,the number can be 1..8 + for routine sequence ,the number has no effect for inserted sequence + \param[out] none + \retval none +*/ +void adc_discontinuous_mode_config(uint32_t adc_periph, uint8_t adc_sequence, uint8_t length) +{ + /* disable discontinuous mode of routine & inserted channel */ + ADC_CTL0(adc_periph) &= ~((uint32_t)(ADC_CTL0_DISRC | ADC_CTL0_DISIC)); + switch(adc_sequence) { + case ADC_ROUTINE_CHANNEL: + /* config the number of conversions in discontinuous mode */ + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_DISNUM); + if((length <= 8U) && (length >= 1U)) { + ADC_CTL0(adc_periph) |= CTL0_DISNUM(((uint32_t)length - ADC_CHANNEL_LENGTH_SUBTRACT_ONE)); + } + /* enable routine sequence discontinuous mode */ + ADC_CTL0(adc_periph) |= (uint32_t)ADC_CTL0_DISRC; + break; + case ADC_INSERTED_CHANNEL: + /* enable inserted sequence discontinuous mode */ + ADC_CTL0(adc_periph) |= (uint32_t)ADC_CTL0_DISIC; + break; + case ADC_CHANNEL_DISCON_DISABLE: + /* disable discontinuous mode of routine & inserted channel */ + default: + break; + } +} + +/*! + \brief configure the length of routine sequence or inserted sequence + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_sequence: select the sequence + only one parameter can be selected which is shown as below: + \arg ADC_ROUTINE_CHANNEL: routine sequence + \arg ADC_INSERTED_CHANNEL: inserted sequence + \param[in] length: the length of the channel + routine channel 1-16 + inserted channel 1-4 + \param[out] none + \retval none +*/ +void adc_channel_length_config(uint32_t adc_periph, uint8_t adc_sequence, uint32_t length) +{ + switch(adc_sequence) { + case ADC_ROUTINE_CHANNEL: + if((length >= 1U) && (length <= 16U)) { + ADC_RSQ0(adc_periph) &= ~((uint32_t)ADC_RSQ0_RL); + ADC_RSQ0(adc_periph) |= RSQ0_RL((uint32_t)(length - ADC_CHANNEL_LENGTH_SUBTRACT_ONE)); + } + break; + case ADC_INSERTED_CHANNEL: + if((length >= 1U) && (length <= 4U)) { + ADC_ISQ(adc_periph) &= ~((uint32_t)ADC_ISQ_IL); + ADC_ISQ(adc_periph) |= ISQ_IL((uint32_t)(length - ADC_CHANNEL_LENGTH_SUBTRACT_ONE)); + } + break; + default: + break; + } +} + +/*! + \brief configure ADC routine channel + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] rank: the routine sequence rank,this parameter must be between 0 to 15 + \param[in] adc_channel: the selected ADC channel + only one parameter can be selected which is shown as below: + \arg ADC_CHANNEL_x(x=0..18): ADC channelx + \param[in] sample_time: the sample time value + only one parameter can be selected which is shown as below: + \arg ADC_SAMPLETIME_3: 3 cycles + \arg ADC_SAMPLETIME_15: 15 cycles + \arg ADC_SAMPLETIME_28: 28 cycles + \arg ADC_SAMPLETIME_56: 56 cycles + \arg ADC_SAMPLETIME_84: 84 cycles + \arg ADC_SAMPLETIME_112: 112 cycles + \arg ADC_SAMPLETIME_144: 144 cycles + \arg ADC_SAMPLETIME_480: 480 cycles + \param[out] none + \retval none +*/ +void adc_routine_channel_config(uint32_t adc_periph, uint8_t rank, uint8_t adc_channel, uint32_t sample_time) +{ + uint32_t rsq, sampt; + + /* ADC routine sequence config */ + if(rank < ADC_ROUTINE_CHANNEL_RANK_SIX) { + /* the routine sequence rank is smaller than six */ + rsq = ADC_RSQ2(adc_periph); + rsq &= ~((uint32_t)(ADC_RSQX_RSQN << (ADC_ROUTINE_CHANNEL_RANK_LENGTH * rank))); + /* the channel number is written to these bits to select a channel as the nth conversion in the routine sequence */ + rsq |= ((uint32_t)adc_channel << (ADC_ROUTINE_CHANNEL_RANK_LENGTH * rank)); + ADC_RSQ2(adc_periph) = rsq; + } else if(rank < ADC_ROUTINE_CHANNEL_RANK_TWELVE) { + /* the routine sequence rank is smaller than twelve */ + rsq = ADC_RSQ1(adc_periph); + rsq &= ~((uint32_t)(ADC_RSQX_RSQN << (ADC_ROUTINE_CHANNEL_RANK_LENGTH * (rank - ADC_ROUTINE_CHANNEL_RANK_SIX)))); + /* the channel number is written to these bits to select a channel as the nth conversion in the routine sequence */ + rsq |= ((uint32_t)adc_channel << (ADC_ROUTINE_CHANNEL_RANK_LENGTH * (rank - ADC_ROUTINE_CHANNEL_RANK_SIX))); + ADC_RSQ1(adc_periph) = rsq; + } else if(rank < ADC_ROUTINE_CHANNEL_RANK_SIXTEEN) { + /* the routine sequence rank is smaller than sixteen */ + rsq = ADC_RSQ0(adc_periph); + rsq &= ~((uint32_t)(ADC_RSQX_RSQN << (ADC_ROUTINE_CHANNEL_RANK_LENGTH * (rank - ADC_ROUTINE_CHANNEL_RANK_TWELVE)))); + /* the channel number is written to these bits to select a channel as the nth conversion in the routine sequence */ + rsq |= ((uint32_t)adc_channel << (ADC_ROUTINE_CHANNEL_RANK_LENGTH * (rank - ADC_ROUTINE_CHANNEL_RANK_TWELVE))); + ADC_RSQ0(adc_periph) = rsq; + } else { + } + + /* ADC sampling time config */ + if(adc_channel < ADC_CHANNEL_SAMPLE_TEN) { + /* the routine sequence rank is smaller than ten */ + sampt = ADC_SAMPT1(adc_periph); + sampt &= ~((uint32_t)(ADC_SAMPTX_SPTN << (ADC_CHANNEL_SAMPLE_LENGTH * adc_channel))); + /* channel sample time set*/ + sampt |= (uint32_t)(sample_time << (ADC_CHANNEL_SAMPLE_LENGTH * adc_channel)); + ADC_SAMPT1(adc_periph) = sampt; + } else if(adc_channel <= ADC_CHANNEL_SAMPLE_EIGHTEEN) { + /* the routine sequence rank is smaller than eighteen */ + sampt = ADC_SAMPT0(adc_periph); + sampt &= ~((uint32_t)(ADC_SAMPTX_SPTN << (ADC_CHANNEL_SAMPLE_LENGTH * (adc_channel - ADC_CHANNEL_SAMPLE_TEN)))); + /* channel sample time set*/ + sampt |= (uint32_t)(sample_time << (ADC_CHANNEL_SAMPLE_LENGTH * (adc_channel - ADC_CHANNEL_SAMPLE_TEN))); + ADC_SAMPT0(adc_periph) = sampt; + } else { + } +} + +/*! + \brief configure ADC inserted channel + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] rank: the inserted sequence rank,this parameter must be between 0 to 3 + \param[in] adc_channel: the selected ADC channel + only one parameter can be selected which is shown as below: + \arg ADC_CHANNEL_x(x=0..18): ADC Channelx + \param[in] sample_time: The sample time value + only one parameter can be selected which is shown as below: + \arg ADC_SAMPLETIME_3: 3 cycles + \arg ADC_SAMPLETIME_15: 15 cycles + \arg ADC_SAMPLETIME_28: 28 cycles + \arg ADC_SAMPLETIME_56: 56 cycles + \arg ADC_SAMPLETIME_84: 84 cycles + \arg ADC_SAMPLETIME_112: 112 cycles + \arg ADC_SAMPLETIME_144: 144 cycles + \arg ADC_SAMPLETIME_480: 480 cycles + \param[out] none + \retval none +*/ +void adc_inserted_channel_config(uint32_t adc_periph, uint8_t rank, uint8_t adc_channel, uint32_t sample_time) +{ + uint8_t inserted_length; + uint32_t isq, sampt; + + /* get inserted sequence length */ + inserted_length = (uint8_t)GET_BITS(ADC_ISQ(adc_periph), 20U, 21U); + /* the channel number is written to these bits to select a channel as the nth conversion in the inserted sequence */ + if(rank < 4U) { + isq = ADC_ISQ(adc_periph); + isq &= ~((uint32_t)(ADC_ISQ_ISQN << (ADC_INSERTED_CHANNEL_SHIFT_LENGTH - (inserted_length - rank) * ADC_INSERTED_CHANNEL_RANK_LENGTH))); + isq |= ((uint32_t)adc_channel << (ADC_INSERTED_CHANNEL_SHIFT_LENGTH - (inserted_length - rank) * ADC_INSERTED_CHANNEL_RANK_LENGTH)); + ADC_ISQ(adc_periph) = isq; + } + + /* ADC sampling time config */ + if(adc_channel < ADC_CHANNEL_SAMPLE_TEN) { + /* the inserted sequence rank is smaller than ten */ + sampt = ADC_SAMPT1(adc_periph); + sampt &= ~((uint32_t)(ADC_SAMPTX_SPTN << (ADC_CHANNEL_SAMPLE_LENGTH * adc_channel))); + /* channel sample time set*/ + sampt |= (uint32_t) sample_time << (ADC_CHANNEL_SAMPLE_LENGTH * adc_channel); + ADC_SAMPT1(adc_periph) = sampt; + } else if(adc_channel <= ADC_CHANNEL_SAMPLE_EIGHTEEN) { + /* the inserted sequence rank is smaller than eighteen */ + sampt = ADC_SAMPT0(adc_periph); + sampt &= ~((uint32_t)(ADC_SAMPTX_SPTN << (ADC_CHANNEL_SAMPLE_LENGTH * (adc_channel - ADC_CHANNEL_SAMPLE_TEN)))); + /* channel sample time set*/ + sampt |= ((uint32_t)sample_time << (ADC_CHANNEL_SAMPLE_LENGTH * (adc_channel - ADC_CHANNEL_SAMPLE_TEN))); + ADC_SAMPT0(adc_periph) = sampt; + } else { + } +} + +/*! + \brief configure ADC inserted channel offset + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] inserted_channel : insert channel select + only one parameter can be selected which is shown as below: + \arg ADC_INSERTED_CHANNEL_0: inserted channel0 + \arg ADC_INSERTED_CHANNEL_1: inserted channel1 + \arg ADC_INSERTED_CHANNEL_2: inserted channel2 + \arg ADC_INSERTED_CHANNEL_3: inserted channel3 + \param[in] offset : the offset data + \param[out] none + \retval none +*/ +void adc_inserted_channel_offset_config(uint32_t adc_periph, uint8_t inserted_channel, uint16_t offset) +{ + uint8_t inserted_length; + uint32_t num = 0U; + + inserted_length = (uint8_t)GET_BITS(ADC_ISQ(adc_periph), 20U, 21U); + num = ((uint32_t)ADC_OFFSET_LENGTH - ((uint32_t)inserted_length - (uint32_t)inserted_channel)); + + if(num <= ADC_OFFSET_LENGTH) { + /* calculate the offset of the register */ + num = num * ADC_OFFSET_SHIFT_LENGTH; + /* config the offset of the selected channels */ + REG32((adc_periph) + 0x14U + num) = IOFFX_IOFF((uint32_t)offset); + } +} + +/*! + \brief configure ADC external trigger source + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_sequence: select the sequence + only one parameter can be selected which is shown as below: + \arg ADC_ROUTINE_CHANNEL: routine sequence + \arg ADC_INSERTED_CHANNEL: inserted sequence + \param[in] external_trigger_source: routine or inserted sequence trigger source + for routine sequence: + only one parameter can be selected which is shown as below: + \arg ADC_EXTTRIG_ROUTINE_T0_CH0: external trigger timer 0 CC0 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T0_CH1: external trigger timer 0 CC1 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T0_CH2: external trigger timer 0 CC2 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T1_CH1: external trigger timer 1 CC1 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T1_CH2: external trigger timer 1 CC2 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T1_CH3: external trigger timer 1 CC3 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T1_TRGO: external trigger timer 1 TRGO event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T2_CH0 : external trigger timer 2 CC0 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T2_TRGO : external trigger timer 2 TRGO event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T3_CH3: external trigger timer 3 CC3 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T4_CH0: external trigger timer 4 CC0 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T4_CH1: external trigger timer 4 CC1 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T4_CH2: external trigger timer 4 CC2 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T7_CH0: external trigger timer 7 CC0 event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_T7_TRGO: external trigger timer 7 TRGO event select for routine sequence + \arg ADC_EXTTRIG_ROUTINE_EXTI_11: external trigger extiline 11 select for routine sequence + for inserted sequence: + only one parameter can be selected which is shown as below: + \arg ADC_EXTTRIG_INSERTED_T0_CH3: timer0 capture compare 3 + \arg ADC_EXTTRIG_INSERTED_T0_TRGO: timer0 TRGO event + \arg ADC_EXTTRIG_INSERTED_T1_CH0: timer1 capture compare 0 + \arg ADC_EXTTRIG_INSERTED_T1_TRGO: timer1 TRGO event + \arg ADC_EXTTRIG_INSERTED_T2_CH1: timer2 capture compare 1 + \arg ADC_EXTTRIG_INSERTED_T2_CH3: timer2 capture compare 3 + \arg ADC_EXTTRIG_INSERTED_T3_CH0: timer3 capture compare 0 + \arg ADC_EXTTRIG_INSERTED_T3_CH1: timer3 capture compare 1 + \arg ADC_EXTTRIG_INSERTED_T3_CH2: timer3 capture compare 2 + \arg ADC_EXTTRIG_INSERTED_T3_TRGO: timer3 capture compare TRGO + \arg ADC_EXTTRIG_INSERTED_T4_CH3: timer4 capture compare 3 + \arg ADC_EXTTRIG_INSERTED_T4_TRGO: timer4 capture compare TRGO + \arg ADC_EXTTRIG_INSERTED_T7_CH1: timer7 capture compare 1 + \arg ADC_EXTTRIG_INSERTED_T7_CH2: timer7 capture compare 2 + \arg ADC_EXTTRIG_INSERTED_T7_CH3: timer7 capture compare 3 + \arg ADC_EXTTRIG_INSERTED_EXTI_15: external interrupt line 15 + \param[out] none + \retval none +*/ +void adc_external_trigger_source_config(uint32_t adc_periph, uint8_t adc_sequence, uint32_t external_trigger_source) +{ + switch(adc_sequence) { + case ADC_ROUTINE_CHANNEL: + /* configure ADC routine sequence external trigger source */ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_ETSRC); + ADC_CTL1(adc_periph) |= (uint32_t)external_trigger_source; + break; + case ADC_INSERTED_CHANNEL: + /* configure ADC inserted sequence external trigger source */ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_ETSIC); + ADC_CTL1(adc_periph) |= (uint32_t)external_trigger_source; + break; + default: + break; + } +} + +/*! + \brief enable ADC external trigger + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_sequence: select the sequence + only one parameter can be selected which is shown as below: + \arg ADC_ROUTINE_CHANNEL: routine sequence + \arg ADC_INSERTED_CHANNEL: inserted sequence + \param[in] trigger_mode: external trigger mode + only one parameter can be selected which is shown as below: + \arg EXTERNAL_TRIGGER_DISABLE: external trigger disable + \arg EXTERNAL_TRIGGER_RISING: rising edge of external trigger + \arg EXTERNAL_TRIGGER_FALLING: falling edge of external trigger + \arg EXTERNAL_TRIGGER_RISING_FALLING: rising and falling edge of external trigger + \param[out] none + \retval none +*/ +void adc_external_trigger_config(uint32_t adc_periph, uint8_t adc_sequence, uint32_t trigger_mode) +{ + switch(adc_sequence) { + case ADC_ROUTINE_CHANNEL: + /* configure ADC routine sequence external trigger mode */ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_ETMRC); + ADC_CTL1(adc_periph) |= (uint32_t)(trigger_mode << ROUTINE_TRIGGER_MODE); + break; + case ADC_INSERTED_CHANNEL: + /* configure ADC inserted sequence external trigger mode */ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_ETMIC); + ADC_CTL1(adc_periph) |= (uint32_t)(trigger_mode << INSERTED_TRIGGER_MODE); + break; + default: + break; + } +} + +/*! + \brief enable ADC software trigger + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_sequence: select the sequence + only one parameter can be selected which is shown as below: + \arg ADC_ROUTINE_CHANNEL: routine sequence + \arg ADC_INSERTED_CHANNEL: inserted sequence + \param[out] none + \retval none +*/ +void adc_software_trigger_enable(uint32_t adc_periph, uint8_t adc_sequence) +{ + switch(adc_sequence) { + case ADC_ROUTINE_CHANNEL: + /* enable ADC routine sequence software trigger */ + ADC_CTL1(adc_periph) |= (uint32_t)ADC_CTL1_SWRCST; + break; + case ADC_INSERTED_CHANNEL: + /* enable ADC inserted sequence software trigger */ + ADC_CTL1(adc_periph) |= (uint32_t)ADC_CTL1_SWICST; + break; + default: + break; + } +} + +/*! + \brief configure end of conversion mode + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] end_selection: end of conversion mode + only one parameter can be selected which is shown as below: + \arg ADC_EOC_SET_SEQUENCE: only at the end of a sequence of routine conversions, the EOC bit is set.Overflow detection is disabled unless DMA=1. + \arg ADC_EOC_SET_CONVERSION: at the end of each routine conversion, the EOC bit is set.Overflow is detected automatically. + \param[out] none + \retval none +*/ +void adc_end_of_conversion_config(uint32_t adc_periph, uint8_t end_selection) +{ + switch(end_selection) { + case ADC_EOC_SET_SEQUENCE: + /* only at the end of a sequence of routine conversions, the EOC bit is set */ + ADC_CTL1(adc_periph) &= ~((uint32_t)ADC_CTL1_EOCM); + break; + case ADC_EOC_SET_CONVERSION: + /* at the end of each routine conversion, the EOC bit is set.Overflow is detected automatically */ + ADC_CTL1(adc_periph) |= (uint32_t)(ADC_CTL1_EOCM); + break; + default: + break; + } +} + +/*! + \brief read ADC routine data register + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] none + \param[out] none + \retval the conversion value +*/ +uint16_t adc_routine_data_read(uint32_t adc_periph) +{ + return (uint16_t)(ADC_RDATA(adc_periph)); +} + +/*! + \brief read ADC inserted data register + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] inserted_channel : insert channel select + only one parameter can be selected which is shown as below: + \arg ADC_INSERTED_CHANNEL_0: inserted channel0 + \arg ADC_INSERTED_CHANNEL_1: inserted channel1 + \arg ADC_INSERTED_CHANNEL_2: inserted channel2 + \arg ADC_INSERTED_CHANNEL_3: inserted channel3 + \param[out] none + \retval the conversion value +*/ +uint16_t adc_inserted_data_read(uint32_t adc_periph, uint8_t inserted_channel) +{ + uint32_t idata; + /* read the data of the selected channel */ + switch(inserted_channel) { + case ADC_INSERTED_CHANNEL_0: + /* read the data of channel 0 */ + idata = ADC_IDATA0(adc_periph); + break; + case ADC_INSERTED_CHANNEL_1: + /* read the data of channel 1 */ + idata = ADC_IDATA1(adc_periph); + break; + case ADC_INSERTED_CHANNEL_2: + /* read the data of channel 2 */ + idata = ADC_IDATA2(adc_periph); + break; + case ADC_INSERTED_CHANNEL_3: + /* read the data of channel 3 */ + idata = ADC_IDATA3(adc_periph); + break; + default: + idata = 0U; + break; + } + return (uint16_t)idata; +} + +/*! + \brief disable ADC analog watchdog single channel + \param[in] adc_periph: ADCx, x=0,1,2 + \param[out] none + \retval none +*/ +void adc_watchdog_single_channel_disable(uint32_t adc_periph) +{ + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_WDSC); +} + +/*! + \brief enable ADC analog watchdog single channel + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_channel: the selected ADC channel + only one parameter can be selected which is shown as below: + \arg ADC_CHANNEL_x: ADC Channelx(x=0..18) + \param[out] none + \retval none +*/ +void adc_watchdog_single_channel_enable(uint32_t adc_periph, uint8_t adc_channel) +{ + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_WDCHSEL); + + /* analog watchdog channel select */ + ADC_CTL0(adc_periph) |= (uint32_t)adc_channel; + ADC_CTL0(adc_periph) |= (uint32_t) ADC_CTL0_WDSC; +} + +/*! + \brief configure ADC analog watchdog sequence channel + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_sequence: the sequence use analog watchdog + only one parameter can be selected which is shown as below: + \arg ADC_ROUTINE_CHANNEL: routine sequence + \arg ADC_INSERTED_CHANNEL: inserted sequence + \arg ADC_ROUTINE_INSERTED_CHANNEL: both routine and inserted sequence + \param[out] none + \retval none +*/ +void adc_watchdog_sequence_channel_enable(uint32_t adc_periph, uint8_t adc_sequence) +{ + ADC_CTL0(adc_periph) &= ~((uint32_t)(ADC_CTL0_RWDEN | ADC_CTL0_IWDEN | ADC_CTL0_WDSC)); + /* select the sequence */ + switch(adc_sequence) { + case ADC_ROUTINE_CHANNEL: + /* routine channel analog watchdog enable */ + ADC_CTL0(adc_periph) |= (uint32_t) ADC_CTL0_RWDEN; + break; + case ADC_INSERTED_CHANNEL: + /* inserted channel analog watchdog enable */ + ADC_CTL0(adc_periph) |= (uint32_t) ADC_CTL0_IWDEN; + break; + case ADC_ROUTINE_INSERTED_CHANNEL: + /* routine and inserted channel analog watchdog enable */ + ADC_CTL0(adc_periph) |= (uint32_t)(ADC_CTL0_RWDEN | ADC_CTL0_IWDEN); + break; + default: + break; + } +} + +/*! + \brief disable ADC analog watchdog + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_sequence: the sequence use analog watchdog + only one parameter can be selected which is shown as below: + \arg ADC_ROUTINE_CHANNEL: routine sequence + \arg ADC_INSERTED_CHANNEL: inserted sequence + \arg ADC_ROUTINE_INSERTED_CHANNEL: both routine and inserted sequence + \param[out] none + \retval none +*/ +void adc_watchdog_disable(uint32_t adc_periph, uint8_t adc_sequence) +{ + /* select the sequence */ + switch(adc_sequence) { + case ADC_ROUTINE_CHANNEL: + /* disable ADC analog watchdog routine sequence */ + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_RWDEN); + break; + case ADC_INSERTED_CHANNEL: + /* disable ADC analog watchdog inserted sequence */ + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_IWDEN); + break; + case ADC_ROUTINE_INSERTED_CHANNEL: + /* disable ADC analog watchdog routine and inserted sequence */ + ADC_CTL0(adc_periph) &= ~((uint32_t)(ADC_CTL0_RWDEN | ADC_CTL0_IWDEN)); + break; + default: + break; + } +} + +/*! + \brief configure ADC analog watchdog threshold + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] low_threshold: analog watchdog low threshold,0..4095 + \param[in] high_threshold: analog watchdog high threshold,0..4095 + \param[out] none + \retval none +*/ +void adc_watchdog_threshold_config(uint32_t adc_periph, uint16_t low_threshold, uint16_t high_threshold) +{ + /* configure ADC analog watchdog low threshold */ + ADC_WDLT(adc_periph) = (uint32_t)WDLT_WDLT(low_threshold); + /* configure ADC analog watchdog high threshold */ + ADC_WDHT(adc_periph) = (uint32_t)WDHT_WDHT(high_threshold); +} + +/*! + \brief configure the ADC sync mode + \param[in] sync_mode: ADC sync mode + only one parameter can be selected which is shown as below: + \arg ADC_SYNC_MODE_INDEPENDENT: all the ADCs work independently + \arg ADC_DAUL_ROUTINE_PARALLEL_INSERTED_PARALLEL: ADC0 and ADC1 work in combined routine parallel & inserted parallel mode + \arg ADC_DAUL_ROUTINE_PARALLEL_INSERTED_ROTATION: ADC0 and ADC1 work in combined routine parallel & trigger rotation mode + \arg ADC_DAUL_INSERTED_PARALLEL: ADC0 and ADC1 work in inserted parallel mode + \arg ADC_DAUL_ROUTINE_PARALLEL: ADC0 and ADC1 work in routine parallel mode + \arg ADC_DAUL_ROUTINE_FOLLOW_UP: ADC0 and ADC1 work in follow-up mode + \arg ADC_DAUL_INSERTED_TRRIGGER_ROTATION: ADC0 and ADC1 work in trigger rotation mode + \arg ADC_ALL_ROUTINE_PARALLEL_INSERTED_PARALLEL: all ADCs work in combined routine parallel & inserted parallel mode + \arg ADC_ALL_ROUTINE_PARALLEL_INSERTED_ROTATION: all ADCs work in combined routine parallel & trigger rotation mode + \arg ADC_ALL_INSERTED_PARALLEL: all ADCs work in inserted parallel mode + \arg ADC_ALL_ROUTINE_PARALLEL: all ADCs work in routine parallel mode + \arg ADC_ALL_ROUTINE_FOLLOW_UP: all ADCs work in follow-up mode + \arg ADC_ALL_INSERTED_TRRIGGER_ROTATION: all ADCs work in trigger rotation mode + \param[out] none + \retval none +*/ +void adc_sync_mode_config(uint32_t sync_mode) +{ + ADC_SYNCCTL &= ~(ADC_SYNCCTL_SYNCM); + ADC_SYNCCTL |= sync_mode; +} + +/*! + \brief configure the delay between 2 sampling phases in ADC sync modes + \param[in] sample_delay: the delay between 2 sampling phases in ADC sync modes + only one parameter can be selected which is shown as below: + \arg ADC_SYNC_DELAY_xCYCLE: x=5..20,the delay between 2 sampling phases in ADC sync modes is x ADC clock cycles + \param[out] none + \retval none +*/ +void adc_sync_delay_config(uint32_t sample_delay) +{ + ADC_SYNCCTL &= ~(ADC_SYNCCTL_SYNCDLY); + ADC_SYNCCTL |= sample_delay; +} + +/*! + \brief configure ADC sync DMA mode selection + \param[in] dma_mode: ADC sync DMA mode + only one parameter can be selected which is shown as below: + \arg ADC_SYNC_DMA_DISABLE: ADC sync DMA disabled + \arg ADC_SYNC_DMA_MODE0: ADC sync DMA mode 0 + \arg ADC_SYNC_DMA_MODE1: ADC sync DMA mode 1 + \param[out] none + \retval none +*/ +void adc_sync_dma_config(uint32_t dma_mode) +{ + ADC_SYNCCTL &= ~(ADC_SYNCCTL_SYNCDMA); + ADC_SYNCCTL |= dma_mode; +} + +/*! + \brief configure ADC sync DMA engine is disabled after the end of transfer signal from DMA controller is detected + \param[in] none + \param[out] none + \retval none +*/ +void adc_sync_dma_request_after_last_enable(void) +{ + ADC_SYNCCTL |= ADC_SYNCCTL_SYNCDDM; +} + +/*! + \brief configure ADC sync DMA engine issues requests according to the SYNCDMA bits + \param[in] none + \param[out] none + \retval none +*/ +void adc_sync_dma_request_after_last_disable(void) +{ + ADC_SYNCCTL &= ~(ADC_SYNCCTL_SYNCDDM); +} + +/*! + \brief read ADC sync routine data register + \param[in] none + \param[out] none + \retval sync routine data +*/ +uint32_t adc_sync_routine_data_read(void) +{ + return (uint32_t)ADC_SYNCDATA; +} + +/*! + \brief get the bit state of ADCx software start conversion + \param[in] adc_periph: ADCx, x=0,1,2 only one among these parameters can be selected + \param[in] none + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus adc_routine_software_startconv_flag_get(uint32_t adc_periph) +{ + FlagStatus reval = RESET; + if((uint32_t)RESET != (ADC_STAT(adc_periph) & ADC_STAT_STRC)) { + reval = SET; + } + return reval; +} + +/*! + \brief get the bit state of ADCx software inserted channel start conversion + \param[in] adc_periph: ADCx, x=0,1,2 only one among these parameters can be selected + \param[in] none + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus adc_inserted_software_startconv_flag_get(uint32_t adc_periph) +{ + FlagStatus reval = RESET; + if((uint32_t)RESET != (ADC_STAT(adc_periph) & ADC_STAT_STIC)) { + reval = SET; + } + return reval; +} + +/*! + \brief get the ADC flag bits + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_flag: the adc flag bits + only one parameter can be selected which is shown as below: + \arg ADC_FLAG_WDE: analog watchdog event flag + \arg ADC_FLAG_EOC: end of sequence conversion flag + \arg ADC_FLAG_EOIC: end of inserted sequence conversion flag + \arg ADC_FLAG_STIC: start flag of inserted sequence + \arg ADC_FLAG_STRC: start flag of routine sequence + \arg ADC_FLAG_ROVF: routine data register overflow flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus adc_flag_get(uint32_t adc_periph, uint32_t adc_flag) +{ + FlagStatus reval = RESET; + if(ADC_STAT(adc_periph) & adc_flag) { + reval = SET; + } + return reval; + +} + +/*! + \brief clear the ADC flag bits + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_flag: the adc flag bits + only one parameter can be selected which is shown as below: + \arg ADC_FLAG_WDE: analog watchdog event flag + \arg ADC_FLAG_EOC: end of sequence conversion flag + \arg ADC_FLAG_EOIC: end of inserted sequence conversion flag + \arg ADC_FLAG_STIC: start flag of inserted sequence + \arg ADC_FLAG_STRC: start flag of routine sequence + \arg ADC_FLAG_ROVF: routine data register overflow flag + \param[out] none + \retval none +*/ +void adc_flag_clear(uint32_t adc_periph, uint32_t adc_flag) +{ + ADC_STAT(adc_periph) &= ~((uint32_t)adc_flag); +} + +/*! + \brief enable ADC interrupt + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_interrupt: the adc interrupt flag + only one parameter can be selected which is shown as below: + \arg ADC_INT_WDE: analog watchdog interrupt flag + \arg ADC_INT_EOC: end of sequence conversion interrupt flag + \arg ADC_INT_EOIC: end of inserted sequence conversion interrupt flag + \arg ADC_INT_ROVF: routine data register overflow interrupt flag + \param[out] none + \retval none +*/ +void adc_interrupt_enable(uint32_t adc_periph, uint32_t adc_interrupt) +{ + switch(adc_interrupt) { + case ADC_INT_WDE: + /* enable analog watchdog interrupt */ + ADC_CTL0(adc_periph) |= (uint32_t) ADC_CTL0_WDEIE; + break; + case ADC_INT_EOC: + /* enable end of sequence conversion interrupt */ + ADC_CTL0(adc_periph) |= (uint32_t) ADC_CTL0_EOCIE; + break; + case ADC_INT_EOIC: + /* enable end of inserted sequence conversion interrupt */ + ADC_CTL0(adc_periph) |= (uint32_t) ADC_CTL0_EOICIE; + break; + case ADC_INT_ROVF: + ADC_CTL0(adc_periph) |= (uint32_t) ADC_CTL0_ROVFIE; + break; + default: + break; + } +} + +/*! + \brief disable ADC interrupt + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_flag: the adc interrupt flag + only one parameter can be selected which is shown as below: + \arg ADC_INT_WDE: analog watchdog interrupt flag + \arg ADC_INT_EOC: end of sequence conversion interrupt flag + \arg ADC_INT_EOIC: end of inserted sequence conversion interrupt flag + \arg ADC_INT_ROVF: routine data register overflow interrupt flag + \param[out] none + \retval none +*/ +void adc_interrupt_disable(uint32_t adc_periph, uint32_t adc_interrupt) +{ + switch(adc_interrupt) { + /* select the interrupt source */ + case ADC_INT_WDE: + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_WDEIE); + break; + case ADC_INT_EOC: + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_EOCIE); + break; + case ADC_INT_EOIC: + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_EOICIE); + break; + case ADC_INT_ROVF: + ADC_CTL0(adc_periph) &= ~((uint32_t)ADC_CTL0_ROVFIE); + break; + default: + break; + } +} + +/*! + \brief get the ADC interrupt bits + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_interrupt: the adc interrupt bits + only one parameter can be selected which is shown as below: + \arg ADC_INT_FLAG_WDE: analog watchdog interrupt + \arg ADC_INT_FLAG_EOC: end of sequence conversion interrupt + \arg ADC_INT_FLAG_EOIC: end of inserted sequence conversion interrupt + \arg ADC_INT_FLAG_ROVF: routine data register overflow interrupt + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus adc_interrupt_flag_get(uint32_t adc_periph, uint32_t adc_interrupt) +{ + FlagStatus interrupt_flag = RESET; + uint32_t state; + /* check the interrupt bits */ + switch(adc_interrupt) { + case ADC_INT_FLAG_WDE: + /* get the ADC analog watchdog interrupt bits */ + state = ADC_STAT(adc_periph) & ADC_STAT_WDE; + if((ADC_CTL0(adc_periph) & ADC_CTL0_WDEIE) && state) { + interrupt_flag = SET; + } + break; + case ADC_INT_FLAG_EOC: + /* get the ADC end of sequence conversion interrupt bits */ + state = ADC_STAT(adc_periph) & ADC_STAT_EOC; + if((ADC_CTL0(adc_periph) & ADC_CTL0_EOCIE) && state) { + interrupt_flag = SET; + } + break; + case ADC_INT_FLAG_EOIC: + /* get the ADC end of inserted sequence conversion interrupt bits */ + state = ADC_STAT(adc_periph) & ADC_STAT_EOIC; + if((ADC_CTL0(adc_periph) & ADC_CTL0_EOICIE) && state) { + interrupt_flag = SET; + } + break; + case ADC_INT_FLAG_ROVF: + /* get the ADC routine data register overflow interrupt bits */ + state = ADC_STAT(adc_periph) & ADC_STAT_ROVF; + if((ADC_CTL0(adc_periph) & ADC_CTL0_ROVFIE) && state) { + interrupt_flag = SET; + } + break; + default: + break; + } + return interrupt_flag; +} + +/*! + \brief clear the ADC flag + \param[in] adc_periph: ADCx, x=0,1,2 + \param[in] adc_interrupt: the adc status flag + only one parameter can be selected which is shown as below: + \arg ADC_INT_FLAG_WDE: analog watchdog interrupt + \arg ADC_INT_FLAG_EOC: end of sequence conversion interrupt + \arg ADC_INT_FLAG_EOIC: end of inserted sequence conversion interrupt + \arg ADC_INT_FLAG_ROVF: routine data register overflow interrupt + \param[out] none + \retval none +*/ +void adc_interrupt_flag_clear(uint32_t adc_periph, uint32_t adc_interrupt) +{ + ADC_STAT(adc_periph) &= ~((uint32_t)adc_interrupt); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_can.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_can.c new file mode 100644 index 0000000..c5388f7 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_can.c @@ -0,0 +1,1431 @@ +/*! + \file gd32f5xx_can.c + \brief CAN driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_can.h" +#include + +#define CAN_ERROR_HANDLE(s) do{}while(1) + +/* This table can be used to calculate data length in FD mode */ +const uint8_t g_can_fdlength_table[] = {12, 16, 20, 24, 32, 48, 64}; + +/*! + \brief deinitialize CAN + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval none +*/ +void can_deinit(uint32_t can_periph) +{ + if(CAN0 == can_periph) { + rcu_periph_reset_enable(RCU_CAN0RST); + rcu_periph_reset_disable(RCU_CAN0RST); + } else { + rcu_periph_reset_enable(RCU_CAN1RST); + rcu_periph_reset_disable(RCU_CAN1RST); + } +} + +/*! + \brief initialize CAN parameter struct with a default value + \param[in] type: the type of CAN parameter struct + only one parameter can be selected which is shown as below: + \arg CAN_INIT_STRUCT: the CAN initial struct + \arg CAN_FILTER_STRUCT: the CAN filter struct + \arg CAN_FD_FRAME_STRUCT: the CAN FD initial struct + \arg CAN_TX_MESSAGE_STRUCT: the CAN TX message struct + \arg CAN_RX_MESSAGE_STRUCT: the CAN RX message struct + \param[in] p_struct: the pointer of the specific struct + \param[out] none + \retval none +*/ +void can_struct_para_init(can_struct_type_enum type, void *p_struct) +{ + uint8_t i; + + if(NULL == p_struct) { + CAN_ERROR_HANDLE("struct parameter can not be NULL \r\n"); + } + + /* get type of the struct */ + switch(type) { + /* used for can_init() */ + case CAN_INIT_STRUCT: + ((can_parameter_struct *)p_struct)->auto_bus_off_recovery = DISABLE; + ((can_parameter_struct *)p_struct)->auto_retrans = DISABLE; + ((can_parameter_struct *)p_struct)->auto_wake_up = DISABLE; + ((can_parameter_struct *)p_struct)->prescaler = 0x03FFU; + ((can_parameter_struct *)p_struct)->rec_fifo_overwrite = DISABLE; + ((can_parameter_struct *)p_struct)->resync_jump_width = CAN_BT_SJW_1TQ; + ((can_parameter_struct *)p_struct)->time_segment_1 = CAN_BT_BS1_3TQ; + ((can_parameter_struct *)p_struct)->time_segment_2 = CAN_BT_BS2_1TQ; + ((can_parameter_struct *)p_struct)->time_triggered = DISABLE; + ((can_parameter_struct *)p_struct)->trans_fifo_order = DISABLE; + ((can_parameter_struct *)p_struct)->working_mode = CAN_NORMAL_MODE; + + break; + /* used for can_filter_init() */ + case CAN_FILTER_STRUCT: + ((can_filter_parameter_struct *)p_struct)->filter_bits = CAN_FILTERBITS_32BIT; + ((can_filter_parameter_struct *)p_struct)->filter_enable = DISABLE; + ((can_filter_parameter_struct *)p_struct)->filter_fifo_number = CAN_FIFO0; + ((can_filter_parameter_struct *)p_struct)->filter_list_high = 0x0000U; + ((can_filter_parameter_struct *)p_struct)->filter_list_low = 0x0000U; + ((can_filter_parameter_struct *)p_struct)->filter_mask_high = 0x0000U; + ((can_filter_parameter_struct *)p_struct)->filter_mask_low = 0x0000U; + ((can_filter_parameter_struct *)p_struct)->filter_mode = CAN_FILTERMODE_MASK; + ((can_filter_parameter_struct *)p_struct)->filter_number = 0U; + + break; + /* used for can_fd_init() */ + case CAN_FD_FRAME_STRUCT: + ((can_fdframe_struct *)p_struct)->data_prescaler = 0x0400U; + ((can_fdframe_struct *)p_struct)->data_resync_jump_width = 1U - 1U; + ((can_fdframe_struct *)p_struct)->data_time_segment_1 = 3U - 1U; + ((can_fdframe_struct *)p_struct)->data_time_segment_2 = 2U - 1U; + ((can_fdframe_struct *)p_struct)->delay_compensation = DISABLE; + ((can_fdframe_struct *)p_struct)->esi_mode = CAN_ESIMOD_HARDWARE; + ((can_fdframe_struct *)p_struct)->excp_event_detect = ENABLE; + ((can_fdframe_struct *)p_struct)->fd_frame = DISABLE; + ((can_fdframe_struct *)p_struct)->iso_bosch = CAN_FDMOD_ISO; + ((can_fdframe_struct *)p_struct)->p_delay_compensation = 0U; + + break; + /* used for can_message_transmit() */ + case CAN_TX_MESSAGE_STRUCT: + ((can_trasnmit_message_struct *)p_struct)->fd_brs = CAN_BRS_DISABLE; + ((can_trasnmit_message_struct *)p_struct)->fd_esi = CAN_ESI_DOMINANT; + ((can_trasnmit_message_struct *)p_struct)->fd_flag = CAN_FDF_CLASSIC; + + for(i = 0U; i < 64U; i++) { + ((can_trasnmit_message_struct *)p_struct)->tx_data[i] = 0U; + } + + ((can_trasnmit_message_struct *)p_struct)->tx_dlen = 0u; + ((can_trasnmit_message_struct *)p_struct)->tx_efid = 0U; + ((can_trasnmit_message_struct *)p_struct)->tx_ff = (uint8_t)CAN_FF_STANDARD; + ((can_trasnmit_message_struct *)p_struct)->tx_ft = (uint8_t)CAN_FT_DATA; + ((can_trasnmit_message_struct *)p_struct)->tx_sfid = 0U; + + break; + /* used for can_message_receive() */ + case CAN_RX_MESSAGE_STRUCT: + ((can_receive_message_struct *)p_struct)->fd_brs = CAN_BRS_DISABLE; + ((can_receive_message_struct *)p_struct)->fd_esi = CAN_ESI_DOMINANT; + ((can_receive_message_struct *)p_struct)->fd_flag = CAN_FDF_CLASSIC; + + for(i = 0U; i < 64U; i++) { + ((can_receive_message_struct *)p_struct)->rx_data[i] = 0U; + } + + ((can_receive_message_struct *)p_struct)->rx_dlen = 0U; + ((can_receive_message_struct *)p_struct)->rx_efid = 0U; + ((can_receive_message_struct *)p_struct)->rx_ff = (uint8_t)CAN_FF_STANDARD; + ((can_receive_message_struct *)p_struct)->rx_fi = 0U; + ((can_receive_message_struct *)p_struct)->rx_ft = (uint8_t)CAN_FT_DATA; + ((can_receive_message_struct *)p_struct)->rx_sfid = 0U; + + break; + + default: + CAN_ERROR_HANDLE("parameter is invalid \r\n"); + } +} + +/*! + \brief initialize CAN + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] can_parameter_init: parameters for CAN initialization + \arg working_mode: CAN_NORMAL_MODE, CAN_LOOPBACK_MODE, CAN_SILENT_MODE, CAN_SILENT_LOOPBACK_MODE + \arg resync_jump_width: 0x00 - 0x07 + \arg time_segment_1: 0x00 - 0x7F + \arg time_segment_2: 0x00 - 0x1F + \arg time_triggered: ENABLE or DISABLE + \arg auto_bus_off_recovery: ENABLE or DISABLE + \arg auto_wake_up: ENABLE or DISABLE + \arg auto_retrans: ENABLE or DISABLE + \arg rec_fifo_overwrite: ENABLE or DISABLE + \arg trans_fifo_order: ENABLE or DISABLE + \arg prescaler: 0x0001 - 0x0400 + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus can_init(uint32_t can_periph, can_parameter_struct *can_parameter_init) +{ + uint32_t timeout = CAN_TIMEOUT; + ErrStatus flag = ERROR; + uint32_t fdctl_status; + + /* disable sleep mode */ + CAN_CTL(can_periph) &= ~CAN_CTL_SLPWMOD; + /* enable initialize mode */ + CAN_CTL(can_periph) |= CAN_CTL_IWMOD; + /* wait ACK */ + while((CAN_STAT_IWS != (CAN_STAT(can_periph) & CAN_STAT_IWS)) && (0U != timeout)) { + timeout--; + } + /* check initialize working success */ + if(CAN_STAT_IWS != (CAN_STAT(can_periph) & CAN_STAT_IWS)) { + flag = ERROR; + } else { + /* set the bit timing register */ + fdctl_status = CAN_FDCTL(can_periph); + if(CAN_FDCTL_FDEN != (fdctl_status & CAN_FDCTL_FDEN)) { + /* CAN FD disable, should first enable, then write */ + fdctl_status = fdctl_status | CAN_FDCTL_FDEN; + CAN_FDCTL(can_periph) = fdctl_status; + CAN_BT(can_periph) = (BT_MODE((uint32_t)can_parameter_init->working_mode) | \ + BT_SJW((uint32_t)can_parameter_init->resync_jump_width) | \ + BT_BS1((uint32_t)can_parameter_init->time_segment_1) | \ + BT_BS2((uint32_t)can_parameter_init->time_segment_2) | \ + BT_BAUDPSC(((uint32_t)(can_parameter_init->prescaler) - 1U))); + fdctl_status = fdctl_status & (~CAN_FDCTL_FDEN); + CAN_FDCTL(can_periph) = fdctl_status; + } else { + /* CAN FD enable */ + CAN_BT(can_periph) = (BT_MODE((uint32_t)can_parameter_init->working_mode) | \ + BT_SJW((uint32_t)can_parameter_init->resync_jump_width) | \ + BT_BS1((uint32_t)can_parameter_init->time_segment_1) | \ + BT_BS2((uint32_t)can_parameter_init->time_segment_2) | \ + BT_BAUDPSC(((uint32_t)(can_parameter_init->prescaler) - 1U))); + } + + /* time trigger communication mode */ + if(ENABLE == can_parameter_init->time_triggered) { + CAN_CTL(can_periph) |= CAN_CTL_TTC; + } else { + CAN_CTL(can_periph) &= ~CAN_CTL_TTC; + } + /* automatic bus-off management */ + if(ENABLE == can_parameter_init->auto_bus_off_recovery) { + CAN_CTL(can_periph) |= CAN_CTL_ABOR; + } else { + CAN_CTL(can_periph) &= ~CAN_CTL_ABOR; + } + /* automatic wakeup mode */ + if(ENABLE == can_parameter_init->auto_wake_up) { + CAN_CTL(can_periph) |= CAN_CTL_AWU; + } else { + CAN_CTL(can_periph) &= ~CAN_CTL_AWU; + } + /* automatic retransmission mode */ + if(ENABLE == can_parameter_init->auto_retrans) { + CAN_CTL(can_periph) &= ~CAN_CTL_ARD; + } else { + CAN_CTL(can_periph) |= CAN_CTL_ARD; + } + /* receive FIFO overwrite mode */ + if(ENABLE == can_parameter_init->rec_fifo_overwrite) { + CAN_CTL(can_periph) &= ~CAN_CTL_RFOD; + } else { + CAN_CTL(can_periph) |= CAN_CTL_RFOD; + } + /* transmit FIFO order */ + if(ENABLE == can_parameter_init->trans_fifo_order) { + CAN_CTL(can_periph) |= CAN_CTL_TFO; + } else { + CAN_CTL(can_periph) &= ~CAN_CTL_TFO; + } + /* disable initialize mode */ + CAN_CTL(can_periph) &= ~CAN_CTL_IWMOD; + timeout = CAN_TIMEOUT; + /* wait the ACK */ + while((CAN_STAT_IWS == (CAN_STAT(can_periph) & CAN_STAT_IWS)) && (0U != timeout)) { + timeout--; + } + /* check exit initialize mode */ + if(0U != timeout) { + flag = SUCCESS; + } + } + return flag; +} + +/*! + \brief initialize CAN FD function + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] can_fdframe_init: parameters for CAN FD initialization + \arg fd_frame: ENABLE or DISABLE + \arg excp_event_detect: ENABLE or DISABLE + \arg delay_compensation: ENABLE or DISABLE + \arg p_delay_compensation: the pointer of tdc struct + can_fd_tdc_struct: + tdc_mode: CAN_TDCMOD_CALC_AND_OFFSET or CAN_TDCMOD_OFFSET + tdc_filter: 0x00 - 0x07 + tdc_offset: 0x00 - 0x07 + \arg iso_bosch: CAN_FDMOD_ISO or CAN_FDMOD_BOSCH + \arg esi_mode: CAN_ESIMOD_HARDWARE or CAN_ESIMOD_SOFTWARE + \arg data_resync_jump_width: 0x00 - 0x07 + \arg data_time_segment_1: 0x00 - 0x0F + \arg data_time_segment_2: 0x00 - 0x07 + \arg data_prescaler: 0x0001 - 0x0400 + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus can_fd_init(uint32_t can_periph, can_fdframe_struct *can_fdframe_init) +{ + uint32_t timeout = CAN_TIMEOUT; + uint32_t tempreg = 0U; + + /* check null pointer */ + if(0 == can_fdframe_init) { + return ERROR; + } + /* disable sleep mode */ + CAN_CTL(can_periph) &= ~CAN_CTL_SLPWMOD; + /* enable initialize mode */ + CAN_CTL(can_periph) |= CAN_CTL_IWMOD; + /* wait ACK */ + while((CAN_STAT_IWS != (CAN_STAT(can_periph) & CAN_STAT_IWS)) && (0U != timeout)) { + timeout--; + } + /* check initialize working success */ + if(CAN_STAT_IWS != (CAN_STAT(can_periph) & CAN_STAT_IWS)) { + return ERROR; + } else { + /* set the data bit timing register */ + CAN_DBT(can_periph) = (BT_DSJW((uint32_t)can_fdframe_init->data_resync_jump_width) | \ + BT_DBS1((uint32_t)can_fdframe_init->data_time_segment_1) | \ + BT_DBS2((uint32_t)can_fdframe_init->data_time_segment_2) | \ + BT_BAUDPSC(((uint32_t)can_fdframe_init->data_prescaler) - 1U)); + + tempreg = can_fdframe_init->esi_mode | can_fdframe_init->iso_bosch; + + /* Protocol exception event detection */ + if(ENABLE == can_fdframe_init->excp_event_detect) { + tempreg &= ~CAN_FDCTL_PRED; + } else { + tempreg |= CAN_FDCTL_PRED; + } + + /* Transmitter delay compensation mode */ + if(ENABLE == can_fdframe_init->delay_compensation) { + tempreg |= CAN_FDCTL_TDCEN; + /* p_delay_compensation pointer should be config when TDC mode is enabled */ + if(0 != can_fdframe_init->p_delay_compensation) { + tempreg |= (can_fdframe_init->p_delay_compensation->tdc_mode & CAN_FDCTL_TDCMOD); + CAN_FDTDC(can_periph) = (FDTDC_TDCF(can_fdframe_init->p_delay_compensation->tdc_filter) | FDTDC_TDCO( + can_fdframe_init->p_delay_compensation->tdc_offset)); + } else { + return ERROR; + } + } else { + /* Transmitter delay compensation mode is disabled */ + tempreg &= ~CAN_FDCTL_TDCEN; + } + + /* FD operation mode */ + if(ENABLE == can_fdframe_init->fd_frame) { + tempreg |= CAN_FDCTL_FDEN; + } else { + tempreg &= ~CAN_FDCTL_FDEN; + } + CAN_FDCTL(can_periph) = tempreg; + + /* disable initialize mode */ + CAN_CTL(can_periph) &= ~CAN_CTL_IWMOD; + timeout = CAN_TIMEOUT; + /* wait the ACK */ + while((CAN_STAT_IWS == (CAN_STAT(can_periph) & CAN_STAT_IWS)) && (0U != timeout)) { + timeout--; + } + /* check exit initialize mode */ + if(0U == timeout) { + return ERROR; + } + } + + return SUCCESS; +} + +/*! + \brief initialize CAN filter + \param[in] can_filter_parameter_init: struct for CAN filter initialization + \arg filter_list_high: 0x0000 - 0xFFFF + \arg filter_list_low: 0x0000 - 0xFFFF + \arg filter_mask_high: 0x0000 - 0xFFFF + \arg filter_mask_low: 0x0000 - 0xFFFF + \arg filter_fifo_number: CAN_FIFO0, CAN_FIFO1 + \arg filter_number: 0 - 27 + \arg filter_mode: CAN_FILTERMODE_MASK, CAN_FILTERMODE_LIST + \arg filter_bits: CAN_FILTERBITS_32BIT, CAN_FILTERBITS_16BIT + \arg filter_enable: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void can_filter_init(can_filter_parameter_struct *can_filter_parameter_init) +{ + uint32_t val = 0U; + + val = ((uint32_t)1) << (can_filter_parameter_init->filter_number); + /* filter lock disable */ + CAN_FCTL(CAN0) |= CAN_FCTL_FLD; + /* disable filter */ + CAN_FW(CAN0) &= ~(uint32_t)val; + + /* filter 16 bits */ + if(CAN_FILTERBITS_16BIT == can_filter_parameter_init->filter_bits) { + /* set filter 16 bits */ + CAN_FSCFG(CAN0) &= ~(uint32_t)val; + /* first 16 bits list and first 16 bits mask or first 16 bits list and second 16 bits list */ + CAN_FDATA0(CAN0, can_filter_parameter_init->filter_number) = \ + FDATA_MASK_HIGH((can_filter_parameter_init->filter_mask_low) & CAN_FILTER_MASK_16BITS) | \ + FDATA_MASK_LOW((can_filter_parameter_init->filter_list_low) & CAN_FILTER_MASK_16BITS); + /* second 16 bits list and second 16 bits mask or third 16 bits list and fourth 16 bits list */ + CAN_FDATA1(CAN0, can_filter_parameter_init->filter_number) = \ + FDATA_MASK_HIGH((can_filter_parameter_init->filter_mask_high) & CAN_FILTER_MASK_16BITS) | \ + FDATA_MASK_LOW((can_filter_parameter_init->filter_list_high) & CAN_FILTER_MASK_16BITS); + } + /* filter 32 bits */ + if(CAN_FILTERBITS_32BIT == can_filter_parameter_init->filter_bits) { + /* set filter 32 bits */ + CAN_FSCFG(CAN0) |= (uint32_t)val; + /* 32 bits list or first 32 bits list */ + CAN_FDATA0(CAN0, can_filter_parameter_init->filter_number) = \ + FDATA_MASK_HIGH((can_filter_parameter_init->filter_list_high) & CAN_FILTER_MASK_16BITS) | + FDATA_MASK_LOW((can_filter_parameter_init->filter_list_low) & CAN_FILTER_MASK_16BITS); + /* 32 bits mask or second 32 bits list */ + CAN_FDATA1(CAN0, can_filter_parameter_init->filter_number) = \ + FDATA_MASK_HIGH((can_filter_parameter_init->filter_mask_high) & CAN_FILTER_MASK_16BITS) | + FDATA_MASK_LOW((can_filter_parameter_init->filter_mask_low) & CAN_FILTER_MASK_16BITS); + } + + /* filter mode */ + if(CAN_FILTERMODE_MASK == can_filter_parameter_init->filter_mode) { + /* mask mode */ + CAN_FMCFG(CAN0) &= ~(uint32_t)val; + } else { + /* list mode */ + CAN_FMCFG(CAN0) |= (uint32_t)val; + } + + /* filter FIFO */ + if(CAN_FIFO0 == (can_filter_parameter_init->filter_fifo_number)) { + /* FIFO0 */ + CAN_FAFIFO(CAN0) &= ~(uint32_t)val; + } else { + /* FIFO1 */ + CAN_FAFIFO(CAN0) |= (uint32_t)val; + } + + /* filter working */ + if(ENABLE == can_filter_parameter_init->filter_enable) { + + CAN_FW(CAN0) |= (uint32_t)val; + } + + /* filter lock enable */ + CAN_FCTL(CAN0) &= ~CAN_FCTL_FLD; +} + +/*! + \brief CAN filter mask mode initialization + \param[in] id: extended(11-bits) or standard(29-bits) identifier + \arg 0x00000000 - 0x1FFFFFFF + \param[in] mask: extended(11-bits) or standard(29-bits) identifier mask + \arg 0x00000000 - 0x1FFFFFFF + \param[in] format_fifo: format and FIFO states + only one parameter can be selected which is shown as below: + \arg CAN_STANDARD_FIFO0 + \arg CAN_STANDARD_FIFO1 + \arg CAN_EXTENDED_FIFO0 + \arg CAN_EXTENDED_FIFO1 + \param[in] filter_number: filter sequence number + \arg 0x00 - 0x1B + \param[out] none + \retval none +*/ +void can_filter_mask_mode_init(uint32_t id, uint32_t mask, can_format_fifo_enum format_fifo, uint16_t filter_number) +{ + can_filter_parameter_struct can_filter; + + /* Initialize the filter structure */ + can_struct_para_init(CAN_FILTER_STRUCT, &can_filter); + + /* filter config */ + can_filter.filter_number = filter_number; + can_filter.filter_mode = CAN_FILTERMODE_MASK; + can_filter.filter_bits = CAN_FILTERBITS_32BIT; + can_filter.filter_enable = ENABLE; + + switch(format_fifo) { + /* standard FIFO 0 */ + case CAN_STANDARD_FIFO0: + can_filter.filter_fifo_number = CAN_FIFO0; + /* configure SFID[10:0] */ + can_filter.filter_list_high = (uint16_t)id << 5; + can_filter.filter_list_low = 0x0000U; + /* configure SFID[10:0] mask */ + can_filter.filter_mask_high = (uint16_t)mask << 5; + /* both data and remote frames can be received */ + can_filter.filter_mask_low = (uint16_t)(1U << 2U); + + break; + /* standard FIFO 1 */ + case CAN_STANDARD_FIFO1: + can_filter.filter_fifo_number = CAN_FIFO1; + /* configure SFID[10:0] */ + can_filter.filter_list_high = (uint16_t)id << 5; + can_filter.filter_list_low = 0x0000U; + /* configure SFID[10:0] mask */ + can_filter.filter_mask_high = (uint16_t)mask << 5; + /* both data and remote frames can be received */ + can_filter.filter_mask_low = (uint16_t)(1U << 2U); + + break; + /* extended FIFO 0 */ + case CAN_EXTENDED_FIFO0: + can_filter.filter_fifo_number = CAN_FIFO0; + /* configure EFID[28:13] */ + can_filter.filter_list_high = (uint16_t)(id >> 13); + /* configure EFID[12:0] and frame format bit set */ + can_filter.filter_list_low = ((uint16_t)(id << 3)) | (1U << 2); + /* configure EFID[28:13] mask */ + can_filter.filter_mask_high = (uint16_t)(mask >> 13); + /* configure EFID[12:0] and frame format bit mask */ + /* both data and remote frames can be received */ + can_filter.filter_mask_low = ((uint16_t)(mask << 3)) | (1U << 2); + + break; + /* extended FIFO 1 */ + case CAN_EXTENDED_FIFO1: + can_filter.filter_fifo_number = CAN_FIFO1; + /* configure EFID[28:13] */ + can_filter.filter_list_high = (uint16_t)(id >> 13); + /* configure EFID[12:0] and frame format bit set */ + can_filter.filter_list_low = ((uint16_t)(id << 3)) | (1U << 2); + /* configure EFID[28:13] mask */ + can_filter.filter_mask_high = (uint16_t)(mask >> 13); + /* configure EFID[12:0] and frame format bit mask */ + /* both data and remote frames can be received */ + can_filter.filter_mask_low = ((uint16_t)(mask << 3)) | (1U << 2); + + break; + default: + CAN_ERROR_HANDLE("parameter is invalid \r\n"); + } + + can_filter_init(&can_filter); +} + +/*! + \brief CAN communication mode configure + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] mode: communication mode + only one parameter can be selected which is shown as below: + \arg CAN_NORMAL_MODE + \arg CAN_LOOPBACK_MODE + \arg CAN_SILENT_MODE + \arg CAN_SILENT_LOOPBACK_MODE + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus can_monitor_mode_set(uint32_t can_periph, uint8_t mode) +{ + ErrStatus reval = SUCCESS; + uint32_t timeout = CAN_TIMEOUT; + + if(mode == (mode & CAN_SILENT_LOOPBACK_MODE)) { + /* disable sleep mode */ + CAN_CTL(can_periph) &= (~(uint32_t)CAN_CTL_SLPWMOD); + /* set initialize mode */ + CAN_CTL(can_periph) |= (uint8_t)CAN_CTL_IWMOD; + /* wait the acknowledge */ + timeout = CAN_TIMEOUT; + while((CAN_STAT_IWS != (CAN_STAT(can_periph) & CAN_STAT_IWS)) && (0U != timeout)) { + timeout--; + } + + if(CAN_STAT_IWS != (CAN_STAT(can_periph) & CAN_STAT_IWS)) { + reval = ERROR; + } else { + CAN_BT(can_periph) &= ~BT_MODE(3); + CAN_BT(can_periph) |= BT_MODE(mode); + + timeout = CAN_TIMEOUT; + /* enter normal mode */ + CAN_CTL(can_periph) &= ~(uint32_t)(CAN_CTL_SLPWMOD | CAN_CTL_IWMOD); + /* wait the acknowledge */ + while((0U != (CAN_STAT(can_periph) & (CAN_STAT_IWS | CAN_STAT_SLPWS))) && (0U != timeout)) { + timeout--; + } + if(0U != (CAN_STAT(can_periph) & (CAN_STAT_IWS | CAN_STAT_SLPWS))) { + reval = ERROR; + } + } + } else { + reval = ERROR; + } + + return reval; +} + +/*! + \brief CAN FD frame function enable + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval none +*/ +void can_fd_function_enable(uint32_t can_periph) +{ + CAN_FDCTL(can_periph) |= CAN_FDCTL_FDEN; +} + +/*! + \brief CAN FD frame function disable + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval none +*/ +void can_fd_function_disable(uint32_t can_periph) +{ + CAN_FDCTL(can_periph) &= ~CAN_FDCTL_FDEN; +} + +/*! + \brief set CAN1 filter start bank number + \param[in] start_bank: CAN1 start bank number + only one parameter can be selected which is shown as below: + \arg (1..27) + \param[out] none + \retval none +*/ +void can1_filter_start_bank(uint8_t start_bank) +{ + /* filter lock disable */ + CAN_FCTL(CAN0) |= CAN_FCTL_FLD; + /* set CAN1 filter start number */ + CAN_FCTL(CAN0) &= ~(uint32_t)CAN_FCTL_HBC1F; + CAN_FCTL(CAN0) |= FCTL_HBC1F(start_bank); + /* filter lock enable */ + CAN_FCTL(CAN0) &= ~CAN_FCTL_FLD; +} + +/*! + \brief enable CAN debug freeze + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval none +*/ +void can_debug_freeze_enable(uint32_t can_periph) +{ + /* set DFZ bit */ + CAN_CTL(can_periph) |= CAN_CTL_DFZ; + + if(CAN0 == can_periph) { + dbg_periph_enable(DBG_CAN0_HOLD); + } else { + dbg_periph_enable(DBG_CAN1_HOLD); + } +} + +/*! + \brief disable CAN debug freeze + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval none +*/ +void can_debug_freeze_disable(uint32_t can_periph) +{ + /* set DFZ bit */ + CAN_CTL(can_periph) &= ~CAN_CTL_DFZ; + + if(CAN0 == can_periph) { + dbg_periph_disable(DBG_CAN0_HOLD); + } else { + dbg_periph_disable(DBG_CAN1_HOLD); + } +} + +/*! + \brief enable CAN time trigger mode + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval none +*/ +void can_time_trigger_mode_enable(uint32_t can_periph) +{ + uint8_t mailbox_number; + + /* enable the TTC mode */ + CAN_CTL(can_periph) |= CAN_CTL_TTC; + /* enable time stamp */ + for(mailbox_number = 0U; mailbox_number < 3U; mailbox_number++) { + CAN_TMP(can_periph, mailbox_number) |= CAN_TMP_TSEN; + } +} + +/*! + \brief disable CAN time trigger mode + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval none +*/ +void can_time_trigger_mode_disable(uint32_t can_periph) +{ + uint8_t mailbox_number; + + /* disable the TTC mode */ + CAN_CTL(can_periph) &= ~CAN_CTL_TTC; + /* reset TSEN bits */ + for(mailbox_number = 0U; mailbox_number < 3U; mailbox_number++) { + CAN_TMP(can_periph, mailbox_number) &= ~CAN_TMP_TSEN; + } +} + +/*! + \brief transmit CAN message + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] transmit_message: struct for CAN transmit message + \arg tx_sfid: 0x00000000 - 0x000007FF + \arg tx_efid: 0x00000000 - 0x1FFFFFFF + \arg tx_ff: CAN_FF_STANDARD, CAN_FF_EXTENDED + \arg tx_ft: CAN_FT_DATA, CAN_FT_REMOTE + \arg tx_dlen: 0 - 8 (FD mode: 0 - 8, or 12, 16, 20, 24, 32, 48, 64) + \arg tx_data[]: 0x00 - 0xFF + \param[out] none + \retval mailbox_number +*/ +uint8_t can_message_transmit(uint32_t can_periph, can_trasnmit_message_struct *transmit_message) +{ + uint8_t mailbox_number = CAN_MAILBOX0; + uint8_t i = 0U; + uint8_t hit = 0U; + uint32_t canfd_en = 0U; + volatile uint32_t p_temp; + uint32_t reg_temp = 0U; + + /* select one empty mailbox */ + if(CAN_TSTAT_TME0 == (CAN_TSTAT(can_periph)&CAN_TSTAT_TME0)) { + mailbox_number = CAN_MAILBOX0; + } else if(CAN_TSTAT_TME1 == (CAN_TSTAT(can_periph)&CAN_TSTAT_TME1)) { + mailbox_number = CAN_MAILBOX1; + } else if(CAN_TSTAT_TME2 == (CAN_TSTAT(can_periph)&CAN_TSTAT_TME2)) { + mailbox_number = CAN_MAILBOX2; + } else { + mailbox_number = CAN_NOMAILBOX; + } + /* return no mailbox empty */ + if(CAN_NOMAILBOX == mailbox_number) { + return CAN_NOMAILBOX; + } + + CAN_TMI(can_periph, mailbox_number) &= CAN_TMI_TEN; + if(CAN_FF_STANDARD == transmit_message->tx_ff) { + /* set transmit mailbox standard identifier */ + CAN_TMI(can_periph, mailbox_number) |= (uint32_t)(TMI_SFID(transmit_message->tx_sfid) | \ + transmit_message->tx_ft); + } else { + /* set transmit mailbox extended identifier */ + CAN_TMI(can_periph, mailbox_number) |= (uint32_t)(TMI_EFID(transmit_message->tx_efid) | \ + transmit_message->tx_ff | \ + transmit_message->tx_ft); + } + + if(CAN_FDF_CLASSIC == transmit_message->fd_flag) { + /* set the data length */ + CAN_TMP(can_periph, mailbox_number) &= ~(CAN_TMP_DLENC | CAN_TMP_ESI | CAN_TMP_BRS | CAN_TMP_FDF); + CAN_TMP(can_periph, mailbox_number) |= transmit_message->tx_dlen; + /* set the data */ + CAN_TMDATA0(can_periph, mailbox_number) = TMDATA0_DB3(transmit_message->tx_data[3]) | \ + TMDATA0_DB2(transmit_message->tx_data[2]) | \ + TMDATA0_DB1(transmit_message->tx_data[1]) | \ + TMDATA0_DB0(transmit_message->tx_data[0]); + CAN_TMDATA1(can_periph, mailbox_number) = TMDATA1_DB7(transmit_message->tx_data[7]) | \ + TMDATA1_DB6(transmit_message->tx_data[6]) | \ + TMDATA1_DB5(transmit_message->tx_data[5]) | \ + TMDATA1_DB4(transmit_message->tx_data[4]); + } else { + canfd_en = CAN_FDCTL(can_periph) & CAN_FDCTL_FDEN; + /* check FD function has been enabled */ + if(canfd_en) { + if(transmit_message->tx_dlen <= 8U) { + /* set the data length */ + reg_temp |= transmit_message->tx_dlen; + } else { + /* data length greater than 8 */ + for(i = 0U; i < 7U; i++) { + if(transmit_message->tx_dlen == g_can_fdlength_table[i]) { + hit = 1U; + break; + } + } + /* data length is valid */ + if(1U == hit) { + reg_temp |= 9U + i; + } else { + CAN_ERROR_HANDLE("dlen is invalid \r\n"); + } + } + reg_temp |= (((uint32_t)transmit_message->fd_brs << 5U) | ((uint32_t)transmit_message->fd_esi << 4U) | (( + uint32_t)transmit_message->fd_flag << 7U)); + CAN_TMP(can_periph, mailbox_number) = reg_temp; + + /* set the data */ + i = transmit_message->tx_dlen / 4U; + + /* data length is 5-7 need send 2 word */ + if((1U == i) && (4U != transmit_message->tx_dlen)) { + i++; + } + p_temp = (uint32_t)transmit_message->tx_data; + if((0U == i)) { + CAN_TMDATA0(can_periph, mailbox_number) = *(uint32_t *)p_temp; + } else { + for(; i > 0U; i--) { + CAN_TMDATA0(can_periph, mailbox_number) = *(uint32_t *)p_temp; + p_temp = ((uint32_t)((uint32_t)p_temp + 4U)); + } + } + + } else { + CAN_ERROR_HANDLE("CAN FD function disabled \r\n"); + } + } + + /* enable transmission */ + CAN_TMI(can_periph, mailbox_number) |= CAN_TMI_TEN; + + return mailbox_number; +} + +/*! + \brief get CAN transmit state + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] mailbox_number + only one parameter can be selected which is shown as below: + \arg CAN_MAILBOX(x=0,1,2) + \param[out] none + \retval can_transmit_state_enum +*/ +can_transmit_state_enum can_transmit_states(uint32_t can_periph, uint8_t mailbox_number) +{ + can_transmit_state_enum state = CAN_TRANSMIT_FAILED; + uint32_t val = 0U; + + /* check selected mailbox state */ + switch(mailbox_number) { + /* mailbox0 */ + case CAN_MAILBOX0: + val = CAN_TSTAT(can_periph) & (CAN_TSTAT_MTF0 | CAN_TSTAT_MTFNERR0 | CAN_TSTAT_TME0); + break; + /* mailbox1 */ + case CAN_MAILBOX1: + val = CAN_TSTAT(can_periph) & (CAN_TSTAT_MTF1 | CAN_TSTAT_MTFNERR1 | CAN_TSTAT_TME1); + break; + /* mailbox2 */ + case CAN_MAILBOX2: + val = CAN_TSTAT(can_periph) & (CAN_TSTAT_MTF2 | CAN_TSTAT_MTFNERR2 | CAN_TSTAT_TME2); + break; + default: + val = CAN_TRANSMIT_FAILED; + break; + } + + switch(val) { + /* transmit pending */ + case(CAN_STATE_PENDING): + state = CAN_TRANSMIT_PENDING; + break; + /* mailbox0 transmit succeeded */ + case(CAN_TSTAT_MTF0 | CAN_TSTAT_MTFNERR0 | CAN_TSTAT_TME0): + state = CAN_TRANSMIT_OK; + break; + /* mailbox1 transmit succeeded */ + case(CAN_TSTAT_MTF1 | CAN_TSTAT_MTFNERR1 | CAN_TSTAT_TME1): + state = CAN_TRANSMIT_OK; + break; + /* mailbox2 transmit succeeded */ + case(CAN_TSTAT_MTF2 | CAN_TSTAT_MTFNERR2 | CAN_TSTAT_TME2): + state = CAN_TRANSMIT_OK; + break; + /* transmit failed */ + default: + state = CAN_TRANSMIT_FAILED; + break; + } + return state; +} + +/*! + \brief stop CAN transmission + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] mailbox_number + only one parameter can be selected which is shown as below: + \arg CAN_MAILBOXx(x=0,1,2) + \param[out] none + \retval none +*/ +void can_transmission_stop(uint32_t can_periph, uint8_t mailbox_number) +{ + if(CAN_MAILBOX0 == mailbox_number) { + CAN_TSTAT(can_periph) |= CAN_TSTAT_MST0; + while(CAN_TSTAT_MST0 == (CAN_TSTAT(can_periph) & CAN_TSTAT_MST0)) { + } + } else if(CAN_MAILBOX1 == mailbox_number) { + CAN_TSTAT(can_periph) |= CAN_TSTAT_MST1; + while(CAN_TSTAT_MST1 == (CAN_TSTAT(can_periph) & CAN_TSTAT_MST1)) { + } + } else if(CAN_MAILBOX2 == mailbox_number) { + CAN_TSTAT(can_periph) |= CAN_TSTAT_MST2; + while(CAN_TSTAT_MST2 == (CAN_TSTAT(can_periph) & CAN_TSTAT_MST2)) { + } + } else { + /* illegal parameters */ + } +} + +/*! + \brief CAN receive message + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] fifo_number + \arg CAN_FIFOx(x=0,1) + \param[out] receive_message: struct for CAN receive message + \arg rx_sfid: 0x00000000 - 0x000007FF + \arg rx_efid: 0x00000000 - 0x1FFFFFFF + \arg rx_ff: CAN_FF_STANDARD, CAN_FF_EXTENDED + \arg rx_ft: CAN_FT_DATA, CAN_FT_REMOTE + \arg rx_dlen: 0 - 8 (FD mode: 0 - 8, or 12, 16, 20, 24, 32, 48, 64) + \arg rx_data[]: 0x00 - 0xFF + \arg rx_fi: 0 - 27 + \retval none +*/ +void can_message_receive(uint32_t can_periph, uint8_t fifo_number, can_receive_message_struct *receive_message) +{ + uint32_t canfd_en = 0U; + volatile uint32_t p_temp; + uint32_t data_temp; + uint8_t canfd_recv_cnt = 0U; + uint8_t i; + + /* get the frame format */ + receive_message->rx_ff = (uint8_t)(CAN_RFIFOMI_FF & CAN_RFIFOMI(can_periph, fifo_number)); + if(CAN_FF_STANDARD == receive_message->rx_ff) { + /* get standard identifier */ + receive_message->rx_sfid = (uint32_t)(GET_RFIFOMI_SFID(CAN_RFIFOMI(can_periph, fifo_number))); + } else { + /* get extended identifier */ + receive_message->rx_efid = (uint32_t)(GET_RFIFOMI_EFID(CAN_RFIFOMI(can_periph, fifo_number))); + } + + /* get frame type */ + receive_message->rx_ft = (uint8_t)(CAN_RFIFOMI_FT & CAN_RFIFOMI(can_periph, fifo_number)); + /* filtering index */ + receive_message->rx_fi = (uint8_t)(GET_RFIFOMP_FI(CAN_RFIFOMP(can_periph, fifo_number))); + receive_message->fd_flag = (uint8_t)((CAN_RFIFOMP_FDF & CAN_RFIFOMP(can_periph, fifo_number)) >> 7); + + canfd_en = CAN_FDCTL(can_periph) & CAN_FDCTL_FDEN; + if(!canfd_en) { + if(CAN_FDF_CLASSIC == receive_message->fd_flag) { + /* get receive data length */ + receive_message->rx_dlen = (uint8_t)(GET_RFIFOMP_DLENC(CAN_RFIFOMP(can_periph, fifo_number))); + /* receive data */ + receive_message->rx_data[0] = (uint8_t)(GET_RFIFOMDATA0_DB0(CAN_RFIFOMDATA0(can_periph, fifo_number))); + receive_message->rx_data[1] = (uint8_t)(GET_RFIFOMDATA0_DB1(CAN_RFIFOMDATA0(can_periph, fifo_number))); + receive_message->rx_data[2] = (uint8_t)(GET_RFIFOMDATA0_DB2(CAN_RFIFOMDATA0(can_periph, fifo_number))); + receive_message->rx_data[3] = (uint8_t)(GET_RFIFOMDATA0_DB3(CAN_RFIFOMDATA0(can_periph, fifo_number))); + receive_message->rx_data[4] = (uint8_t)(GET_RFIFOMDATA1_DB4(CAN_RFIFOMDATA1(can_periph, fifo_number))); + receive_message->rx_data[5] = (uint8_t)(GET_RFIFOMDATA1_DB5(CAN_RFIFOMDATA1(can_periph, fifo_number))); + receive_message->rx_data[6] = (uint8_t)(GET_RFIFOMDATA1_DB6(CAN_RFIFOMDATA1(can_periph, fifo_number))); + receive_message->rx_data[7] = (uint8_t)(GET_RFIFOMDATA1_DB7(CAN_RFIFOMDATA1(can_periph, fifo_number))); + } else { + CAN_ERROR_HANDLE("CAN FD function disabled \r\n"); + } + } else { + /* check FD function has been enabled */ + /* get receive data length */ + canfd_recv_cnt = (uint8_t)(GET_RFIFOMP_DLENC(CAN_RFIFOMP(can_periph, fifo_number))); + + if(canfd_recv_cnt <= 8U) { + /* set the data length */ + receive_message->rx_dlen = canfd_recv_cnt; + } else { + receive_message->rx_dlen = g_can_fdlength_table[canfd_recv_cnt - 9U]; + } + + receive_message->fd_brs = (uint8_t)((CAN_RFIFOMP(can_periph, fifo_number) & CAN_RFIFOMP_BRS) >> 5); + receive_message->fd_esi = (uint8_t)((CAN_RFIFOMP(can_periph, fifo_number) & CAN_RFIFOMP_ESI) >> 4); + + /* get the data */ + i = receive_message->rx_dlen / 4U; + + /* data length is 5-7 need receive 2 word */ + if((1U == i) && (4U != receive_message->rx_dlen)) { + i++; + } + p_temp = (uint32_t)(uint32_t)receive_message->rx_data; + if(0U == i) { + data_temp = CAN_RFIFOMDATA0(can_periph, fifo_number); + *(uint32_t *)p_temp = data_temp; + } else { + /* get the data by reading from CAN_RFIFOMDATA0 register*/ + for(; i > 0U; i--) { + data_temp = CAN_RFIFOMDATA0(can_periph, fifo_number); + *(uint32_t *)p_temp = data_temp; + p_temp = ((uint32_t)((uint32_t)p_temp + 4U)); + } + } + } + + /* release FIFO */ + if(CAN_FIFO0 == fifo_number) { + CAN_RFIFO0(can_periph) |= CAN_RFIFO0_RFD0; + } else { + CAN_RFIFO1(can_periph) |= CAN_RFIFO1_RFD1; + } +} + +/*! + \brief release FIFO + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] fifo_number + only one parameter can be selected which is shown as below: + \arg CAN_FIFOx(x=0,1) + \param[out] none + \retval none +*/ +void can_fifo_release(uint32_t can_periph, uint8_t fifo_number) +{ + if(CAN_FIFO0 == fifo_number) { + CAN_RFIFO0(can_periph) |= CAN_RFIFO0_RFD0; + } else if(CAN_FIFO1 == fifo_number) { + CAN_RFIFO1(can_periph) |= CAN_RFIFO1_RFD1; + } else { + /* illegal parameters */ + CAN_ERROR_HANDLE("CAN FIFO NUM is invalid \r\n"); + } +} + +/*! + \brief CAN receive message length + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] fifo_number + only one parameter can be selected which is shown as below: + \arg CAN_FIFOx(x=0,1) + \param[out] none + \retval message length +*/ +uint8_t can_receive_message_length_get(uint32_t can_periph, uint8_t fifo_number) +{ + uint8_t val = 0U; + + if(CAN_FIFO0 == fifo_number) { + /* FIFO0 */ + val = (uint8_t)(CAN_RFIFO0(can_periph) & CAN_RFIF_RFL_MASK); + } else if(CAN_FIFO1 == fifo_number) { + /* FIFO1 */ + val = (uint8_t)(CAN_RFIFO1(can_periph) & CAN_RFIF_RFL_MASK); + } else { + /* illegal parameters */ + } + return val; +} + +/*! + \brief set CAN working mode + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] can_working_mode + only one parameter can be selected which is shown as below: + \arg CAN_MODE_INITIALIZE + \arg CAN_MODE_NORMAL + \arg CAN_MODE_SLEEP + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus can_working_mode_set(uint32_t can_periph, uint8_t working_mode) +{ + ErrStatus flag = ERROR; + /* timeout for IWS or also for SLPWS bits */ + uint32_t timeout = CAN_TIMEOUT; + + if(CAN_MODE_INITIALIZE == working_mode) { + /* disable sleep mode */ + CAN_CTL(can_periph) &= (~(uint32_t)CAN_CTL_SLPWMOD); + /* set initialize mode */ + CAN_CTL(can_periph) |= (uint8_t)CAN_CTL_IWMOD; + /* wait the acknowledge */ + while((CAN_STAT_IWS != (CAN_STAT(can_periph) & CAN_STAT_IWS)) && (0U != timeout)) { + timeout--; + } + if(CAN_STAT_IWS != (CAN_STAT(can_periph) & CAN_STAT_IWS)) { + flag = ERROR; + } else { + flag = SUCCESS; + } + } else if(CAN_MODE_NORMAL == working_mode) { + /* enter normal mode */ + CAN_CTL(can_periph) &= ~(uint32_t)(CAN_CTL_SLPWMOD | CAN_CTL_IWMOD); + /* wait the acknowledge */ + while((0U != (CAN_STAT(can_periph) & (CAN_STAT_IWS | CAN_STAT_SLPWS))) && (0U != timeout)) { + timeout--; + } + if(0U != (CAN_STAT(can_periph) & (CAN_STAT_IWS | CAN_STAT_SLPWS))) { + flag = ERROR; + } else { + flag = SUCCESS; + } + } else if(CAN_MODE_SLEEP == working_mode) { + /* disable initialize mode */ + CAN_CTL(can_periph) &= (~(uint32_t)CAN_CTL_IWMOD); + /* set sleep mode */ + CAN_CTL(can_periph) |= (uint8_t)CAN_CTL_SLPWMOD; + /* wait the acknowledge */ + while((CAN_STAT_SLPWS != (CAN_STAT(can_periph) & CAN_STAT_SLPWS)) && (0U != timeout)) { + timeout--; + } + if(CAN_STAT_SLPWS != (CAN_STAT(can_periph) & CAN_STAT_SLPWS)) { + flag = ERROR; + } else { + flag = SUCCESS; + } + } else { + flag = ERROR; + } + return flag; +} + +/*! + \brief wake up CAN + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus can_wakeup(uint32_t can_periph) +{ + ErrStatus flag = ERROR; + uint32_t timeout = CAN_TIMEOUT; + + /* wakeup */ + CAN_CTL(can_periph) &= ~CAN_CTL_SLPWMOD; + + while((0U != (CAN_STAT(can_periph) & CAN_STAT_SLPWS)) && (0x00U != timeout)) { + timeout--; + } + /* check state */ + if(0U != (CAN_STAT(can_periph) & CAN_STAT_SLPWS)) { + flag = ERROR; + } else { + flag = SUCCESS; + } + return flag; +} + +/*! + \brief get CAN error type + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval can_error_enum + \arg CAN_ERROR_NONE: no error + \arg CAN_ERROR_FILL: fill error + \arg CAN_ERROR_FORMATE: format error + \arg CAN_ERROR_ACK: ACK error + \arg CAN_ERROR_BITRECESSIVE: bit recessive + \arg CAN_ERROR_BITDOMINANTER: bit dominant error + \arg CAN_ERROR_CRC: CRC error + \arg CAN_ERROR_SOFTWARECFG: software configure +*/ +can_error_enum can_error_get(uint32_t can_periph) +{ + can_error_enum error; + error = CAN_ERROR_NONE; + + /* get error type */ + error = (can_error_enum)(GET_ERR_ERRN(CAN_ERR(can_periph))); + return error; +} + +/*! + \brief get CAN receive error number + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval error number +*/ +uint8_t can_receive_error_number_get(uint32_t can_periph) +{ + uint8_t val; + + /* get error count */ + val = (uint8_t)(GET_ERR_RECNT(CAN_ERR(can_periph))); + return val; +} + +/*! + \brief get CAN transmit error number + \param[in] can_periph + \arg CANx(x=0,1) + \param[out] none + \retval error number +*/ +uint8_t can_transmit_error_number_get(uint32_t can_periph) +{ + uint8_t val; + + val = (uint8_t)(GET_ERR_TECNT(CAN_ERR(can_periph))); + return val; +} + +/*! + \brief get CAN flag state + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] flag: CAN flags, refer to can_flag_enum + only one parameter can be selected which is shown as below: + \arg CAN_FLAG_RXL: RX level + \arg CAN_FLAG_LASTRX: last sample value of RX pin + \arg CAN_FLAG_RS: receiving state + \arg CAN_FLAG_TS: transmitting state + \arg CAN_FLAG_SLPIF: status change flag of entering sleep working mode + \arg CAN_FLAG_WUIF: status change flag of wakeup from sleep working mode + \arg CAN_FLAG_ERRIF: error flag + \arg CAN_FLAG_SLPWS: sleep working state + \arg CAN_FLAG_IWS: initial working state + \arg CAN_FLAG_TMLS2: transmit mailbox 2 last sending in TX FIFO + \arg CAN_FLAG_TMLS1: transmit mailbox 1 last sending in TX FIFO + \arg CAN_FLAG_TMLS0: transmit mailbox 0 last sending in TX FIFO + \arg CAN_FLAG_TME2: transmit mailbox 2 empty + \arg CAN_FLAG_TME1: transmit mailbox 1 empty + \arg CAN_FLAG_TME0: transmit mailbox 0 empty + \arg CAN_FLAG_MTE2: mailbox 2 transmit error + \arg CAN_FLAG_MTE1: mailbox 1 transmit error + \arg CAN_FLAG_MTE0: mailbox 0 transmit error + \arg CAN_FLAG_MAL2: mailbox 2 arbitration lost + \arg CAN_FLAG_MAL1: mailbox 1 arbitration lost + \arg CAN_FLAG_MAL0: mailbox 0 arbitration lost + \arg CAN_FLAG_MTFNERR2: mailbox 2 transmit finished with no error + \arg CAN_FLAG_MTFNERR1: mailbox 1 transmit finished with no error + \arg CAN_FLAG_MTFNERR0: mailbox 0 transmit finished with no error + \arg CAN_FLAG_MTF2: mailbox 2 transmit finished + \arg CAN_FLAG_MTF1: mailbox 1 transmit finished + \arg CAN_FLAG_MTF0: mailbox 0 transmit finished + \arg CAN_FLAG_RFO0: receive FIFO0 overfull + \arg CAN_FLAG_RFF0: receive FIFO0 full + \arg CAN_FLAG_RFO1: receive FIFO1 overfull + \arg CAN_FLAG_RFF1: receive FIFO1 full + \arg CAN_FLAG_BOERR: bus-off error + \arg CAN_FLAG_PERR: passive error + \arg CAN_FLAG_WERR: warning error + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus can_flag_get(uint32_t can_periph, can_flag_enum flag) +{ + /* get flag and interrupt enable state */ + if(RESET != (CAN_REG_VAL(can_periph, flag) & BIT(CAN_BIT_POS(flag)))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear CAN flag state + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] flag: CAN flags, refer to can_flag_enum + only one parameter can be selected which is shown as below: + \arg CAN_FLAG_SLPIF: status change flag of entering sleep working mode + \arg CAN_FLAG_WUIF: status change flag of wakeup from sleep working mode + \arg CAN_FLAG_ERRIF: error flag + \arg CAN_FLAG_MTE2: mailbox 2 transmit error + \arg CAN_FLAG_MTE1: mailbox 1 transmit error + \arg CAN_FLAG_MTE0: mailbox 0 transmit error + \arg CAN_FLAG_MAL2: mailbox 2 arbitration lost + \arg CAN_FLAG_MAL1: mailbox 1 arbitration lost + \arg CAN_FLAG_MAL0: mailbox 0 arbitration lost + \arg CAN_FLAG_MTFNERR2: mailbox 2 transmit finished with no error + \arg CAN_FLAG_MTFNERR1: mailbox 1 transmit finished with no error + \arg CAN_FLAG_MTFNERR0: mailbox 0 transmit finished with no error + \arg CAN_FLAG_MTF2: mailbox 2 transmit finished + \arg CAN_FLAG_MTF1: mailbox 1 transmit finished + \arg CAN_FLAG_MTF0: mailbox 0 transmit finished + \arg CAN_FLAG_RFO0: receive FIFO0 overfull + \arg CAN_FLAG_RFF0: receive FIFO0 full + \arg CAN_FLAG_RFO1: receive FIFO1 overfull + \arg CAN_FLAG_RFF1: receive FIFO1 full + \param[out] none + \retval none +*/ +void can_flag_clear(uint32_t can_periph, can_flag_enum flag) +{ + CAN_REG_VAL(can_periph, flag) = BIT(CAN_BIT_POS(flag)); +} + +/*! + \brief enable CAN interrupt + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] interrupt + one or more parameters can be selected which are shown as below: + \arg CAN_INT_TME: transmit mailbox empty interrupt enable + \arg CAN_INT_RFNE0: receive FIFO0 not empty interrupt enable + \arg CAN_INT_RFF0: receive FIFO0 full interrupt enable + \arg CAN_INT_RFO0: receive FIFO0 overfull interrupt enable + \arg CAN_INT_RFNE1: receive FIFO1 not empty interrupt enable + \arg CAN_INT_RFF1: receive FIFO1 full interrupt enable + \arg CAN_INT_RFO1: receive FIFO1 overfull interrupt enable + \arg CAN_INT_WERR: warning error interrupt enable + \arg CAN_INT_PERR: passive error interrupt enable + \arg CAN_INT_BO: bus-off interrupt enable + \arg CAN_INT_ERRN: error number interrupt enable + \arg CAN_INT_ERR: error interrupt enable + \arg CAN_INT_WAKEUP: wakeup interrupt enable + \arg CAN_INT_SLPW: sleep working interrupt enable + \param[out] none + \retval none +*/ +void can_interrupt_enable(uint32_t can_periph, uint32_t interrupt) +{ + CAN_INTEN(can_periph) |= interrupt; +} + +/*! + \brief disable CAN interrupt + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] interrupt + one or more parameters can be selected which are shown as below: + \arg CAN_INT_TME: transmit mailbox empty interrupt enable + \arg CAN_INT_RFNE0: receive FIFO0 not empty interrupt enable + \arg CAN_INT_RFF0: receive FIFO0 full interrupt enable + \arg CAN_INT_RFO0: receive FIFO0 overfull interrupt enable + \arg CAN_INT_RFNE1: receive FIFO1 not empty interrupt enable + \arg CAN_INT_RFF1: receive FIFO1 full interrupt enable + \arg CAN_INT_RFO1: receive FIFO1 overfull interrupt enable + \arg CAN_INT_WERR: warning error interrupt enable + \arg CAN_INT_PERR: passive error interrupt enable + \arg CAN_INT_BO: bus-off interrupt enable + \arg CAN_INT_ERRN: error number interrupt enable + \arg CAN_INT_ERR: error interrupt enable + \arg CAN_INT_WAKEUP: wakeup interrupt enable + \arg CAN_INT_SLPW: sleep working interrupt enable + \param[out] none + \retval none +*/ +void can_interrupt_disable(uint32_t can_periph, uint32_t interrupt) +{ + CAN_INTEN(can_periph) &= ~interrupt; +} + +/*! + \brief get CAN interrupt flag state + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] flag: CAN interrupt flags, refer to can_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg CAN_INT_FLAG_SLPIF: status change interrupt flag of sleep working mode entering + \arg CAN_INT_FLAG_WUIF: status change interrupt flag of wakeup from sleep working mode + \arg CAN_INT_FLAG_ERRIF: error interrupt flag + \arg CAN_INT_FLAG_MTF2: mailbox 2 transmit finished interrupt flag + \arg CAN_INT_FLAG_MTF1: mailbox 1 transmit finished interrupt flag + \arg CAN_INT_FLAG_MTF0: mailbox 0 transmit finished interrupt flag + \arg CAN_INT_FLAG_RFO0: receive FIFO0 overfull interrupt flag + \arg CAN_INT_FLAG_RFF0: receive FIFO0 full interrupt flag + \arg CAN_INT_FLAG_RFL0: receive FIFO0 not empty interrupt flag + \arg CAN_INT_FLAG_RFO1: receive FIFO1 overfull interrupt flag + \arg CAN_INT_FLAG_RFF1: receive FIFO1 full interrupt flag + \arg CAN_INT_FLAG_RFL1: receive FIFO1 not empty interrupt flag + \arg CAN_INT_FLAG_ERRN: error number interrupt flag + \arg CAN_INT_FLAG_BOERR: bus-off error interrupt flag + \arg CAN_INT_FLAG_PERR: passive error interrupt flag + \arg CAN_INT_FLAG_WERR: warning error interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus can_interrupt_flag_get(uint32_t can_periph, can_interrupt_flag_enum flag) +{ + uint32_t ret1 = RESET; + uint32_t ret2 = RESET; + + /* get the status of interrupt flag */ + if(flag == CAN_INT_FLAG_RFL0) { + ret1 = can_receive_message_length_get(can_periph, CAN_FIFO0); + } else if(flag == CAN_INT_FLAG_RFL1) { + ret1 = can_receive_message_length_get(can_periph, CAN_FIFO1); + } else if(flag == CAN_INT_FLAG_ERRN) { + ret1 = can_error_get(can_periph); + } else { + ret1 = CAN_REG_VALS(can_periph, flag) & BIT(CAN_BIT_POS0(flag)); + } + /* get the status of interrupt enable bit */ + ret2 = CAN_INTEN(can_periph) & BIT(CAN_BIT_POS1(flag)); + if(ret1 && ret2) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear CAN interrupt flag state + \param[in] can_periph + \arg CANx(x=0,1) + \param[in] flag: CAN interrupt flags, refer to can_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg CAN_INT_FLAG_SLPIF: status change interrupt flag of sleep working mode entering + \arg CAN_INT_FLAG_WUIF: status change interrupt flag of wakeup from sleep working mode + \arg CAN_INT_FLAG_ERRIF: error interrupt flag + \arg CAN_INT_FLAG_MTF2: mailbox 2 transmit finished interrupt flag + \arg CAN_INT_FLAG_MTF1: mailbox 1 transmit finished interrupt flag + \arg CAN_INT_FLAG_MTF0: mailbox 0 transmit finished interrupt flag + \arg CAN_INT_FLAG_RFO0: receive FIFO0 overfull interrupt flag + \arg CAN_INT_FLAG_RFF0: receive FIFO0 full interrupt flag + \arg CAN_INT_FLAG_RFO1: receive FIFO1 overfull interrupt flag + \arg CAN_INT_FLAG_RFF1: receive FIFO1 full interrupt flag + \param[out] none + \retval none +*/ +void can_interrupt_flag_clear(uint32_t can_periph, can_interrupt_flag_enum flag) +{ + CAN_REG_VALS(can_periph, flag) = BIT(CAN_BIT_POS0(flag)); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau.c new file mode 100644 index 0000000..f11f8bd --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau.c @@ -0,0 +1,719 @@ +/*! + \file gd32f5xx_cau.c + \brief CAU driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_cau.h" +#include "gd32f5xx_rcu.h" + +#define FLAG_MASK ((uint32_t)0x00000020U) +#define STAT0_AESDES_MASK ((uint32_t)0x00000015U) +#define STAT0_TDES_MASK ((uint32_t)0x00000014U) + +/*! + \brief reset the CAU peripheral + \param[in] none + \param[out] none + \retval none +*/ +void cau_deinit(void) +{ + /* enable CAU reset state */ + rcu_periph_reset_enable(RCU_CAURST); + /* release CAU from reset state */ + rcu_periph_reset_disable(RCU_CAURST); +} + + +/*! + \brief initialize the CAU encrypt and decrypt parameter struct with the default values + \param[in] none + \param[out] cau_parameter: + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key + key_size: key size in bytes + iv: initialization vector + iv_size: iv size in bytes + input: input data + in_length: input data length in bytes + aad: additional authentication data + aad_size: header size + \retval none +*/ +void cau_struct_para_init(cau_parameter_struct *cau_parameter) +{ + /* set the CAU encrypt and decrypt parameters struct with the default values */ + cau_parameter->alg_dir = CAU_ENCRYPT; + cau_parameter->key = 0U; + cau_parameter->key_size = 0U; + cau_parameter->iv = 0U; + cau_parameter->iv_size = 0U; + cau_parameter->input = 0U; + cau_parameter->in_length = 0U; + cau_parameter->aad = 0U; + cau_parameter->aad_size = 0U; +} + +/*! + \brief initialize the key parameter structure with the default values + \param[in] none + \param[out] key_initpara: + key_0_high: key 0 high + key_0_low: key 0 low + key_1_high: key 1 high + key_1_low: key 1 low + key_2_high: key 2 high + key_2_low: key 2 low + key_3_high: key 3 high + key_3_low: key 3 low + \retval none +*/ +void cau_key_struct_para_init(cau_key_parameter_struct *key_initpara) +{ + /* set the key parameters struct with the default values */ + key_initpara->key_0_high = 0U; + key_initpara->key_0_low = 0U; + key_initpara->key_1_high = 0U; + key_initpara->key_1_low = 0U; + key_initpara->key_2_high = 0U; + key_initpara->key_2_low = 0U; + key_initpara->key_3_high = 0U; + key_initpara->key_3_low = 0U; +} + +/*! + \brief initialize the vectors parameter struct with the default values + \param[in] none + \param[out] iv_initpara: + iv_0_high: init vector 0 high + iv_0_low: init vector 0 low + iv_1_high: init vector 1 high + iv_1_low: init vector 1 low + \retval none +*/ +void cau_iv_struct_para_init(cau_iv_parameter_struct *iv_initpara) +{ + /* set the vectors parameters struct with the default values */ + iv_initpara->iv_0_high = 0U; + iv_initpara->iv_0_low = 0U; + iv_initpara->iv_1_high = 0U; + iv_initpara->iv_1_low = 0U; +} + +/*! + \brief initialize the context parameter struct with the default values + \param[in] none + \param[out] cau_context: + ctl_config: current configuration + iv_0_high: init vector 0 high + iv_0_low: init vector 0 low + iv_1_high: init vector 1 high + iv_1_low: init vector 1 low + key_0_high: key 0 high + key_0_low: key 0 low + key_1_high: key 1 high + key_1_low: key 1 low + key_2_high: key 2 high + key_2_low: key 2 low + key_3_high: key 3 high + key_3_low: key 3 low + gcmccmctxs[8]: GCM or CCM mode context switch + gcmctxs[8]: GCM mode context switch + \retval none +*/ +void cau_context_struct_para_init(cau_context_parameter_struct *cau_context) +{ + cau_context->ctl_config = 0U; + + /* set the vectors parameters with the default values */ + cau_context->iv_0_high = 0U; + cau_context->iv_0_low = 0U; + cau_context->iv_1_high = 0U; + cau_context->iv_1_low = 0U; + + /* set the key parameters with the default values */ + cau_context->key_0_high = 0U; + cau_context->key_0_low = 0U; + cau_context->key_1_high = 0U; + cau_context->key_1_low = 0U; + cau_context->key_2_high = 0U; + cau_context->key_2_low = 0U; + cau_context->key_3_high = 0U; + cau_context->key_3_low = 0U; + + /* set the context switch with the default values */ + cau_context->gcmccmctxs[0] = 0U; + cau_context->gcmccmctxs[1] = 0U; + cau_context->gcmccmctxs[2] = 0U; + cau_context->gcmccmctxs[3] = 0U; + cau_context->gcmccmctxs[4] = 0U; + cau_context->gcmccmctxs[5] = 0U; + cau_context->gcmccmctxs[6] = 0U; + cau_context->gcmccmctxs[7] = 0U; + + cau_context->gcmctxs[0] = 0U; + cau_context->gcmctxs[1] = 0U; + cau_context->gcmctxs[2] = 0U; + cau_context->gcmctxs[3] = 0U; + cau_context->gcmctxs[4] = 0U; + cau_context->gcmctxs[5] = 0U; + cau_context->gcmctxs[6] = 0U; + cau_context->gcmctxs[7] = 0U; +} + +/*! + \brief enable the CAU peripheral + \param[in] none + \param[out] none + \retval none +*/ +void cau_enable(void) +{ + /* enable the CAU processor */ + CAU_CTL |= CAU_CTL_CAUEN; +} + +/*! + \brief disable the CAU peripheral + \param[in] none + \param[out] none + \retval none +*/ +void cau_disable(void) +{ + /* disable the CAU processor */ + CAU_CTL &= ~CAU_CTL_CAUEN; +} + +/*! + \brief enable the CAU DMA interface + \param[in] dma_req: specify the CAU DMA transfer request to be enabled + one or more parameters can be selected which are shown as below: + \arg CAU_DMA_INFIFO: DMA for incoming(Rx) data transfer + \arg CAU_DMA_OUTFIFO: DMA for outgoing(Tx) data transfer + \param[out] none + \retval none +*/ +void cau_dma_enable(uint32_t dma_req) +{ + /* enable the selected CAU DMA request */ + CAU_DMAEN |= dma_req; +} + +/*! + \brief disable the CAU DMA interface + \param[in] dma_req: specify the CAU DMA transfer request to be disabled + one or more parameters can be selected which are shown as below: + \arg CAU_DMA_INFIFO: DMA for incoming(Rx) data transfer + \arg CAU_DMA_OUTFIFO: DMA for outgoing(Tx) data transfer + \param[out] none + \retval none +*/ +void cau_dma_disable(uint32_t dma_req) +{ + /* disable the selected CAU DMA request */ + CAU_DMAEN &= ~(dma_req); +} + +/*! + \brief initialize the CAU peripheral + \param[in] alg_dir: algorithm direction + only one parameter can be selected which is shown as below: + \arg CAU_ENCRYPT: encrypt + \arg CAU_DECRYPT: decrypt + \param[in] algo_mode: algorithm mode selection + only one parameter can be selected which is shown as below: + \arg CAU_MODE_TDES_ECB: TDES-ECB (3DES Electronic codebook) + \arg CAU_MODE_TDES_CBC: TDES-CBC (3DES Cipher block chaining) + \arg CAU_MODE_DES_ECB: DES-ECB (simple DES Electronic codebook) + \arg CAU_MODE_DES_CBC: DES-CBC (simple DES Cipher block chaining) + \arg CAU_MODE_AES_ECB: AES-ECB (AES Electronic codebook) + \arg CAU_MODE_AES_CBC: AES-CBC (AES Cipher block chaining) + \arg CAU_MODE_AES_CTR: AES-CTR (AES counter mode) + \arg CAU_MODE_AES_KEY: AES decryption key preparation mode + \arg CAU_MODE_AES_GCM: AES-GCM (AES Galois/counter mode) + \arg CAU_MODE_AES_CCM: AES-CCM (AES combined cipher machine mode) + \arg CAU_MODE_AES_CFB: AES-CFB (cipher feedback mode) + \arg CAU_MODE_AES_OFB: AES-OFB (output feedback mode) + \param[in] swapping: data swapping selection + only one parameter can be selected which is shown as below: + \arg CAU_SWAPPING_32BIT: no swapping + \arg CAU_SWAPPING_16BIT: half-word swapping + \arg CAU_SWAPPING_8BIT: bytes swapping + \arg CAU_SWAPPING_1BIT: bit swapping + \param[out] none + \retval none +*/ +void cau_init(uint32_t alg_dir, uint32_t algo_mode, uint32_t swapping) +{ + /* select algorithm mode */ + CAU_CTL &= ~CAU_CTL_ALGM; + CAU_CTL |= algo_mode; + + /* select data swapping */ + CAU_CTL &= ~CAU_CTL_DATAM; + CAU_CTL |= swapping; + + /* select algorithm direction */ + CAU_CTL &= ~CAU_CTL_CAUDIR; + CAU_CTL |= alg_dir; +} + +/*! + \brief configure key size if use AES algorithm + \param[in] key_size: key length selection when aes mode + only one parameter can be selected which is shown as below: + \arg CAU_KEYSIZE_128BIT: 128 bit key length + \arg CAU_KEYSIZE_192BIT: 192 bit key length + \arg CAU_KEYSIZE_256BIT: 256 bit key length + \param[out] none + \retval none +*/ +void cau_aes_keysize_config(uint32_t key_size) +{ + CAU_CTL &= ~CAU_CTL_KEYM; + CAU_CTL |= key_size; +} + +/*! + \brief initialize the key parameters + \param[in] key_initpara: key init parameter struct + key_0_high: key 0 high + key_0_low: key 0 low + key_1_high: key 1 high + key_1_low: key 1 low + key_2_high: key 2 high + key_2_low: key 2 low + key_3_high: key 3 high + key_3_low: key 3 low + \param[out] none + \retval none +*/ +void cau_key_init(cau_key_parameter_struct *key_initpara) +{ + CAU_KEY0H = key_initpara->key_0_high; + CAU_KEY0L = key_initpara->key_0_low; + CAU_KEY1H = key_initpara->key_1_high; + CAU_KEY1L = key_initpara->key_1_low; + CAU_KEY2H = key_initpara->key_2_high; + CAU_KEY2L = key_initpara->key_2_low; + CAU_KEY3H = key_initpara->key_3_high; + CAU_KEY3L = key_initpara->key_3_low; +} + +/*! + \brief initialize the vectors parameters + \param[in] iv_initpara: vectors init parameter struct + iv_0_high: init vector 0 high + iv_0_low: init vector 0 low + iv_1_high: init vector 1 high + iv_1_low: init vector 1 low + \param[out] none + \retval none +*/ +void cau_iv_init(cau_iv_parameter_struct *iv_initpara) +{ + CAU_IV0H = iv_initpara->iv_0_high; + CAU_IV0L = iv_initpara->iv_0_low; + CAU_IV1H = iv_initpara->iv_1_high; + CAU_IV1L = iv_initpara->iv_1_low; +} + +/*! + \brief configure phase + \param[in] phase: gcm or ccm phase + only one parameter can be selected which is shown as below: + \arg CAU_PREPARE_PHASE: prepare phase + \arg CAU_AAD_PHASE: AAD phase + \arg CAU_ENCRYPT_DECRYPT_PHASE: encryption/decryption phase + \arg CAU_TAG_PHASE: tag phase + \param[out] none + \retval none +*/ +void cau_phase_config(uint32_t phase) +{ + uint32_t temp; + /* Get the CTL register */ + temp = CAU_CTL; + /* Reset the phase configuration bits */ + temp &= ~CAU_CTL_GCM_CCMPH; + /* Set the selected phase */ + temp |= phase; + /* Set the CTL register */ + CAU_CTL = temp; +} + +/*! + \brief flush the IN and OUT FIFOs + \param[in] none + \param[out] none + \retval none +*/ +void cau_fifo_flush(void) +{ + /* reset the read and write pointers of the FIFOs */ + CAU_CTL |= CAU_CTL_FFLUSH; +} + +/*! + \brief return whether CAU peripheral is enabled or disabled + \param[in] none + \param[out] none + \retval ControlStatus: ENABLE or DISABLE +*/ +ControlStatus cau_enable_state_get(void) +{ + ControlStatus ret = DISABLE; + if(RESET != (CAU_CTL & CAU_CTL_CAUEN)) { + ret = ENABLE; + } + return ret; +} + +/*! + \brief write data to the IN FIFO + \param[in] data: data to write (0 - 0xFFFFFFFF) + \param[out] none + \retval none +*/ +void cau_data_write(uint32_t data) +{ + CAU_DI = data; +} + +/*! + \brief return the last data entered into the output FIFO + \param[in] none + \param[out] none + \retval last data entered into the output FIFO +*/ +uint32_t cau_data_read(void) +{ + return CAU_DO; +} + +/*! + \brief save context before context switching + \param[in] key_initpara: key init parameter struct + key_0_high: key 0 high + key_0_low: key 0 low + key_1_high: key 1 high + key_1_low: key 1 low + key_2_high: key 2 high + key_2_low: key 2 low + key_3_high: key 3 high + key_3_low: key 3 low + \param[out] cau_context: + ctl_config: current configuration + iv_0_high: init vector 0 high + iv_0_low: init vector 0 low + iv_1_high: init vector 1 high + iv_1_low: init vector 1 low + key_0_high: key 0 high + key_0_low: key 0 low + key_1_high: key 1 high + key_1_low: key 1 low + key_2_high: key 2 high + key_2_low: key 2 low + key_3_high: key 3 high + key_3_low: key 3 low + gcmccmctxs[8]: GCM or CCM mode context switch + gcmctxs[8]: GCM mode context switch + \retval none +*/ +void cau_context_save(cau_context_parameter_struct *cau_context, cau_key_parameter_struct *key_initpara) +{ + uint32_t checkmask = 0U; + uint32_t checkbits = 0U; + uint32_t algm_reg = 0U; + + /* stop DMA transfers on the IN FIFO by clearing the DMAIEN bit in the CAU_DMAEN */ + CAU_DMAEN &= ~CAU_DMA_INFIFO; + + algm_reg = CAU_CTL & CAU_CTL_ALGM; + /* AES or DES */ + if((uint32_t)0 != (algm_reg & (~CAU_MODE_TDES_CBC))) { + /* wait until both the IN and OUT FIFOs are empty (IEM=1 and ONE=0 in the CAU_STAT0 register) and BUSY=0 */ + checkbits = CAU_STAT0_IEM; + checkmask = STAT0_AESDES_MASK; + /* TDES */ + } else { + /* wait until OUT FIFO is empty (ONE=0 in the CAU_STAT0 register) and BUSY=0 */ + checkbits = 0U; + checkmask = STAT0_TDES_MASK; + } + + while((CAU_STAT0 & checkmask) != checkbits) { + } + + /* stop DMA transfers on the OUT FIFO by clear CAU_DMAEN_DMAOEN=0 */ + CAU_DMAEN &= ~CAU_DMAEN_DMAOEN; + /* disable CAU */ + CAU_CTL &= ~CAU_CTL_CAUEN; + + /* save the current configuration (bit 19, bit[17:16] and bit[9:2] in the CAU_CTL register) */ + cau_context->ctl_config = CAU_CTL & (CAU_CTL_GCM_CCMPH | + CAU_CTL_KEYM | + CAU_CTL_DATAM | + CAU_CTL_ALGM | + CAU_CTL_CAUDIR | + CAU_CTL_NBPILB); + + /* save the key value */ + cau_context->key_0_high = key_initpara->key_0_high; + cau_context->key_0_low = key_initpara->key_0_low; + cau_context->key_1_high = key_initpara->key_1_high; + cau_context->key_1_low = key_initpara->key_1_low; + cau_context->key_2_high = key_initpara->key_2_high; + cau_context->key_2_low = key_initpara->key_2_low; + cau_context->key_3_high = key_initpara->key_3_high; + cau_context->key_3_low = key_initpara->key_3_low; + + if((CAU_MODE_TDES_ECB != algm_reg) && (CAU_MODE_DES_ECB != algm_reg) && (CAU_MODE_AES_ECB != algm_reg)) { + /* if not in ECB mode, save the initialization vectors */ + cau_context->iv_0_high = CAU_IV0H; + cau_context->iv_0_low = CAU_IV0L; + cau_context->iv_1_high = CAU_IV1H; + cau_context->iv_1_low = CAU_IV1L; + } + + /* if in GCM/CCM mode, save the context switch registers */ + if((CAU_MODE_AES_GCM == algm_reg) || (CAU_MODE_AES_CCM == algm_reg)) { + cau_context->gcmccmctxs[0U] = CAU_GCMCCMCTXSx(0U); + cau_context->gcmccmctxs[1U] = CAU_GCMCCMCTXSx(1U); + cau_context->gcmccmctxs[2U] = CAU_GCMCCMCTXSx(2U); + cau_context->gcmccmctxs[3U] = CAU_GCMCCMCTXSx(3U); + cau_context->gcmccmctxs[4U] = CAU_GCMCCMCTXSx(4U); + cau_context->gcmccmctxs[5U] = CAU_GCMCCMCTXSx(5U); + cau_context->gcmccmctxs[6U] = CAU_GCMCCMCTXSx(6U); + cau_context->gcmccmctxs[7U] = CAU_GCMCCMCTXSx(7U); + } + + /* if in GCM mode, save the context switch registers */ + if(CAU_MODE_AES_GCM == algm_reg) { + cau_context->gcmctxs[0U] = CAU_GCMCTXSx(0U); + cau_context->gcmctxs[1U] = CAU_GCMCTXSx(1U); + cau_context->gcmctxs[2U] = CAU_GCMCTXSx(2U); + cau_context->gcmctxs[3U] = CAU_GCMCTXSx(3U); + cau_context->gcmctxs[4U] = CAU_GCMCTXSx(4U); + cau_context->gcmctxs[5U] = CAU_GCMCTXSx(5U); + cau_context->gcmctxs[6U] = CAU_GCMCTXSx(6U); + cau_context->gcmctxs[7U] = CAU_GCMCTXSx(7U); + } +} + +/*! + \brief restore context after context switching + \param[in] cau_context: + ctl_config: current configuration + iv_0_high: init vector 0 high + iv_0_low: init vector 0 low + iv_1_high: init vector 1 high + iv_1_low: init vector 1 low + key_0_high: key 0 high + key_0_low: key 0 low + key_1_high: key 1 high + key_1_low: key 1 low + key_2_high: key 2 high + key_2_low: key 2 low + key_3_high: key 3 high + key_3_low: key 3 low + gcmccmctxs[8]: GCM or CCM mode context switch + gcmctxs[8]: GCM mode context switch + \param[out] none + \retval none +*/ +void cau_context_restore(cau_context_parameter_struct *cau_context) +{ + uint32_t algm_reg, aes_decrypt; + + /* configure the processor with the saved configuration */ + CAU_CTL = cau_context->ctl_config; + + algm_reg = CAU_CTL & CAU_CTL_ALGM; + + /* restore the key value */ + CAU_KEY0H = cau_context->key_0_high; + CAU_KEY0L = cau_context->key_0_low; + CAU_KEY1H = cau_context->key_1_high; + CAU_KEY1L = cau_context->key_1_low; + CAU_KEY2H = cau_context->key_2_high; + CAU_KEY2L = cau_context->key_2_low; + CAU_KEY3H = cau_context->key_3_high; + CAU_KEY3L = cau_context->key_3_low; + + if((CAU_MODE_TDES_ECB != algm_reg) && (CAU_MODE_DES_ECB != algm_reg) && (CAU_MODE_AES_ECB != algm_reg)) { + /* restore the initialization vectors */ + CAU_IV0H = cau_context->iv_0_high; + CAU_IV0L = cau_context->iv_0_low; + CAU_IV1H = cau_context->iv_1_high; + CAU_IV1L = cau_context->iv_1_low; + } + + /* if in GCM/CCM mode, restore the context switch registers */ + if((CAU_MODE_AES_GCM == algm_reg) || (CAU_MODE_AES_CCM == algm_reg)) { + CAU_GCMCCMCTXSx(0U) = cau_context->gcmccmctxs[0U]; + CAU_GCMCCMCTXSx(1U) = cau_context->gcmccmctxs[1U]; + CAU_GCMCCMCTXSx(2U) = cau_context->gcmccmctxs[2U]; + CAU_GCMCCMCTXSx(3U) = cau_context->gcmccmctxs[3U]; + CAU_GCMCCMCTXSx(4U) = cau_context->gcmccmctxs[4U]; + CAU_GCMCCMCTXSx(5U) = cau_context->gcmccmctxs[5U]; + CAU_GCMCCMCTXSx(6U) = cau_context->gcmccmctxs[6U]; + CAU_GCMCCMCTXSx(7U) = cau_context->gcmccmctxs[7U]; + } + + /* if in GCM mode, restore the context switch registers */ + if(CAU_MODE_AES_GCM == algm_reg) { + CAU_GCMCTXSx(0U) = cau_context->gcmctxs[0U]; + CAU_GCMCTXSx(1U) = cau_context->gcmctxs[1U]; + CAU_GCMCTXSx(2U) = cau_context->gcmctxs[2U]; + CAU_GCMCTXSx(3U) = cau_context->gcmctxs[3U]; + CAU_GCMCTXSx(4U) = cau_context->gcmctxs[4U]; + CAU_GCMCTXSx(5U) = cau_context->gcmctxs[5U]; + CAU_GCMCTXSx(6U) = cau_context->gcmctxs[6U]; + CAU_GCMCTXSx(7U) = cau_context->gcmctxs[7U]; + } + + /* if it is AES ECB/CBC decryption, then first prepare key */ + aes_decrypt = CAU_CTL & (CAU_CTL_ALGM | CAU_CTL_CAUDIR); + if(((CAU_MODE_AES_ECB | CAU_DECRYPT) == aes_decrypt) || ((CAU_MODE_AES_CBC | CAU_DECRYPT) == aes_decrypt)) { + uint32_t alg_dir, algo_mode, swapping; + + /* flush IN/OUT FIFOs */ + cau_fifo_flush(); + /* parameters for key preparation for AES decryption */ + alg_dir = CAU_DECRYPT; + algo_mode = CAU_MODE_AES_KEY; + swapping = CAU_SWAPPING_32BIT; + cau_init(alg_dir, algo_mode, swapping); + + /* enable CAU */ + cau_enable(); + + /* wait until BUSY=0 */ + while((uint32_t)0U != cau_flag_get(CAU_FLAG_BUSY)) { + } + + /* parameters for decryption */ + CAU_CTL = cau_context->ctl_config; + } + + /* enable CAU */ + cau_enable(); +} + +/*! + \brief get the CAU flag status + \param[in] flag: CAU flag status + only one parameter can be selected which is shown as below: + \arg CAU_FLAG_INFIFO_EMPTY: input FIFO empty + \arg CAU_FLAG_INFIFO_NO_FULL: input FIFO is not full + \arg CAU_FLAG_OUTFIFO_NO_EMPTY: output FIFO not empty + \arg CAU_FLAG_OUTFIFO_FULL: output FIFO is full + \arg CAU_FLAG_BUSY: the CAU core is busy + \arg CAU_FLAG_INFIFO: input FIFO flag status + \arg CAU_FLAG_OUTFIFO: output FIFO flag status + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus cau_flag_get(uint32_t flag) +{ + uint32_t reg = 0U; + FlagStatus ret_flag = RESET; + + /* check if the flag is in CAU_STAT1 register */ + if(RESET != (flag & FLAG_MASK)) { + reg = CAU_STAT1; + } else { + /* the flag is in CAU_STAT0 register */ + reg = CAU_STAT0; + } + + /* check the status of the specified CAU flag */ + if(RESET != (reg & flag)) { + ret_flag = SET; + } + + return ret_flag; +} + +/*! + \brief enable the CAU interrupts + \param[in] interrupt: specify the CAU interrupt source to be enabled + one or more parameters can be selected which are shown as below: + \arg CAU_INT_INFIFO: input FIFO interrupt + \arg CAU_INT_OUTFIFO: output FIFO interrupt + \param[out] none + \retval none +*/ +void cau_interrupt_enable(uint32_t interrupt) +{ + /* enable the selected CAU interrupt */ + CAU_INTEN |= interrupt; +} + +/*! + \brief disable the CAU interrupts + \param[in] interrupt: specify the CAU interrupt source to be disabled + one or more parameters can be selected which are shown as below: + \arg CAU_INT_INFIFO: input FIFO interrupt + \arg CAU_INT_OUTFIFO: output FIFO interrupt + \param[out] none + \retval none +*/ +void cau_interrupt_disable(uint32_t interrupt) +{ + /* disable the selected CAU interrupt */ + CAU_INTEN &= ~(interrupt); +} + +/*! + \brief get the interrupt flag + \param[in] interrupt: CAU interrupt flag + only one parameter can be selected which is shown as below: + \arg CAU_INT_FLAG_INFIFO: input FIFO interrupt + \arg CAU_INT_FLAG_OUTFIFO: output FIFO interrupt + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus cau_interrupt_flag_get(uint32_t interrupt) +{ + FlagStatus flag = RESET; + + /* check the status of the specified CAU interrupt */ + if(RESET != (CAU_INTF & interrupt)) { + flag = SET; + } + + return flag; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_aes.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_aes.c new file mode 100644 index 0000000..c5a9bc7 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_aes.c @@ -0,0 +1,915 @@ +/*! + \file gd32f5xx_cau_aes.c + \brief CAU AES driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_cau.h" +#include "string.h" + +#define AESBSY_TIMEOUT ((uint32_t)0x00010000U) +#define BLOCK_B0_MASK ((uint8_t)0x07U) +#define BLOCK_DATA_SIZE 16U +#define MAX_CCM_IV_SIZE 15U + +/* configure AES key structure parameter */ +static void cau_aes_key_config(uint8_t *key, uint32_t keysize, cau_key_parameter_struct *cau_key_initpara); +/* fill data into data input register */ +static ErrStatus cau_fill_data(uint8_t *input, uint32_t in_length); +/* AES calculate process */ +static ErrStatus cau_aes_calculate(uint8_t *input, uint32_t in_length, uint8_t *output); + +/*! + \brief encrypt and decrypt using AES in ECB mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key + key_size: key size in bits, must be either 128, 192 or 256 + input: input data + in_length: input data length in bytes, must be a multiple of 16 bytes + \param[out] output: pointer to the returned buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_aes_ecb(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + __IO uint32_t counter = 0U; + uint32_t busystatus = 0U; + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* AES key structure parameter config */ + cau_aes_key_config(cau_parameter->key, cau_parameter->key_size, &key_initpara); + /* key initialization */ + cau_key_init(&key_initpara); + + /* AES decryption */ + if(CAU_DECRYPT == cau_parameter->alg_dir) { + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* initialize the CAU peripheral */ + cau_init(CAU_DECRYPT, CAU_MODE_AES_KEY, CAU_SWAPPING_32BIT); + + /* enable the CAU peripheral */ + cau_enable(); + + /* wait until the busy flag is RESET */ + do { + busystatus = cau_flag_get(CAU_FLAG_BUSY); + counter++; + } while((AESBSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus) { + return ERROR; + } + } + + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_AES_ECB, CAU_SWAPPING_8BIT); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + + /* enable the CAU peripheral */ + cau_enable(); + /* AES calculate process */ + ret = cau_aes_calculate(cau_parameter->input, cau_parameter->in_length, output); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief encrypt and decrypt using AES in CBC mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key + key_size: key size in bits, must be either 128, 192 or 256 + iv: initialization vector, 16 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 16 bytes + \param[out] output: pointer to the returned buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_aes_cbc(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + cau_iv_parameter_struct iv_initpara; + __IO uint32_t counter = 0U; + uint32_t busystatus = 0U; + + uint32_t ivaddr = (uint32_t)cau_parameter->iv; + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* AES key structure parameter config */ + cau_aes_key_config(cau_parameter->key, cau_parameter->key_size, &key_initpara); + /* key initialization */ + cau_key_init(&key_initpara); + + /* AES decryption */ + if(CAU_DECRYPT == cau_parameter->alg_dir) { + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* initialize the CAU peripheral */ + cau_init(CAU_DECRYPT, CAU_MODE_AES_KEY, CAU_SWAPPING_32BIT); + + /* enable the CAU peripheral */ + cau_enable(); + + /* wait until the busy flag is RESET */ + do { + busystatus = cau_flag_get(CAU_FLAG_BUSY); + counter++; + } while((AESBSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus) { + return ERROR; + } + } + + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_AES_CBC, CAU_SWAPPING_8BIT); + + /* vectors initialization */ + iv_initpara.iv_0_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_0_low = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_low = __REV(*(uint32_t *)(ivaddr)); + cau_iv_init(&iv_initpara); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + + /* enable the CAU peripheral */ + cau_enable(); + /* AES calculate process */ + ret = cau_aes_calculate(cau_parameter->input, cau_parameter->in_length, output); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief encrypt and decrypt using AES in CTR mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key + key_size: key size in bits, must be either 128, 192 or 256 + iv: initialization vector, 16 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 16 bytes + \param[out] output: pointer to the returned buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_aes_ctr(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + cau_iv_parameter_struct iv_initpara; + uint32_t ivaddr = (uint32_t)cau_parameter->iv; + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_AES_CTR, CAU_SWAPPING_8BIT); + + /* AES key structure parameter config */ + cau_aes_key_config(cau_parameter->key, cau_parameter->key_size, &key_initpara); + /* key initialization */ + cau_key_init(&key_initpara); + + /* vectors initialization */ + iv_initpara.iv_0_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_0_low = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_low = __REV(*(uint32_t *)(ivaddr)); + cau_iv_init(&iv_initpara); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + + /* enable the CAU peripheral */ + cau_enable(); + /* AES calculate process */ + ret = cau_aes_calculate(cau_parameter->input, cau_parameter->in_length, output); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief encrypt and decrypt using AES in CFB mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key + key_size: key size in bits, must be either 128, 192 or 256 + iv: initialization vector, 16 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 16 bytes + \param[out] output: pointer to the returned buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_aes_cfb(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + cau_iv_parameter_struct iv_initpara; + uint32_t ivaddr = (uint32_t)cau_parameter->iv; + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_AES_CFB, CAU_SWAPPING_8BIT); + + /* AES key structure parameter config */ + cau_aes_key_config(cau_parameter->key, cau_parameter->key_size, &key_initpara); + /* key initialization */ + cau_key_init(&key_initpara); + + /* vectors initialization */ + iv_initpara.iv_0_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_0_low = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_low = __REV(*(uint32_t *)(ivaddr)); + cau_iv_init(&iv_initpara); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* enable the CAU peripheral */ + cau_enable(); + /* AES calculate process */ + ret = cau_aes_calculate(cau_parameter->input, cau_parameter->in_length, output); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief encrypt and decrypt using AES in OFB mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key + key_size: key size in bits, must be either 128, 192 or 256 + iv: initialization vector, 16 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 16 bytes + \param[out] output: pointer to the returned buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_aes_ofb(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + cau_iv_parameter_struct iv_initpara; + uint32_t ivaddr = (uint32_t)cau_parameter->iv; + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_AES_OFB, CAU_SWAPPING_8BIT); + + /* AES key structure parameter config */ + cau_aes_key_config(cau_parameter->key, cau_parameter->key_size, &key_initpara); + /* key initialization */ + cau_key_init(&key_initpara); + + /* vectors initialization */ + iv_initpara.iv_0_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_0_low = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_low = __REV(*(uint32_t *)(ivaddr)); + cau_iv_init(&iv_initpara); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* enable the CAU peripheral */ + cau_enable(); + /* AES calculate process */ + ret = cau_aes_calculate(cau_parameter->input, cau_parameter->in_length, output); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief encrypt and decrypt using AES in GCM mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key + key_size: key size in bits, must be either 128, 192 or 256 + iv: initialization vector, 16 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 16 bytes + aad: additional authentication data + aad_size: aad size in bytes, must be a multiple of 16 bytes + \param[out] output: pointer to the returned output data buffer + \param[out] tag: pointer to the returned tag buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_aes_gcm(cau_parameter_struct *cau_parameter, uint8_t *output, uint8_t *tag) +{ + ErrStatus ret = SUCCESS; + cau_key_parameter_struct key_initpara; + cau_iv_parameter_struct iv_initpara; + uint64_t aadlength = (uint64_t)cau_parameter->aad_size * 8U; + uint64_t inputlength = (uint64_t)cau_parameter->in_length * 8U; + uint32_t ivaddr = (uint32_t)cau_parameter->iv; + uint32_t tagaddr = (uint32_t)tag; + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_AES_GCM, CAU_SWAPPING_8BIT); + + /* AES key structure parameter config */ + cau_aes_key_config(cau_parameter->key, cau_parameter->key_size, &key_initpara); + /* key initialization */ + cau_key_init(&key_initpara); + + /* vectors initialization */ + iv_initpara.iv_0_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_0_low = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_1_low = __REV(*(uint32_t *)(ivaddr)); + cau_iv_init(&iv_initpara); + + /* prepare phase */ + /* select prepare phase */ + cau_phase_config(CAU_PREPARE_PHASE); + /* enable the CAU peripheral */ + cau_enable(); + /* wait for CAUEN bit to be 0 */ + while(ENABLE == cau_enable_state_get()) { + } + + /* aad phase */ + if((uint32_t)0U != cau_parameter->aad_size) { + /* select aad phase */ + cau_phase_config(CAU_AAD_PHASE); + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* enable the CAU peripheral */ + cau_enable(); + + ret = cau_fill_data(cau_parameter->aad, cau_parameter->aad_size); + + if(ERROR == ret) { + return ret; + } + } + + /* encrypt or dcrypt phase */ + if((uint32_t)0U != cau_parameter->in_length) { + /* select encrypt or dcrypt phase */ + cau_phase_config(CAU_ENCRYPT_DECRYPT_PHASE); + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* enable the CAU peripheral */ + cau_enable(); + + /* AES calculate process */ + ret = cau_aes_calculate(cau_parameter->input, cau_parameter->in_length, output); + + if(ERROR == ret) { + return ret; + } + } + + /* tag phase */ + /* select tag phase */ + cau_phase_config(CAU_TAG_PHASE); + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* enable the CAU peripheral */ + cau_enable(); + + if(DISABLE == cau_enable_state_get()) { + return ERROR; + } + + cau_data_write(__REV((uint32_t)(aadlength >> 32U))); + cau_data_write(__REV((uint32_t)aadlength)); + cau_data_write(__REV((uint32_t)(inputlength >> 32U))); + cau_data_write(__REV((uint32_t)inputlength)); + + /* wait until the ONE flag is set */ + while(RESET == cau_flag_get(CAU_FLAG_OUTFIFO_NO_EMPTY)) { + } + + /* read the tag in the OUT FIFO */ + *(uint32_t *)(tagaddr) = cau_data_read(); + tagaddr += 4U; + *(uint32_t *)(tagaddr) = cau_data_read(); + tagaddr += 4U; + *(uint32_t *)(tagaddr) = cau_data_read(); + tagaddr += 4U; + *(uint32_t *)(tagaddr) = cau_data_read(); + tagaddr += 4U; + + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief encrypt and decrypt using AES in CCM mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key + key_size: key size in bytes + iv: initialization vector + iv_size: iv size in bytes + input: input data + in_length: input data length in bytes + aad: additional authentication data + aad_size: aad size + \param[in] mac_size: mac size (in bytes) + \param[out] output: pointer to the returned output data buffer + \param[out] tag: pointer to the returned tag buffer + \param[out] aad_buf: pointer to the user buffer used when formatting aad block + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_aes_ccm(cau_parameter_struct *cau_parameter, uint8_t *output, uint8_t tag[], uint32_t tag_size, + uint8_t aad_buf[]) +{ + cau_key_parameter_struct key_initpara; + cau_iv_parameter_struct iv_initpara; + ErrStatus ret = ERROR; + uint32_t inputaddr = (uint32_t)cau_parameter->input; + uint32_t inputsize = cau_parameter->in_length; + uint32_t aadaddr = (uint32_t)cau_parameter->aad; + uint32_t aadsize = cau_parameter->aad_size; + uint32_t aad_block_size = 0U; + uint32_t ivaddr = (uint32_t)cau_parameter->iv; + uint32_t ivsize = cau_parameter->iv_size; + uint32_t outputaddr = (uint32_t)output; + uint32_t i = 0U, plen = 0U; + uint32_t head_index = 0U; + uint8_t blockb0[16U] = {0U}; + uint8_t counter[16U] = {0U}; + uint32_t ctraddr = (uint32_t)counter; + uint32_t b0addr = (uint32_t)blockb0; + uint32_t temp_tag[4U]; + + /* formatting the aad block */ + if((uint32_t)0U != aadsize) { + /* check that the aad length is lower than 2^16 - 2^8 = 65536 - 256 = 65280 */ + if(aadsize < 65280U) { + aad_buf[head_index++] = (uint8_t)((aadsize >> 8U) & 0xFFU); + aad_buf[head_index++] = (uint8_t)((aadsize) & 0xFFU); + aad_block_size = aadsize + 2U; + } else { + /* aad is encoded as 0xFF || 0xFE || [aadsize]32, i.e., six octets */ + aad_buf[head_index++] = 0xFFU; + aad_buf[head_index++] = 0xFEU; + aad_buf[head_index++] = (uint8_t)((aadsize & 0xFF000000U) >> 24U); + aad_buf[head_index++] = (uint8_t)((aadsize & 0x00FF0000U) >> 16U); + aad_buf[head_index++] = (uint8_t)((aadsize & 0x0000FF00U) >> 8U); + aad_buf[head_index++] = (uint8_t)(aadsize & 0x000000FFU); + aad_block_size = aadsize + 6U; + } + /* copy the aad buffer in internal buffer "HBuffer" */ + for(i = 0U; i < aadsize; i++) { + aad_buf[head_index++] = *(uint8_t *)((uint32_t)(aadaddr + i)); + } + /* check if the aad block size is modulo 16 */ + if(0U != (aad_block_size % 16U)) { + /* Padd the aad buffer with 0s till the HBuffer length is modulo 16 */ + for(i = aad_block_size; i <= ((aad_block_size / 16U) + 1U) * 16U; i++) { + aad_buf[i] = 0U; + } + /* set the aad size to modulo 16 */ + aad_block_size = ((aad_block_size / 16U) + 1U) * 16U; + } + /* set the pointer aadaddr to HBuffer */ + aadaddr = (uint32_t)aad_buf; + } + + /* formatting the block B0 */ + if(0U != aadsize) { + blockb0[0] = 0x40U; + } + /* flags byte */ + blockb0[0] |= (0U | (((((uint8_t) tag_size - 2U) / 2U) & 0x07U) << 3U) | (((uint8_t)(15U - ivsize) - 1U) & 0x07U)); + + if(ivsize > MAX_CCM_IV_SIZE) { + return ERROR; + } + + for(i = 0U; i < ivsize; i++) { + blockb0[i + 1U] = *(uint8_t *)((uint32_t)(ivaddr + i)); + } + + /* the byte length for payload length expressing, which plus the ivsize must equal to 15 bytes */ + plen = 15U - ivsize; + /* if the byte length for payload length expressing is more than 4 bytes */ + if(plen > 4U) { + /* pad the blockb0 after vectors, and before the last 4 bytes */ + for(; i < 11U; i++) { + blockb0[i + 1U] = 0U; + } + blockb0[12U] = (uint8_t)((inputsize >> 24U) & 0xFFU); + blockb0[13U] = (uint8_t)((inputsize >> 16U) & 0xFFU); + blockb0[14U] = (uint8_t)((inputsize >> 8U) & 0xFFU); + blockb0[15U] = (uint8_t)(inputsize & 0xFFU); + } else { + /* the payload length is expressed in plen bytes */ + for(; i < 15U; i++) { + blockb0[i + 1U] = (uint8_t)((inputsize >> ((plen - 1U) * 8U)) & 0xFFU); + plen--; + } + } + + /* formatting the initial counter */ + /* byte 0: bits 0-2 contain the same encoding of q as in B0 */ + counter[0] = blockb0[0] & BLOCK_B0_MASK; + for(i = 1U; i < ivsize + 1U; i++) { + counter[i] = blockb0[i]; + } + /* set the LSB to 1 */ + counter[15] |= 0x01U; + + /* prepare phase */ + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* clear CAUEN bit to ensure CAU is disable */ + cau_disable(); + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_AES_CCM, CAU_SWAPPING_8BIT); + /* select prepare phase */ + cau_phase_config(CAU_PREPARE_PHASE); + + /* AES key structure parameter config */ + cau_aes_key_config(cau_parameter->key, cau_parameter->key_size, &key_initpara); + /* key initialization */ + cau_key_init(&key_initpara); + + /* vectors initialization */ + iv_initpara.iv_0_high = __REV(*(uint32_t *)(ctraddr)); + ctraddr += 4U; + iv_initpara.iv_0_low = __REV(*(uint32_t *)(ctraddr)); + ctraddr += 4U; + iv_initpara.iv_1_high = __REV(*(uint32_t *)(ctraddr)); + ctraddr += 4U; + iv_initpara.iv_1_low = __REV(*(uint32_t *)(ctraddr)); + cau_iv_init(&iv_initpara); + + /* enable the CAU peripheral */ + cau_enable(); + + /* write block B0 in the In FIFO */ + cau_data_write(*(uint32_t *)(b0addr)); + b0addr += 4U; + cau_data_write(*(uint32_t *)(b0addr)); + b0addr += 4U; + cau_data_write(*(uint32_t *)(b0addr)); + b0addr += 4U; + cau_data_write(*(uint32_t *)(b0addr)); + + /* wait for CAUEN bit to be 0 */ + while(ENABLE == cau_enable_state_get()) { + } + + /* aad phase */ + if((uint32_t)0U != aadsize) { + /* select aad phase */ + cau_phase_config(CAU_AAD_PHASE); + /* enable the CAU peripheral */ + cau_enable(); + + ret = cau_fill_data((uint8_t *)aadaddr, aad_block_size); + + if(ERROR == ret) { + return ret; + } + } + + /* encrypt or dcrypt phase */ + inputsize = cau_parameter->in_length; + + if((uint32_t)0U != inputsize) { + /* select encrypt or dcrypt phase */ + cau_phase_config(CAU_ENCRYPT_DECRYPT_PHASE); + /* enable the CAU peripheral */ + cau_enable(); + + /* AES calculate process */ + ret = cau_aes_calculate((uint8_t *)inputaddr, inputsize, (uint8_t *)outputaddr); + + if(ERROR == ret) { + return ret; + } + } + + /* tag phase */ + /* select final phase */ + cau_phase_config(CAU_TAG_PHASE); + /* enable the CAU peripheral */ + cau_enable(); + + if(DISABLE == cau_enable_state_get()) { + return ERROR; + } + + ctraddr = (uint32_t)counter; + + cau_data_write(*(uint32_t *)(ctraddr)); + ctraddr += 4U; + cau_data_write(*(uint32_t *)(ctraddr)); + ctraddr += 4U; + cau_data_write(*(uint32_t *)(ctraddr)); + ctraddr += 4U; + /* reset bit 0 (after 8-bit swap) is equivalent to reset bit 24 (before 8-bit swap) */ + cau_data_write(*(uint32_t *)(ctraddr) & 0xFEFFFFFFU); + + /* wait until the ONE flag is set */ + while(RESET == cau_flag_get(CAU_FLAG_OUTFIFO_NO_EMPTY)) { + } + + /* read the tag in the OUT FIFO */ + temp_tag[0] = cau_data_read(); + temp_tag[1] = cau_data_read(); + temp_tag[2] = cau_data_read(); + temp_tag[3] = cau_data_read(); + + /* disable the CAU peripheral */ + cau_disable(); + + /* Copy temporary authentication TAG in user TAG buffer */ + for(i = 0U; i < tag_size; i++) { + tag[i] = (uint8_t)(temp_tag[i / 4U] >> (8U * (i % 4U))); + } + + return ret; +} +/*! + \brief AES key structure parameter config + \param[in] key: key used for AES algorithm + \param[in] keysize: length of the key in bits, must be either 128, 192 or 256 + \param[out] cau_key_initpara: key init parameter struct + key_0_high: key 0 high + key_0_low: key 0 low + key_1_high: key 1 high + key_1_low: key 1 low + key_2_high: key 2 high + key_2_low: key 2 low + key_3_high: key 3 high + key_3_low: key 3 low + \retval none +*/ +static void cau_aes_key_config(uint8_t *key, uint32_t keysize, cau_key_parameter_struct *cau_key_initpara) +{ + uint32_t keyaddr = (uint32_t)key; + + switch(keysize) { + case 128: + cau_aes_keysize_config(CAU_KEYSIZE_128BIT); + cau_key_initpara->key_2_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_2_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_3_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_3_low = __REV(*(uint32_t *)(keyaddr)); + break; + case 192: + cau_aes_keysize_config(CAU_KEYSIZE_192BIT); + cau_key_initpara->key_1_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_1_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_2_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_2_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_3_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_3_low = __REV(*(uint32_t *)(keyaddr)); + break; + case 256: + cau_aes_keysize_config(CAU_KEYSIZE_256BIT); + cau_key_initpara->key_0_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_0_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_1_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_1_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_2_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_2_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_3_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + cau_key_initpara->key_3_low = __REV(*(uint32_t *)(keyaddr)); + break; + default: + break; + } +} + +/*! + \brief fill data into data input register + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer in bytes, must be a multiple of 16 bytes + \retval ErrStatus: SUCCESS or ERROR +*/ +static ErrStatus cau_fill_data(uint8_t *input, uint32_t in_length) +{ + uint32_t inputaddr = (uint32_t)input; + uint32_t i = 0U; + __IO uint32_t counter = 0U; + uint32_t busystatus = 0U; + + if(DISABLE == cau_enable_state_get()) { + return ERROR; + } + + for(i = 0U; i < in_length; i += BLOCK_DATA_SIZE) { + /* wait until the IEM flag is set */ + while(RESET == cau_flag_get(CAU_FLAG_INFIFO_EMPTY)) { + } + + if(i + BLOCK_DATA_SIZE > in_length) { + /* the last block data number is less than 128bit */ + uint32_t block_data_temp[4] = {0U}; + + /* fill the remaining bits with zero */ + memcpy(block_data_temp, (uint32_t *)inputaddr, in_length - i); + inputaddr = (uint32_t)block_data_temp; + + /* if GCM encryption or CCM decryption, then configurate NBPILB bits in CTL register */ + if((CAU_CTL & CAU_CTL_GCM_CCMPH) == CAU_ENCRYPT_DECRYPT_PHASE) { + if((CAU_CTL & (CAU_CTL_ALGM | CAU_CTL_CAUDIR)) == (CAU_MODE_AES_GCM | CAU_ENCRYPT)) { + CAU_CTL |= CAU_PADDING_BYTES(i + BLOCK_DATA_SIZE - in_length); + } else if((CAU_CTL & (CAU_CTL_ALGM | CAU_CTL_CAUDIR)) == (CAU_MODE_AES_CCM | CAU_DECRYPT)) { + CAU_CTL |= CAU_PADDING_BYTES(i + BLOCK_DATA_SIZE - in_length); + } else { + } + } + } + + /* write data to the IN FIFO */ + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + } + /* wait until the complete message has been processed */ + counter = 0U; + do { + busystatus = cau_flag_get(CAU_FLAG_BUSY); + counter++; + } while((AESBSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus) { + return ERROR; + } + + return SUCCESS; +} + +/*! + \brief AES calculate process + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer in bytes, must be a multiple of 16 bytes + \param[out] output: pointer to the returned buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +static ErrStatus cau_aes_calculate(uint8_t *input, uint32_t in_length, uint8_t *output) +{ + uint32_t inputaddr = (uint32_t)input; + uint32_t outputaddr = (uint32_t)output; + uint32_t i = 0U; + __IO uint32_t counter = 0U; + uint32_t busystatus = 0U; + + /* the clock is not enabled or there is no embeded CAU peripheral */ + if(DISABLE == cau_enable_state_get()) { + return ERROR; + } + + for(i = 0U; i < in_length; i += BLOCK_DATA_SIZE) { + /* wait until the IEM flag is set */ + while(RESET == cau_flag_get(CAU_FLAG_INFIFO_EMPTY)) { + } + + /* check if the last input data block */ + if(i + BLOCK_DATA_SIZE > in_length) { + /* the last block data number is less than 128bit */ + uint32_t block_data_temp[4] = {0}; + + /* fill the remaining bits with zero */ + memcpy(block_data_temp, (uint32_t *)inputaddr, in_length - i); + inputaddr = (uint32_t)block_data_temp; + + /* if GCM encryption or CCM decryption, then configurate NBPILB bits in CTL register */ + if((CAU_CTL & (CAU_CTL_ALGM | CAU_CTL_CAUDIR)) == (CAU_MODE_AES_GCM | CAU_ENCRYPT)) { + CAU_CTL |= CAU_PADDING_BYTES(i + BLOCK_DATA_SIZE - in_length); + } else if((CAU_CTL & (CAU_CTL_ALGM | CAU_CTL_CAUDIR)) == (CAU_MODE_AES_CCM | CAU_DECRYPT)) { + CAU_CTL |= CAU_PADDING_BYTES(i + BLOCK_DATA_SIZE - in_length); + } else { + } + } + + /* write data to the IN FIFO */ + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + + /* wait until the complete message has been processed */ + counter = 0U; + do { + busystatus = cau_flag_get(CAU_FLAG_BUSY); + counter++; + } while((AESBSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus) { + return ERROR; + } else { + /* read the output block from the output FIFO */ + *(uint32_t *)(outputaddr) = cau_data_read(); + outputaddr += 4U; + *(uint32_t *)(outputaddr) = cau_data_read(); + outputaddr += 4U; + *(uint32_t *)(outputaddr) = cau_data_read(); + outputaddr += 4U; + *(uint32_t *)(outputaddr) = cau_data_read(); + outputaddr += 4U; + } + } + + return SUCCESS; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_des.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_des.c new file mode 100644 index 0000000..691ad84 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_des.c @@ -0,0 +1,183 @@ +/*! + \file gd32f5xx_cau_des.c + \brief CAU DES driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_cau.h" + +#define DESBUSY_TIMEOUT ((uint32_t)0x00010000U) + +/* DES calculate process */ +static ErrStatus cau_des_calculate(uint8_t *input, uint32_t in_length, uint8_t *output); + +/*! + \brief encrypt and decrypt using DES in ECB mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key, 8 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 8 bytes + \param[out] output: pointer to the output buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_des_ecb(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + uint32_t keyaddr = (uint32_t)(cau_parameter->key); + uint32_t inputaddr = (uint32_t)(cau_parameter->input); + uint32_t outputaddr = (uint32_t)output; + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_DES_ECB, CAU_SWAPPING_8BIT); + + /* key initialisation */ + key_initpara.key_1_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_1_low = __REV(*(uint32_t *)(keyaddr)); + cau_key_init(&key_initpara); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* enable the CAU peripheral */ + cau_enable(); + /* DES calculate process */ + ret = cau_des_calculate((uint8_t *)inputaddr, cau_parameter->in_length, (uint8_t *)outputaddr); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief encrypt and decrypt using DES in CBC mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key, 8 bytes + iv: initialization vector, 8 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 8 bytes + \param[out] output: pointer to the output structure + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_des_cbc(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + cau_iv_parameter_struct iv_initpara; + uint32_t keyaddr = (uint32_t)(cau_parameter->key); + uint32_t inputaddr = (uint32_t)(cau_parameter->input); + uint32_t outputaddr = (uint32_t)output; + uint32_t ivaddr = (uint32_t)(cau_parameter->iv); + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_DES_CBC, CAU_SWAPPING_8BIT); + + /* key initialisation */ + key_initpara.key_1_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_1_low = __REV(*(uint32_t *)(keyaddr)); + cau_key_init(&key_initpara); + + /* vectors initialization */ + iv_initpara.iv_0_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_0_low = __REV(*(uint32_t *)(ivaddr)); + cau_iv_init(&iv_initpara); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + + /* enable the CAU peripheral */ + cau_enable(); + /* DES calculate process */ + ret = cau_des_calculate((uint8_t *)inputaddr, cau_parameter->in_length, (uint8_t *)outputaddr); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief DES calculate process + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer in bytes, must be a multiple of 8 bytes + \param[in] output: pointer to the returned buffer + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +static ErrStatus cau_des_calculate(uint8_t *input, uint32_t in_length, uint8_t *output) +{ + uint32_t inputaddr = (uint32_t)input; + uint32_t outputaddr = (uint32_t)output; + uint32_t i = 0U; + __IO uint32_t counter = 0U; + uint32_t busystatus = 0U; + + /* the clock is not enabled or there is no embeded CAU peripheral */ + if(DISABLE == cau_enable_state_get()) { + return ERROR; + } + + for(i = 0U; i < in_length; i += 8U) { + /* write data to the IN FIFO */ + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + + /* wait until the complete message has been processed */ + counter = 0U; + do { + busystatus = cau_flag_get(CAU_FLAG_BUSY); + counter++; + } while((DESBUSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus) { + return ERROR; + } else { + /* read the output block from the output FIFO */ + *(uint32_t *)(outputaddr) = cau_data_read(); + outputaddr += 4U; + *(uint32_t *)(outputaddr) = cau_data_read(); + outputaddr += 4U; + } + } + + return SUCCESS; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_tdes.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_tdes.c new file mode 100644 index 0000000..ffd5931 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_cau_tdes.c @@ -0,0 +1,198 @@ +/*! + \file gd32f5xx_cau_tdes.c + \brief CAU TDES driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_cau.h" + +#define TDESBSY_TIMEOUT ((uint32_t)0x00010000U) + +/* TDES calculate process */ +static ErrStatus cau_tdes_calculate(uint8_t *input, uint32_t in_length, uint8_t *output); + +/*! + \brief encrypt and decrypt using TDES in ECB mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key, 24 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 8 bytes + \param[out] output: pointer to the output structure + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_tdes_ecb(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + uint32_t keyaddr = (uint32_t)(cau_parameter->key); + uint32_t inputaddr = (uint32_t)(cau_parameter->input); + uint32_t outputaddr = (uint32_t)output; + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_TDES_ECB, CAU_SWAPPING_8BIT); + + /* key initialization */ + key_initpara.key_1_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_1_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_2_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_2_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_3_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_3_low = __REV(*(uint32_t *)(keyaddr)); + cau_key_init(&key_initpara); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + + /* enable the CAU peripheral */ + cau_enable(); + /* TDES calculate process */ + ret = cau_tdes_calculate((uint8_t *)inputaddr, cau_parameter->in_length, (uint8_t *)outputaddr); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief encrypt and decrypt using TDES in CBC mode + \param[in] cau_parameter: pointer to the input structure + alg_dir: algorithm direction + CAU_ENCRYPT, CAU_DECRYPT + key: key, 24 bytes + iv: initialization vector, 8 bytes + input: input data + in_length: input data length in bytes, must be a multiple of 8 bytes + \param[out] output: pointer to the output structure + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus cau_tdes_cbc(cau_parameter_struct *cau_parameter, uint8_t *output) +{ + ErrStatus ret = ERROR; + cau_key_parameter_struct key_initpara; + cau_iv_parameter_struct iv_initpara; + uint32_t keyaddr = (uint32_t)(cau_parameter->key); + uint32_t inputaddr = (uint32_t)(cau_parameter->input); + uint32_t outputaddr = (uint32_t)output; + uint32_t ivaddr = (uint32_t)(cau_parameter->iv); + + /* key structure initialization */ + cau_key_struct_para_init(&key_initpara); + /* initialize the CAU peripheral */ + cau_init(cau_parameter->alg_dir, CAU_MODE_TDES_CBC, CAU_SWAPPING_8BIT); + + /* key initialization */ + key_initpara.key_1_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_1_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_2_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_2_low = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_3_high = __REV(*(uint32_t *)(keyaddr)); + keyaddr += 4U; + key_initpara.key_3_low = __REV(*(uint32_t *)(keyaddr)); + cau_key_init(&key_initpara); + + /* vectors initialization */ + iv_initpara.iv_0_high = __REV(*(uint32_t *)(ivaddr)); + ivaddr += 4U; + iv_initpara.iv_0_low = __REV(*(uint32_t *)(ivaddr)); + cau_iv_init(&iv_initpara); + + /* flush the IN and OUT FIFOs */ + cau_fifo_flush(); + /* enable the CAU peripheral */ + cau_enable(); + /* TDES calculate process */ + ret = cau_tdes_calculate((uint8_t *)inputaddr, cau_parameter->in_length, (uint8_t *)outputaddr); + /* disable the CAU peripheral */ + cau_disable(); + + return ret; +} + +/*! + \brief TDES calculate process + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer in bytes, must be a multiple of 8 bytes + \param[out] output: pointer to the returned buffer + \retval ErrStatus: SUCCESS or ERROR +*/ +static ErrStatus cau_tdes_calculate(uint8_t *input, uint32_t in_length, uint8_t *output) +{ + uint32_t inputaddr = (uint32_t)input; + uint32_t outputaddr = (uint32_t)output; + uint32_t i = 0U; + __IO uint32_t counter = 0U; + uint32_t busystatus = 0U; + + /* the clock is not enabled or there is no embeded CAU peripheral */ + if(DISABLE == cau_enable_state_get()) { + return ERROR; + } + + for(i = 0U; i < in_length; i += 8U) { + /* write data to the IN FIFO */ + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + cau_data_write(*(uint32_t *)(inputaddr)); + inputaddr += 4U; + + /* wait until the complete message has been processed */ + counter = 0U; + do { + busystatus = cau_flag_get(CAU_FLAG_BUSY); + counter++; + } while((TDESBSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus) { + return ERROR; + } else { + /* read the output block from the output FIFO */ + *(uint32_t *)(outputaddr) = cau_data_read(); + outputaddr += 4U; + *(uint32_t *)(outputaddr) = cau_data_read(); + outputaddr += 4U; + } + } + + return SUCCESS; +} \ No newline at end of file diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_crc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_crc.c new file mode 100644 index 0000000..e0f57b3 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_crc.c @@ -0,0 +1,127 @@ +/*! + \file gd32f5xx_crc.c + \brief CRC driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_crc.h" + +#define CRC_DATA_RESET_VALUE ((uint32_t)0xFFFFFFFFU) +#define CRC_FDATA_RESET_VALUE ((uint32_t)0x00000000U) + +/*! + \brief deinit CRC calculation unit + \param[in] none + \param[out] none + \retval none +*/ +void crc_deinit(void) +{ + CRC_DATA = CRC_DATA_RESET_VALUE; + CRC_FDATA = CRC_FDATA_RESET_VALUE; + CRC_CTL = (uint32_t)CRC_CTL_RST; +} + +/*! + \brief reset data register(CRC_DATA) to the value of 0xFFFFFFFF + \param[in] none + \param[out] none + \retval none +*/ +void crc_data_register_reset(void) +{ + CRC_CTL |= (uint32_t)CRC_CTL_RST; +} + +/*! + \brief read the value of the data register + \param[in] none + \param[out] none + \retval 32-bit value of the data register,0-0xFFFFFFFF +*/ +uint32_t crc_data_register_read(void) +{ + uint32_t data; + data = CRC_DATA; + return (data); +} + +/*! + \brief read the value of the free data register + \param[in] none + \param[out] none + \retval 8-bit value of the free data register,0-0xFF +*/ +uint8_t crc_free_data_register_read(void) +{ + uint8_t fdata; + fdata = (uint8_t)CRC_FDATA; + return (fdata); +} + +/*! + \brief write data to the free data register + \param[in] free_data: specified 8-bit data + \param[out] none + \retval none +*/ +void crc_free_data_register_write(uint8_t free_data) +{ + CRC_FDATA = (uint32_t)free_data; +} + +/*! + \brief calculate the CRC value of a 32-bit data + \param[in] sdata: specified 32-bit data + \param[out] none + \retval 32-bit value calculated by CRC,0-0xFFFFFFFF +*/ +uint32_t crc_single_data_calculate(uint32_t sdata) +{ + CRC_DATA = sdata; + return (CRC_DATA); +} + +/*! + \brief calculate the CRC value of an array of 32-bit values + \param[in] array: pointer to an array of 32-bit values + \param[in] size: size of the array + \param[out] none + \retval 32-bit value calculated by CRC,0-0xFFFFFFFF +*/ +uint32_t crc_block_data_calculate(uint32_t array[], uint32_t size) +{ + uint32_t index; + for(index = 0U; index < size; index++) { + CRC_DATA = array[index]; + } + return (CRC_DATA); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_ctc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_ctc.c new file mode 100644 index 0000000..d9f891d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_ctc.c @@ -0,0 +1,388 @@ +/*! + \file gd32f5xx_ctc.c + \brief CTC driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_ctc.h" + +#define CTC_FLAG_MASK ((uint32_t)0x00000700U) + +/* CTC register bit offset */ +#define CTC_TRIMVALUE_OFFSET ((uint32_t)8U) +#define CTC_TRIM_VALUE_OFFSET ((uint32_t)8U) +#define CTC_REFCAP_OFFSET ((uint32_t)16U) +#define CTC_LIMIT_VALUE_OFFSET ((uint32_t)16U) + +/*! + \brief reset CTC clock trim controller + \param[in] none + \param[out] none + \retval none +*/ +void ctc_deinit(void) +{ + /* reset CTC */ + rcu_periph_reset_enable(RCU_CTCRST); + rcu_periph_reset_disable(RCU_CTCRST); +} + +/*! + \brief enable CTC trim counter + \param[in] none + \param[out] none + \retval none +*/ +void ctc_counter_enable(void) +{ + CTC_CTL0 |= (uint32_t)CTC_CTL0_CNTEN; +} + +/*! + \brief disable CTC trim counter + \param[in] none + \param[out] none + \retval none +*/ +void ctc_counter_disable(void) +{ + CTC_CTL0 &= (uint32_t)(~CTC_CTL0_CNTEN); +} + +/*! + \brief configure the IRC48M trim value + \param[in] ctc_trim_value: 8-bit IRC48M trim value + \arg 0x00 - 0x3F + \param[out] none + \retval none +*/ +void ctc_irc48m_trim_value_config(uint8_t trim_value) +{ + /* clear TRIMVALUE bits */ + CTC_CTL0 &= (~(uint32_t)CTC_CTL0_TRIMVALUE); + /* set TRIMVALUE bits */ + CTC_CTL0 |= ((uint32_t)trim_value << CTC_TRIM_VALUE_OFFSET); +} + +/*! + \brief generate software reference source sync pulse + \param[in] none + \param[out] none + \retval none +*/ +void ctc_software_refsource_pulse_generate(void) +{ + CTC_CTL0 |= (uint32_t)CTC_CTL0_SWREFPUL; +} + +/*! + \brief configure hardware automatically trim mode + \param[in] hardmode: + only one parameter can be selected which is shown as below: + \arg CTC_HARDWARE_TRIM_MODE_ENABLE: hardware automatically trim mode enable + \arg CTC_HARDWARE_TRIM_MODE_DISABLE: hardware automatically trim mode disable + \param[out] none + \retval none +*/ +void ctc_hardware_trim_mode_config(uint32_t hardmode) +{ + CTC_CTL0 &= (uint32_t)(~CTC_CTL0_AUTOTRIM); + CTC_CTL0 |= (uint32_t)hardmode; +} + +/*! + \brief configure reference signal source polarity + \param[in] polarity: + only one parameter can be selected which is shown as below: + \arg CTC_REFSOURCE_POLARITY_FALLING: reference signal source polarity is falling edge + \arg CTC_REFSOURCE_POLARITY_RISING: reference signal source polarity is rising edge + \param[out] none + \retval none +*/ +void ctc_refsource_polarity_config(uint32_t polarity) +{ + CTC_CTL1 &= (uint32_t)(~CTC_CTL1_REFPOL); + CTC_CTL1 |= (uint32_t)polarity; +} + +/*! + \brief select reference signal source + \param[in] refs: + only one parameter can be selected which is shown as below: + \arg CTC_REFSOURCE_GPIO: GPIO is selected + \arg CTC_REFSOURCE_LXTAL: LXTAL is selected + \param[out] none + \retval none +*/ +void ctc_refsource_signal_select(uint32_t refs) +{ + CTC_CTL1 &= (uint32_t)(~CTC_CTL1_REFSEL); + CTC_CTL1 |= (uint32_t)refs; +} + +/*! + \brief configure reference signal source prescaler + \param[in] prescaler: + only one parameter can be selected which is shown as below: + \arg CTC_REFSOURCE_PSC_OFF: reference signal not divided + \arg CTC_REFSOURCE_PSC_DIV2: reference signal divided by 2 + \arg CTC_REFSOURCE_PSC_DIV4: reference signal divided by 4 + \arg CTC_REFSOURCE_PSC_DIV8: reference signal divided by 8 + \arg CTC_REFSOURCE_PSC_DIV16: reference signal divided by 16 + \arg CTC_REFSOURCE_PSC_DIV32: reference signal divided by 32 + \arg CTC_REFSOURCE_PSC_DIV64: reference signal divided by 64 + \arg CTC_REFSOURCE_PSC_DIV128: reference signal divided by 128 + \param[out] none + \retval none +*/ +void ctc_refsource_prescaler_config(uint32_t prescaler) +{ + CTC_CTL1 &= (uint32_t)(~CTC_CTL1_REFPSC); + CTC_CTL1 |= (uint32_t)prescaler; +} + +/*! + \brief configure clock trim base limit value + \param[in] limit_value: 8-bit clock trim base limit value + \arg 0x00 - 0xFF + \param[out] none + \retval none +*/ +void ctc_clock_limit_value_config(uint8_t limit_value) +{ + CTC_CTL1 &= (uint32_t)(~CTC_CTL1_CKLIM); + CTC_CTL1 |= (uint32_t)((uint32_t)limit_value << CTC_LIMIT_VALUE_OFFSET); +} + +/*! + \brief configure CTC counter reload value + \param[in] reload_value: 16-bit CTC counter reload value + \arg 0x0000 - 0xFFFF + \param[out] none + \retval none +*/ +void ctc_counter_reload_value_config(uint16_t reload_value) +{ + CTC_CTL1 &= (uint32_t)(~CTC_CTL1_RLVALUE); + CTC_CTL1 |= (uint32_t)reload_value; +} + +/*! + \brief read CTC counter capture value when reference sync pulse occurred + \param[in] none + \param[out] none + \retval the 16-bit CTC counter capture value +*/ +uint16_t ctc_counter_capture_value_read(void) +{ + uint16_t capture_value = 0U; + capture_value = (uint16_t)((CTC_STAT & CTC_STAT_REFCAP) >> CTC_REFCAP_OFFSET); + return (capture_value); +} + +/*! + \brief read CTC trim counter direction when reference sync pulse occurred + \param[in] none + \param[out] none + \retval FlagStatus: SET or RESET + \arg SET: CTC trim counter direction is down-counting + \arg RESET: CTC trim counter direction is up-counting +*/ +FlagStatus ctc_counter_direction_read(void) +{ + if(RESET != (CTC_STAT & CTC_STAT_REFDIR)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief read CTC counter reload value + \param[in] none + \param[out] none + \retval the 16-bit CTC counter reload value +*/ +uint16_t ctc_counter_reload_value_read(void) +{ + uint16_t reload_value = 0U; + reload_value = (uint16_t)(CTC_CTL1 & CTC_CTL1_RLVALUE); + return (reload_value); +} + +/*! + \brief read the IRC48M trim value + \param[in] none + \param[out] none + \retval the 8-bit IRC48M trim value +*/ +uint8_t ctc_irc48m_trim_value_read(void) +{ + uint8_t trim_value = 0U; + trim_value = (uint8_t)((CTC_CTL0 & CTC_CTL0_TRIMVALUE) >> CTC_TRIMVALUE_OFFSET); + return (trim_value); +} + +/*! + \brief enable the CTC interrupt + \param[in] interrupt: CTC interrupt enable + one or more parameters can be selected which are shown as below: + \arg CTC_INT_CKOK: clock trim OK interrupt enable + \arg CTC_INT_CKWARN: clock trim warning interrupt enable + \arg CTC_INT_ERR: error interrupt enable + \arg CTC_INT_EREF: expect reference interrupt enable + \param[out] none + \retval none +*/ +void ctc_interrupt_enable(uint32_t interrupt) +{ + CTC_CTL0 |= (uint32_t)interrupt; +} + +/*! + \brief disable the CTC interrupt + \param[in] interrupt: CTC interrupt enable source + one or more parameters can be selected which are shown as below: + \arg CTC_INT_CKOK: clock trim OK interrupt enable + \arg CTC_INT_CKWARN: clock trim warning interrupt enable + \arg CTC_INT_ERR: error interrupt enable + \arg CTC_INT_EREF: expect reference interrupt enable + \param[out] none + \retval none +*/ +void ctc_interrupt_disable(uint32_t interrupt) +{ + CTC_CTL0 &= (uint32_t)(~interrupt); +} + +/*! + \brief get CTC interrupt flag + \param[in] int_flag: the CTC interrupt flag + only one parameter can be selected which is shown as below: + \arg CTC_INT_FLAG_CKOK: clock trim OK interrupt + \arg CTC_INT_FLAG_CKWARN: clock trim warning interrupt + \arg CTC_INT_FLAG_ERR: error interrupt + \arg CTC_INT_FLAG_EREF: expect reference interrupt + \arg CTC_INT_FLAG_CKERR: clock trim error bit interrupt + \arg CTC_INT_FLAG_REFMISS: reference sync pulse miss interrupt + \arg CTC_INT_FLAG_TRIMERR: trim value error interrupt + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus ctc_interrupt_flag_get(uint32_t int_flag) +{ + uint32_t interrupt_flag = 0U, intenable = 0U; + + /* check whether the interrupt is enabled */ + if(RESET != (int_flag & CTC_FLAG_MASK)) { + intenable = CTC_CTL0 & CTC_CTL0_ERRIE; + } else { + intenable = CTC_CTL0 & int_flag; + } + + /* get interrupt flag status */ + interrupt_flag = CTC_STAT & int_flag; + + if(interrupt_flag && intenable) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear CTC interrupt flag + \param[in] int_flag: the CTC interrupt flag + only one parameter can be selected which is shown as below: + \arg CTC_INT_FLAG_CKOK: clock trim OK interrupt + \arg CTC_INT_FLAG_CKWARN: clock trim warning interrupt + \arg CTC_INT_FLAG_ERR: error interrupt + \arg CTC_INT_FLAG_EREF: expect reference interrupt + \arg CTC_INT_FLAG_CKERR: clock trim error bit interrupt + \arg CTC_INT_FLAG_REFMISS: reference sync pulse miss interrupt + \arg CTC_INT_FLAG_TRIMERR: trim value error interrupt + \param[out] none + \retval none +*/ +void ctc_interrupt_flag_clear(uint32_t int_flag) +{ + if(RESET != (int_flag & CTC_FLAG_MASK)) { + CTC_INTC |= CTC_INTC_ERRIC; + } else { + CTC_INTC |= int_flag; + } +} + +/*! + \brief get CTC flag + \param[in] flag: the CTC flag + only one parameter can be selected which is shown as below: + \arg CTC_FLAG_CKOK: clock trim OK flag + \arg CTC_FLAG_CKWARN: clock trim warning flag + \arg CTC_FLAG_ERR: error flag + \arg CTC_FLAG_EREF: expect reference flag + \arg CTC_FLAG_CKERR: clock trim error bit + \arg CTC_FLAG_REFMISS: reference sync pulse miss + \arg CTC_FLAG_TRIMERR: trim value error bit + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus ctc_flag_get(uint32_t flag) +{ + if(RESET != (CTC_STAT & flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear CTC flag + \param[in] flag: the CTC flag + only one parameter can be selected which is shown as below: + \arg CTC_FLAG_CKOK: clock trim OK flag + \arg CTC_FLAG_CKWARN: clock trim warning flag + \arg CTC_FLAG_ERR: error flag + \arg CTC_FLAG_EREF: expect reference flag + \arg CTC_FLAG_CKERR: clock trim error bit + \arg CTC_FLAG_REFMISS: reference sync pulse miss + \arg CTC_FLAG_TRIMERR: trim value error bit + \param[out] none + \retval none +*/ +void ctc_flag_clear(uint32_t flag) +{ + if(RESET != (flag & CTC_FLAG_MASK)) { + CTC_INTC |= CTC_INTC_ERRIC; + } else { + CTC_INTC |= flag; + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dac.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dac.c new file mode 100644 index 0000000..e636b01 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dac.c @@ -0,0 +1,679 @@ +/*! + \file gd32f5xx_dac.c + \brief DAC driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_dac.h" + +/* DAC register bit offset */ +#define OUT1_REG_OFFSET ((uint32_t)0x00000010U) +#define DH_12BIT_OFFSET ((uint32_t)0x00000010U) +#define DH_8BIT_OFFSET ((uint32_t)0x00000008U) + +#define DAC_STAT_FLAG_MASK0 (DAC_FLAG_DDUDR0 | DAC_FLAG_DDUDR1) +#define DAC_INT_EN_MASK0 (DAC_INT_DDUDR0 | DAC_INT_DDUDR1) +#define DAC_INT_FLAG_MASK0 (DAC_INT_FLAG_DDUDR0 | DAC_INT_FLAG_DDUDR1) + +/*! + \brief deinitialize DAC + \param[in] dac_periph: DACx(x=0) + \param[out] none + \retval none +*/ +void dac_deinit(uint32_t dac_periph) +{ + switch(dac_periph){ + case DAC0: + /* reset DAC0 */ + rcu_periph_reset_enable(RCU_DACRST); + rcu_periph_reset_disable(RCU_DACRST); + break; + default: + break; + } +} + +/*! + \brief enable DAC + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval none +*/ +void dac_enable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_CTL0(dac_periph) |= (uint32_t)DAC_CTL0_DEN0; + }else if(DAC_OUT1 == dac_out){ + DAC_CTL0(dac_periph) |= (uint32_t)DAC_CTL0_DEN1; + }else{ + /* illegal parameters */ + } +} + +/*! + \brief disable DAC + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval none +*/ +void dac_disable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DEN0); + }else if(DAC_OUT1 == dac_out){ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DEN1); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief enable DAC DMA function + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval none +*/ +void dac_dma_enable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_CTL0(dac_periph) |= (uint32_t)DAC_CTL0_DDMAEN0; + }else if(DAC_OUT1 == dac_out){ + DAC_CTL0(dac_periph) |= (uint32_t)DAC_CTL0_DDMAEN1; + }else{ + /* illegal parameters */ + } +} + +/*! + \brief disable DAC DMA function + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval none +*/ +void dac_dma_disable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DDMAEN0); + }else if(DAC_OUT1 == dac_out){ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DDMAEN1); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief enable DAC output buffer + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval none +*/ +void dac_output_buffer_enable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DBOFF0); + }else if(DAC_OUT1 == dac_out){ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DBOFF1); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief disable DAC output buffer + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval none +*/ +void dac_output_buffer_disable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_CTL0(dac_periph) |= (uint32_t)DAC_CTL0_DBOFF0; + }else if(DAC_OUT1 == dac_out){ + DAC_CTL0(dac_periph) |= (uint32_t)DAC_CTL0_DBOFF1; + }else{ + /* illegal parameters */ + } +} + +/*! + \brief get DAC output value + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval DAC output data: 0~4095 +*/ +uint16_t dac_output_value_get(uint32_t dac_periph, uint8_t dac_out) +{ + uint16_t data = 0U; + + if(DAC_OUT0 == dac_out){ + /* store the DACx_OUT0 output value */ + data = (uint16_t)DAC_OUT0_DO(dac_periph); + }else if(DAC_OUT1 == dac_out){ + /* store the DACx_OUT1 output value */ + data = (uint16_t)DAC_OUT1_DO(dac_periph); + }else{ + /* illegal parameters */ + } + + return data; +} + +/*! + \brief set DAC data holding register value + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[in] dac_align: DAC data alignment mode + only one parameter can be selected which is shown as below: + \arg DAC_ALIGN_12B_R: 12-bit right-aligned data + \arg DAC_ALIGN_12B_L: 12-bit left-aligned data + \arg DAC_ALIGN_8B_R: 8-bit right-aligned data + \param[in] data: data to be loaded(0~4095) + \param[out] none + \retval none +*/ +void dac_data_set(uint32_t dac_periph, uint8_t dac_out, uint32_t dac_align, uint16_t data) +{ + /* DAC_OUT0 data alignment */ + if(DAC_OUT0 == dac_out){ + switch(dac_align){ + /* 12-bit right-aligned data */ + case DAC_ALIGN_12B_R: + DAC_OUT0_R12DH(dac_periph) = data; + break; + /* 12-bit left-aligned data */ + case DAC_ALIGN_12B_L: + DAC_OUT0_L12DH(dac_periph) = data; + break; + /* 8-bit right-aligned data */ + case DAC_ALIGN_8B_R: + DAC_OUT0_R8DH(dac_periph) = data; + break; + default: + break; + } + }else if(DAC_OUT1 == dac_out){ + /* DAC_OUT1 data alignment */ + switch(dac_align){ + /* 12-bit right-aligned data */ + case DAC_ALIGN_12B_R: + DAC_OUT1_R12DH(dac_periph) = data; + break; + /* 12-bit left-aligned data */ + case DAC_ALIGN_12B_L: + DAC_OUT1_L12DH(dac_periph) = data; + break; + /* 8-bit right-aligned data */ + case DAC_ALIGN_8B_R: + DAC_OUT1_R8DH(dac_periph) = data; + break; + default: + break; + } + }else{ + /* illegal parameters */ + } +} + +/*! + \brief enable DAC trigger + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval none +*/ +void dac_trigger_enable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_CTL0(dac_periph) |= (uint32_t)DAC_CTL0_DTEN0; + }else if(DAC_OUT1 == dac_out){ + DAC_CTL0(dac_periph) |= (uint32_t)DAC_CTL0_DTEN1; + }else{ + /* illegal parameters */ + } +} + +/*! + \brief disable DAC trigger + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[out] none + \retval none +*/ +void dac_trigger_disable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DTEN0); + }else if(DAC_OUT1 == dac_out){ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DTEN1); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief configure DAC trigger source + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[in] triggersource: external trigger of DAC + only one parameter can be selected which is shown as below: + \arg DAC_TRIGGER_T5_TRGO: TIMER5 TRGO + \arg DAC_TRIGGER_T7_TRGO: TIMER7 TRGO + \arg DAC_TRIGGER_T6_TRGO: TIMER6 TRGO + \arg DAC_TRIGGER_T4_TRGO: TIMER4 TRGO + \arg DAC_TRIGGER_T1_TRGO: TIMER1 TRGO + \arg DAC_TRIGGER_T3_TRGO: TIMER3 TRGO + \arg DAC_TRIGGER_EXTI_9: EXTI interrupt line9 event + \arg DAC_TRIGGER_SOFTWARE: software trigger + \param[out] none + \retval none +*/ +void dac_trigger_source_config(uint32_t dac_periph, uint8_t dac_out, uint32_t triggersource) +{ + if(DAC_OUT0 == dac_out){ + /* configure DACx_OUT0 trigger source */ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DTSEL0); + DAC_CTL0(dac_periph) |= triggersource; + }else if(DAC_OUT1 == dac_out){ + /* configure DACx_OUT1 trigger source */ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DTSEL1); + DAC_CTL0(dac_periph) |= (triggersource << OUT1_REG_OFFSET); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief enable DAC software trigger + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \retval none +*/ +void dac_software_trigger_enable(uint32_t dac_periph, uint8_t dac_out) +{ + if(DAC_OUT0 == dac_out){ + DAC_SWT(dac_periph) |= (uint32_t)DAC_SWT_SWTR0; + }else if(DAC_OUT1 == dac_out){ + DAC_SWT(dac_periph) |= (uint32_t)DAC_SWT_SWTR1; + }else{ + /* illegal parameters */ + } +} + +/*! + \brief configure DAC wave mode + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[in] wave_mode: DAC wave mode + only one parameter can be selected which is shown as below: + \arg DAC_WAVE_DISABLE: wave mode disable + \arg DAC_WAVE_MODE_LFSR: LFSR noise mode + \arg DAC_WAVE_MODE_TRIANGLE: triangle noise mode + \param[out] none + \retval none +*/ +void dac_wave_mode_config(uint32_t dac_periph, uint8_t dac_out, uint32_t wave_mode) +{ + if(DAC_OUT0 == dac_out){ + /* configure DACx_OUT0 wave mode */ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DWM0); + DAC_CTL0(dac_periph) |= wave_mode; + }else if(DAC_OUT1 == dac_out){ + /* configure DACx_OUT1 wave mode */ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DWM1); + DAC_CTL0(dac_periph) |= (wave_mode << OUT1_REG_OFFSET); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief configure DAC LFSR noise mode + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[in] unmask_bits: LFSR noise unmask bits + only one parameter can be selected which is shown as below: + \arg DAC_LFSR_BIT0: unmask the LFSR bit0 + \arg DAC_LFSR_BITS1_0: unmask the LFSR bits[1:0] + \arg DAC_LFSR_BITS2_0: unmask the LFSR bits[2:0] + \arg DAC_LFSR_BITS3_0: unmask the LFSR bits[3:0] + \arg DAC_LFSR_BITS4_0: unmask the LFSR bits[4:0] + \arg DAC_LFSR_BITS5_0: unmask the LFSR bits[5:0] + \arg DAC_LFSR_BITS6_0: unmask the LFSR bits[6:0] + \arg DAC_LFSR_BITS7_0: unmask the LFSR bits[7:0] + \arg DAC_LFSR_BITS8_0: unmask the LFSR bits[8:0] + \arg DAC_LFSR_BITS9_0: unmask the LFSR bits[9:0] + \arg DAC_LFSR_BITS10_0: unmask the LFSR bits[10:0] + \arg DAC_LFSR_BITS11_0: unmask the LFSR bits[11:0] + \param[out] none + \retval none +*/ +void dac_lfsr_noise_config(uint32_t dac_periph, uint8_t dac_out, uint32_t unmask_bits) +{ + if(DAC_OUT0 == dac_out){ + /* configure DACx_OUT0 LFSR noise mode */ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DWBW0); + DAC_CTL0(dac_periph) |= unmask_bits; + }else if(DAC_OUT1 == dac_out){ + /* configure DACx_OUT1 LFSR noise mode */ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DWBW1); + DAC_CTL0(dac_periph) |= (unmask_bits << OUT1_REG_OFFSET); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief configure DAC triangle noise mode + \param[in] dac_periph: DACx(x=0) + \param[in] dac_out: DAC_OUTx(x=0,1) + \param[in] amplitude: the amplitude of the triangle + only one parameter can be selected which is shown as below: + \arg DAC_TRIANGLE_AMPLITUDE_1: triangle amplitude is 1 + \arg DAC_TRIANGLE_AMPLITUDE_3: triangle amplitude is 3 + \arg DAC_TRIANGLE_AMPLITUDE_7: triangle amplitude is 7 + \arg DAC_TRIANGLE_AMPLITUDE_15: triangle amplitude is 15 + \arg DAC_TRIANGLE_AMPLITUDE_31: triangle amplitude is 31 + \arg DAC_TRIANGLE_AMPLITUDE_63: triangle amplitude is 63 + \arg DAC_TRIANGLE_AMPLITUDE_127: triangle amplitude is 127 + \arg DAC_TRIANGLE_AMPLITUDE_255: triangle amplitude is 255 + \arg DAC_TRIANGLE_AMPLITUDE_511: triangle amplitude is 511 + \arg DAC_TRIANGLE_AMPLITUDE_1023: triangle amplitude is 1023 + \arg DAC_TRIANGLE_AMPLITUDE_2047: triangle amplitude is 2047 + \arg DAC_TRIANGLE_AMPLITUDE_4095: triangle amplitude is 4095 + \param[out] none + \retval none +*/ +void dac_triangle_noise_config(uint32_t dac_periph, uint8_t dac_out, uint32_t amplitude) +{ + if(DAC_OUT0 == dac_out){ + /* configure DACx_OUT0 triangle noise mode */ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DWBW0); + DAC_CTL0(dac_periph) |= amplitude; + }else if(DAC_OUT1 == dac_out){ + /* configure DACx_OUT1 triangle noise mode */ + DAC_CTL0(dac_periph) &= (uint32_t)(~DAC_CTL0_DWBW1); + DAC_CTL0(dac_periph) |= (amplitude << OUT1_REG_OFFSET); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief enable DAC concurrent mode + \param[in] dac_periph: DACx(x=0) + \param[out] none + \retval none +*/ +void dac_concurrent_enable(uint32_t dac_periph) +{ + uint32_t ctl = 0U; + + ctl = (uint32_t)(DAC_CTL0_DEN0 | DAC_CTL0_DEN1); + DAC_CTL0(dac_periph) |= (uint32_t)ctl; +} + +/*! + \brief disable DAC concurrent mode + \param[in] dac_periph: DACx(x=0) + \param[out] none + \retval none +*/ +void dac_concurrent_disable(uint32_t dac_periph) +{ + uint32_t ctl = 0U; + + ctl = (uint32_t)(DAC_CTL0_DEN0 | DAC_CTL0_DEN1); + DAC_CTL0(dac_periph) &= (uint32_t)(~ctl); +} + +/*! + \brief enable DAC concurrent software trigger + \param[in] dac_periph: DACx(x=0) + \param[out] none + \retval none +*/ +void dac_concurrent_software_trigger_enable(uint32_t dac_periph) +{ + uint32_t swt = 0U; + + swt = (uint32_t)(DAC_SWT_SWTR0 | DAC_SWT_SWTR1); + DAC_SWT(dac_periph) |= (uint32_t)swt; +} + +/*! + \brief enable DAC concurrent buffer function + \param[in] dac_periph: DACx(x=0) + \param[out] none + \retval none +*/ +void dac_concurrent_output_buffer_enable(uint32_t dac_periph) +{ + uint32_t ctl = 0U; + + ctl = (uint32_t)(DAC_CTL0_DBOFF0 | DAC_CTL0_DBOFF1); + DAC_CTL0(dac_periph) &= (uint32_t)(~ctl); +} + +/*! + \brief disable DAC concurrent buffer function + \param[in] dac_periph: DACx(x=0) + \param[out] none + \retval none +*/ +void dac_concurrent_output_buffer_disable(uint32_t dac_periph) +{ + uint32_t ctl = 0U; + + ctl = (uint32_t)(DAC_CTL0_DBOFF0 | DAC_CTL0_DBOFF1); + DAC_CTL0(dac_periph) |= (uint32_t)ctl; +} + +/*! + \brief set DAC concurrent mode data holding register value + \param[in] dac_periph: DACx(x=0) + \param[in] dac_align: DAC data alignment mode + only one parameter can be selected which is shown as below: + \arg DAC_ALIGN_12B_R: 12-bit right-aligned data + \arg DAC_ALIGN_12B_L: 12-bit left-aligned data + \arg DAC_ALIGN_8B_R: 8-bit right-aligned data + \param[in] data0: data to be loaded(0~4095) + \param[in] data1: data to be loaded(0~4095) + \param[out] none + \retval none +*/ +void dac_concurrent_data_set(uint32_t dac_periph, uint32_t dac_align, uint16_t data0, uint16_t data1) +{ + uint32_t data = 0U; + + switch(dac_align){ + /* 12-bit right-aligned data */ + case DAC_ALIGN_12B_R: + data = (uint32_t)(((uint32_t)data1 << DH_12BIT_OFFSET) | data0); + DACC_R12DH(dac_periph) = (uint32_t)data; + break; + /* 12-bit left-aligned data */ + case DAC_ALIGN_12B_L: + data = (uint32_t)(((uint32_t)data1 << DH_12BIT_OFFSET) | data0); + DACC_L12DH(dac_periph) = (uint32_t)data; + break; + /* 8-bit right-aligned data */ + case DAC_ALIGN_8B_R: + data = (uint32_t)(((uint32_t)data1 << DH_8BIT_OFFSET) | data0); + DACC_R8DH(dac_periph) = (uint32_t)data; + break; + default: + break; + } +} + +/*! + \brief get the DAC flag + \param[in] dac_periph: DACx(x=0) + \param[in] flag: the DAC status flags, only one parameter can be selected which is shown + as below: + \arg DAC_FLAG_DDUDR0: DACx_OUT0 DMA underrun flag + \arg DAC_FLAG_DDUDR1: DACx_OUT1 DMA underrun flag + \param[out] none + \retval the state of DAC bit(SET or RESET) +*/ +FlagStatus dac_flag_get(uint32_t dac_periph, uint32_t flag) +{ + if(flag & DAC_STAT_FLAG_MASK0){ + /* check DAC_STAT0 flag */ + if(RESET != (DAC_STAT0(dac_periph) & flag)){ + return SET; + }else{ + return RESET; + } + }else{ + /* illegal parameters */ + return RESET; + } +} + +/*! + \brief clear the DAC flag + \param[in] dac_periph: DACx(x=0) + \param[in] flag: DAC flag + one or more parameter can be selected which are shown as below: + \arg DAC_FLAG_DDUDR0: DACx_OUT0 DMA underrun flag + \arg DAC_FLAG_DDUDR1: DACx_OUT1 DMA underrun flag + \param[out] none + \retval none +*/ +void dac_flag_clear(uint32_t dac_periph, uint32_t flag) +{ + if(flag & DAC_STAT_FLAG_MASK0){ + /* check DAC_STAT0 flag */ + DAC_STAT0(dac_periph) = (uint32_t)(flag & DAC_STAT_FLAG_MASK0); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief enable DAC interrupt(DAC DMA underrun interrupt) + \param[in] dac_periph: DACx(x=0) + \param[in] interrupt: the DAC interrupt + one or more parameter can be selected which are shown as below: + \arg DAC_INT_DDUDR0: DACx_OUT0 DMA underrun interrupt + \arg DAC_INT_DDUDR1: DACx_OUT1 DMA underrun interrupt + \param[out] none + \retval none +*/ +void dac_interrupt_enable(uint32_t dac_periph, uint32_t interrupt) +{ + if(interrupt & DAC_INT_EN_MASK0){ + /* enable underrun interrupt */ + DAC_CTL0(dac_periph) |= (uint32_t)(interrupt & DAC_INT_EN_MASK0); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief disable DAC interrupt(DAC DMA underrun interrupt) + \param[in] dac_periph: DACx(x=0) + \param[in] interrupt: the DAC interrupt + one and more parameter can be selected which are shown as below: + \arg DAC_INT_DDUDR0: DACx_OUT0 DMA underrun interrupt + \arg DAC_INT_DDUDR1: DACx_OUT1 DMA underrun interrupt + \param[out] none + \retval none +*/ +void dac_interrupt_disable(uint32_t dac_periph, uint32_t interrupt) +{ + if(interrupt & DAC_INT_EN_MASK0){ + /* disable underrun interrupt */ + DAC_CTL0(dac_periph) &= (uint32_t)(~(interrupt & DAC_INT_EN_MASK0)); + }else{ + /* illegal parameters */ + } +} + +/*! + \brief get the DAC interrupt flag(DAC DMA underrun interrupt flag) + \param[in] dac_periph: DACx(x=0) + \param[in] int_flag: DAC interrupt flag + only one parameter can be selected which is shown as below: + \arg DAC_INT_FLAG_DDUDR0: DACx_OUT0 DMA underrun interrupt flag + \arg DAC_INT_FLAG_DDUDR1: DACx_OUT1 DMA underrun interrupt flag + \param[out] none + \retval the state of DAC interrupt flag(SET or RESET) +*/ +FlagStatus dac_interrupt_flag_get(uint32_t dac_periph, uint32_t int_flag) +{ + uint32_t reg1 = 0U, reg2 = 0U; + + if(int_flag & DAC_INT_FLAG_MASK0){ + /* check underrun interrupt int_flag */ + reg1 = DAC_STAT0(dac_periph) & int_flag; + reg2 = DAC_CTL0(dac_periph) & int_flag; + }else{ + /* illegal parameters */ + } + + /*get DAC interrupt flag status */ + if((RESET != reg1) && (RESET != reg2)){ + return SET; + }else{ + return RESET; + } +} + +/*! + \brief clear the DAC interrupt flag(DAC DMA underrun interrupt flag) + \param[in] dac_periph: DACx(x=0) + \param[in] int_flag: DAC interrupt flag + one or more parameter can be selected which are shown as below: + \arg DAC_INT_FLAG_DDUDR0: DACx_OUT0 DMA underrun interrupt flag + \arg DAC_INT_FLAG_DDUDR1: DACx_OUT1 DMA underrun interrupt flag + \param[out] none + \retval none +*/ +void dac_interrupt_flag_clear(uint32_t dac_periph, uint32_t int_flag) +{ + /* clear underrun interrupt int_flag */ + if(int_flag & DAC_INT_FLAG_MASK0){ + DAC_STAT0(dac_periph) = (uint32_t)(int_flag & DAC_INT_FLAG_MASK0); + }else{ + /* illegal parameters */ + } +} + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dbg.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dbg.c new file mode 100644 index 0000000..ec13e85 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dbg.c @@ -0,0 +1,209 @@ +/*! + \file gd32f5xx_dbg.c + \brief DBG driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_dbg.h" + +#define DBG_RESET_VAL 0x00000000U +#define DBG_DEVICEID_SET(regval) (BITS(0,3) & ((uint32_t)(regval) << 0)) +/*! + \brief deinitialize the DBG + \param[in] none + \param[out] none + \retval none +*/ +void dbg_deinit(void) +{ + DBG_CTL0 = DBG_RESET_VAL; + DBG_CTL1 = DBG_RESET_VAL; + DBG_CTL2 = DBG_RESET_VAL; +} + +/*! + \brief read DBG_ID code register + \param[in] none + \param[out] none + \retval DBG_ID code +*/ +uint32_t dbg_id_get(void) +{ + return DBG_ID; +} + +/*! + \brief enable low power behavior when the mcu is in debug mode + \param[in] dbg_low_power: + this parameter can be any combination of the following values: + \arg DBG_LOW_POWER_SLEEP: keep debugger connection during sleep mode + \arg DBG_LOW_POWER_DEEPSLEEP: keep debugger connection during deepsleep mode + \arg DBG_LOW_POWER_STANDBY: keep debugger connection during standby mode + \param[out] none + \retval none +*/ +void dbg_low_power_enable(uint32_t dbg_low_power) +{ + DBG_CTL0 |= dbg_low_power; +} + +/*! + \brief disable low power behavior when the mcu is in debug mode + \param[in] dbg_low_power: + this parameter can be any combination of the following values: + \arg DBG_LOW_POWER_SLEEP: donot keep debugger connection during sleep mode + \arg DBG_LOW_POWER_DEEPSLEEP: donot keep debugger connection during deepsleep mode + \arg DBG_LOW_POWER_STANDBY: donot keep debugger connection during standby mode + \param[out] none + \retval none +*/ +void dbg_low_power_disable(uint32_t dbg_low_power) +{ + DBG_CTL0 &= ~dbg_low_power; +} + +/*! + \brief enable peripheral behavior when the mcu is in debug mode + \param[in] dbg_periph: dbg_periph_enum + only one parameter can be selected which is shown as below: + \arg DBG_TIMER1_HOLD: hold TIMER1 counter when core is halted + \arg DBG_TIMER2_HOLD: hold TIMER2 counter when core is halted + \arg DBG_TIMER3_HOLD: hold TIMER3 counter when core is halted + \arg DBG_TIMER4_HOLD: hold TIMER4 counter when core is halted + \arg DBG_TIMER5_HOLD: hold TIMER5 counter when core is halted + \arg DBG_TIMER6_HOLD: hold TIMER6 counter when core is halted + \arg DBG_TIMER11_HOLD: hold TIMER11 counter when core is halted + \arg DBG_TIMER12_HOLD: hold TIMER12 counter when core is halted + \arg DBG_TIMER13_HOLD: hold TIMER13 counter when core is halted + \arg DBG_RTC_HOLD: hold RTC calendar and wakeup counter when core is halted + \arg DBG_WWDGT_HOLD: debug WWDGT kept when core is halted + \arg DBG_FWDGT_HOLD: debug FWDGT kept when core is halted + \arg DBG_I2C3_HOLD: hold I2C3 smbus when core is halted + \arg DBG_I2C4_HOLD: hold I2C4 smbus when core is halted + \arg DBG_I2C5_HOLD: hold I2C5 smbus when core is halted + \arg DBG_I2C0_HOLD: hold I2C0 smbus when core is halted + \arg DBG_I2C1_HOLD: hold I2C1 smbus when core is halted + \arg DBG_I2C2_HOLD: hold I2C2 smbus when core is halted + \arg DBG_CAN0_HOLD: debug CAN0 kept when core is halted + \arg DBG_CAN1_HOLD: debug CAN1 kept when core is halted + \arg DBG_TIMER0_HOLD: hold TIMER0 counter when core is halted + \arg DBG_TIMER7_HOLD: hold TIMER7 counter when core is halted + \arg DBG_TIMER8_HOLD: hold TIMER8 counter when core is halted + \arg DBG_TIMER9_HOLD: hold TIMER9 counter when core is halted + \arg DBG_TIMER10_HOLD: hold TIMER10 counter when core is halted + \retval none +*/ +void dbg_periph_enable(dbg_periph_enum dbg_periph) +{ + DBG_REG_VAL(dbg_periph) |= BIT(DBG_BIT_POS(dbg_periph)); +} + +/*! + \brief disable peripheral behavior when the mcu is in debug mode + \param[in] dbg_periph: dbg_periph_enum + only one parameter can be selected which is shown as below: + \arg DBG_TIMER1_HOLD: hold TIMER1 counter when core is halted + \arg DBG_TIMER2_HOLD: hold TIMER2 counter when core is halted + \arg DBG_TIMER3_HOLD: hold TIMER3 counter when core is halted + \arg DBG_TIMER4_HOLD: hold TIMER4 counter when core is halted + \arg DBG_TIMER5_HOLD: hold TIMER5 counter when core is halted + \arg DBG_TIMER6_HOLD: hold TIMER6 counter when core is halted + \arg DBG_TIMER11_HOLD: hold TIMER11 counter when core is halted + \arg DBG_TIMER12_HOLD: hold TIMER12 counter when core is halted + \arg DBG_TIMER13_HOLD: hold TIMER13 counter when core is halted + \arg DBG_RTC_HOLD: hold RTC calendar and wakeup counter when core is halted + \arg DBG_WWDGT_HOLD: debug WWDGT kept when core is halted + \arg DBG_FWDGT_HOLD: debug FWDGT kept when core is halted + \arg DBG_I2C3_HOLD: hold I2C3 smbus when core is halted + \arg DBG_I2C4_HOLD: hold I2C4 smbus when core is halted + \arg DBG_I2C5_HOLD: hold I2C5 smbus when core is halted + \arg DBG_I2C0_HOLD: hold I2C0 smbus when core is halted + \arg DBG_I2C1_HOLD: hold I2C1 smbus when core is halted + \arg DBG_I2C2_HOLD: hold I2C2 smbus when core is halted + \arg DBG_CAN0_HOLD: debug CAN0 kept when core is halted + \arg DBG_CAN1_HOLD: debug CAN1 kept when core is halted + \arg DBG_TIMER0_HOLD: hold TIMER0 counter when core is halted + \arg DBG_TIMER7_HOLD: hold TIMER7 counter when core is halted + \arg DBG_TIMER8_HOLD: hold TIMER8 counter when core is halted + \arg DBG_TIMER9_HOLD: hold TIMER9 counter when core is halted + \arg DBG_TIMER10_HOLD: hold TIMER10 counter when core is halted + \param[out] none + \retval none +*/ +void dbg_periph_disable(dbg_periph_enum dbg_periph) +{ + DBG_REG_VAL(dbg_periph) &= ~BIT(DBG_BIT_POS(dbg_periph)); +} + +/*! + \brief enable trace pin assignment + \param[in] none + \param[out] none + \retval none +*/ +void dbg_trace_pin_enable(void) +{ + DBG_CTL0 |= DBG_CTL0_TRACE_IOEN; +} + +/*! + \brief disable trace pin assignment + \param[in] none + \param[out] none + \retval none +*/ +void dbg_trace_pin_disable(void) +{ + DBG_CTL0 &= ~DBG_CTL0_TRACE_IOEN; +} + + +/*! + \brief read DBG DEVICEID + \param[in] none + \param[out] none + \retval DBG DEVICEID +*/ +uint32_t dbg_deviceid_get(void) +{ + return DBG_CTL3; +} + +/*! + \brief write DBG DEVICEID + \param[in] deviceid: deviceid which connect to MCU instanceid + \param[out] none + \retval none +*/ +void dbg_deviceid_set(uint32_t deviceid) +{ + DBG_CTL3 = (uint32_t)DBG_DEVICEID_SET(deviceid); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dci.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dci.c new file mode 100644 index 0000000..ee7bd2c --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dci.c @@ -0,0 +1,343 @@ +/*! + \file gd32f5xx_dci.c + \brief DCI driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_dci.h" + +/*! + \brief DCI deinit + \param[in] none + \param[out] none + \retval none +*/ +void dci_deinit(void) +{ + rcu_periph_reset_enable(RCU_DCIRST); + rcu_periph_reset_disable(RCU_DCIRST); +} + +/*! + \brief initialize DCI registers + \param[in] dci_struct: DCI parameter initialization structure + members of the structure and the member values are shown as below: + capture_mode : DCI_CAPTURE_MODE_CONTINUOUS, DCI_CAPTURE_MODE_SNAPSHOT + colck_polarity : DCI_CK_POLARITY_FALLING, DCI_CK_POLARITY_RISING + hsync_polarity : DCI_HSYNC_POLARITY_LOW, DCI_HSYNC_POLARITY_HIGH + vsync_polarity : DCI_VSYNC_POLARITY_LOW, DCI_VSYNC_POLARITY_HIGH + frame_rate : DCI_FRAME_RATE_ALL, DCI_FRAME_RATE_1_2, DCI_FRAME_RATE_1_4 + interface_format: DCI_INTERFACE_FORMAT_8BITS, DCI_INTERFACE_FORMAT_10BITS, + DCI_INTERFACE_FORMAT_12BITS, DCI_INTERFACE_FORMAT_14BITS + \param[out] none + \retval none +*/ +void dci_init(dci_parameter_struct *dci_struct) +{ + uint32_t reg = 0U; + /* disable capture function and DCI */ + DCI_CTL &= ~(DCI_CTL_CAP | DCI_CTL_DCIEN); + /* configure DCI parameter */ + reg |= dci_struct->capture_mode; + reg |= dci_struct->clock_polarity; + reg |= dci_struct->hsync_polarity; + reg |= dci_struct->vsync_polarity; + reg |= dci_struct->frame_rate; + reg |= dci_struct->interface_format; + + DCI_CTL = reg; +} + +/*! + \brief enable DCI function + \param[in] none + \param[out] none + \retval none +*/ +void dci_enable(void) +{ + DCI_CTL |= DCI_CTL_DCIEN; +} + +/*! + \brief disable DCI function + \param[in] none + \param[out] none + \retval none +*/ +void dci_disable(void) +{ + DCI_CTL &= ~DCI_CTL_DCIEN; +} + +/*! + \brief enable DCI capture + \param[in] none + \param[out] none + \retval none +*/ +void dci_capture_enable(void) +{ + DCI_CTL |= DCI_CTL_CAP; +} + +/*! + \brief disable DCI capture + \param[in] none + \param[out] none + \retval none +*/ +void dci_capture_disable(void) +{ + DCI_CTL &= ~DCI_CTL_CAP; +} + +/*! + \brief enable DCI jpeg mode + \param[in] none + \param[out] none + \retval none +*/ +void dci_jpeg_enable(void) +{ + DCI_CTL |= DCI_CTL_JM; +} + +/*! + \brief disable DCI jpeg mode + \param[in] none + \param[out] none + \retval none +*/ +void dci_jpeg_disable(void) +{ + DCI_CTL &= ~DCI_CTL_JM; +} + +/*! + \brief enable cropping window function + \param[in] none + \param[out] none + \retval none +*/ +void dci_crop_window_enable(void) +{ + DCI_CTL |= DCI_CTL_WDEN; +} + +/*! + \brief disable cropping window function + \param[in] none + \param[out] none + \retval none +*/ +void dci_crop_window_disable(void) +{ + DCI_CTL &= ~DCI_CTL_WDEN; +} + +/*! + \brief configure DCI cropping window + \param[in] start_x: window horizontal start position + \param[in] start_y: window vertical start position + \param[in] size_width: window horizontal size + \param[in] size_height: window vertical size + \param[out] none + \retval none +*/ +void dci_crop_window_config(uint16_t start_x, uint16_t start_y, uint16_t size_width, uint16_t size_height) +{ + DCI_CWSPOS = ((uint32_t)start_x | ((uint32_t)start_y << 16)); + DCI_CWSZ = ((uint32_t)size_width | ((uint32_t)size_height << 16)); +} + +/*! + \brief enable embedded synchronous mode + \param[in] none + \param[out] none + \retval none +*/ +void dci_embedded_sync_enable(void) +{ + DCI_CTL |= DCI_CTL_ESM; +} + +/*! + \brief disable embedded synchronous mode + \param[in] none + \param[out] none + \retval none +*/ +void dci_embedded_sync_disable(void) +{ + DCI_CTL &= ~DCI_CTL_ESM; +} +/*! + \brief configure synchronous codes in embedded synchronous mode + \param[in] frame_start: frame start code in embedded synchronous mode + \param[in] line_start: line start code in embedded synchronous mode + \param[in] line_end: line end code in embedded synchronous mode + \param[in] frame_end: frame end code in embedded synchronous mode + \param[out] none + \retval none +*/ +void dci_sync_codes_config(uint8_t frame_start, uint8_t line_start, uint8_t line_end, uint8_t frame_end) +{ + DCI_SC = ((uint32_t)frame_start | ((uint32_t)line_start << 8) | ((uint32_t)line_end << 16) | ((uint32_t)frame_end << 24)); +} + +/*! + \brief configure synchronous codes unmask in embedded synchronous mode + \param[in] frame_start: frame start code unmask bits in embedded synchronous mode + \param[in] line_start: line start code unmask bits in embedded synchronous mode + \param[in] line_end: line end code unmask bits in embedded synchronous mode + \param[in] frame_end: frame end code unmask bits in embedded synchronous mode + \param[out] none + \retval none +*/ +void dci_sync_codes_unmask_config(uint8_t frame_start, uint8_t line_start, uint8_t line_end, uint8_t frame_end) +{ + DCI_SCUMSK = ((uint32_t)frame_start | ((uint32_t)line_start << 8) | ((uint32_t)line_end << 16) | ((uint32_t)frame_end << 24)); +} + +/*! + \brief read DCI data register + \param[in] none + \param[out] none + \retval data +*/ +uint32_t dci_data_read(void) +{ + return DCI_DATA; +} + +/*! + \brief get specified flag + \param[in] flag: + \arg DCI_FLAG_HS: HS line status + \arg DCI_FLAG_VS: VS line status + \arg DCI_FLAG_FV:FIFO valid + \arg DCI_FLAG_EF: end of frame flag + \arg DCI_FLAG_OVR: FIFO overrun flag + \arg DCI_FLAG_ESE: embedded synchronous error flag + \arg DCI_FLAG_VSYNC: vsync flag + \arg DCI_FLAG_EL: end of line flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus dci_flag_get(uint32_t flag) +{ + uint32_t stat = 0U; + + if(flag >> 31) { + /* get flag status from DCI_STAT1 register */ + stat = DCI_STAT1; + } else { + /* get flag status from DCI_STAT0 register */ + stat = DCI_STAT0; + } + + if(flag & stat) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief enable specified DCI interrupt + \param[in] interrupt: + \arg DCI_INT_EF: end of frame interrupt + \arg DCI_INT_OVR: FIFO overrun interrupt + \arg DCI_INT_ESE: embedded synchronous error interrupt + \arg DCI_INT_VSYNC: vsync interrupt + \arg DCI_INT_EL: end of line interrupt + \param[out] none + \retval none +*/ +void dci_interrupt_enable(uint32_t interrupt) +{ + DCI_INTEN |= interrupt; +} + +/*! + \brief disable specified DCI interrupt + \param[in] interrupt: + \arg DCI_INT_EF: end of frame interrupt + \arg DCI_INT_OVR: FIFO overrun interrupt + \arg DCI_INT_ESE: embedded synchronous error interrupt + \arg DCI_INT_VSYNC: vsync interrupt + \arg DCI_INT_EL: end of line interrupt + \param[out] none + \retval none +*/ +void dci_interrupt_disable(uint32_t interrupt) +{ + DCI_INTEN &= ~interrupt; +} + +/*! + \brief clear specified interrupt flag + \param[in] int_flag: + \arg DCI_INT_EF: end of frame interrupt + \arg DCI_INT_OVR: FIFO overrun interrupt + \arg DCI_INT_ESE: embedded synchronous error interrupt + \arg DCI_INT_VSYNC: vsync interrupt + \arg DCI_INT_EL: end of line interrupt + \param[out] none + \retval none +*/ +void dci_interrupt_flag_clear(uint32_t int_flag) +{ + DCI_INTC |= int_flag; +} + +/*! + \brief get specified interrupt flag + \param[in] int_flag: + \arg DCI_INT_FLAG_EF: end of frame interrupt flag + \arg DCI_INT_FLAG_OVR: FIFO overrun interrupt flag + \arg DCI_INT_FLAG_ESE: embedded synchronous error interrupt flag + \arg DCI_INT_FLAG_VSYNC: vsync interrupt flag + \arg DCI_INT_FLAG_EL: end of line interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus dci_interrupt_flag_get(uint32_t int_flag) +{ + if(RESET == (DCI_INTF & int_flag)) { + return RESET; + } else { + return SET; + } +} + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dma.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dma.c new file mode 100644 index 0000000..50c729a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_dma.c @@ -0,0 +1,902 @@ +/*! + \file gd32f5xx_dma.c + \brief DMA driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_dma.h" + +/* DMA register bit offset */ +#define CHXCTL_PERIEN_OFFSET ((uint32_t)25U) + +/*! + \brief deinitialize DMA a channel registers + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel is deinitialized + \arg DMA_CHx(x=0..7) + \param[out] none + \retval none +*/ +void dma_deinit(uint32_t dma_periph, dma_channel_enum channelx) +{ + /* disable DMA a channel */ + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_CHEN; + /* reset DMA channel registers */ + DMA_CHCTL(dma_periph, channelx) = DMA_CHCTL_RESET_VALUE; + DMA_CHCNT(dma_periph, channelx) = DMA_CHCNT_RESET_VALUE; + DMA_CHPADDR(dma_periph, channelx) = DMA_CHPADDR_RESET_VALUE; + DMA_CHM0ADDR(dma_periph, channelx) = DMA_CHMADDR_RESET_VALUE; + DMA_CHM1ADDR(dma_periph, channelx) = DMA_CHMADDR_RESET_VALUE; + DMA_CHFCTL(dma_periph, channelx) = DMA_CHFCTL_RESET_VALUE; + if(channelx < DMA_CH4) { + DMA_INTC0(dma_periph) |= DMA_FLAG_ADD(DMA_CHINTF_RESET_VALUE, channelx); + } else { + channelx -= (dma_channel_enum)4; + DMA_INTC1(dma_periph) |= DMA_FLAG_ADD(DMA_CHINTF_RESET_VALUE, channelx); + } +} + +/*! + \brief initialize the DMA single data mode parameters struct with the default values + \param[in] init_struct: the initialization data needed to initialize DMA channel + \param[out] none + \retval none +*/ +void dma_single_data_para_struct_init(dma_single_data_parameter_struct *init_struct) +{ + /* set the DMA struct with the default values */ + init_struct->periph_addr = 0U; + init_struct->periph_inc = DMA_PERIPH_INCREASE_DISABLE; + init_struct->memory0_addr = 0U; + init_struct->memory_inc = DMA_MEMORY_INCREASE_DISABLE; + init_struct->periph_memory_width = 0U; + init_struct->circular_mode = DMA_CIRCULAR_MODE_DISABLE; + init_struct->direction = DMA_PERIPH_TO_MEMORY; + init_struct->number = 0U; + init_struct->priority = DMA_PRIORITY_LOW; +} + +/*! + \brief initialize the DMA multi data mode parameters struct with the default values + \param[in] init_struct: the initialization data needed to initialize DMA channel + \param[out] none + \retval none +*/ +void dma_multi_data_para_struct_init(dma_multi_data_parameter_struct *init_struct) +{ + /* set the DMA struct with the default values */ + init_struct->periph_addr = 0U; + init_struct->periph_width = 0U; + init_struct->periph_inc = DMA_PERIPH_INCREASE_DISABLE; + init_struct->memory0_addr = 0U; + init_struct->memory_width = 0U; + init_struct->memory_inc = DMA_MEMORY_INCREASE_DISABLE; + init_struct->memory_burst_width = 0U; + init_struct->periph_burst_width = 0U; + init_struct->circular_mode = DMA_CIRCULAR_MODE_DISABLE; + init_struct->direction = DMA_PERIPH_TO_MEMORY; + init_struct->number = 0U; + init_struct->priority = DMA_PRIORITY_LOW; +} + +/*! + \brief initialize DMA single data mode + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel is initialized + \arg DMA_CHx(x=0..7) + \param[in] init_struct: the data needed to initialize DMA single data mode + periph_addr: peripheral base address + periph_inc: DMA_PERIPH_INCREASE_ENABLE,DMA_PERIPH_INCREASE_DISABLE,DMA_PERIPH_INCREASE_FIX + memory0_addr: memory base address + memory_inc: DMA_MEMORY_INCREASE_ENABLE,DMA_MEMORY_INCREASE_DISABLE + periph_memory_width: DMA_PERIPH_WIDTH_8BIT,DMA_PERIPH_WIDTH_16BIT,DMA_PERIPH_WIDTH_32BIT + circular_mode: DMA_CIRCULAR_MODE_ENABLE,DMA_CIRCULAR_MODE_DISABLE + direction: DMA_PERIPH_TO_MEMORY,DMA_MEMORY_TO_PERIPH,DMA_MEMORY_TO_MEMORY + number: the number of remaining data to be transferred by the DMA + priority: DMA_PRIORITY_LOW,DMA_PRIORITY_MEDIUM,DMA_PRIORITY_HIGH,DMA_PRIORITY_ULTRA_HIGH + \param[out] none + \retval none +*/ +void dma_single_data_mode_init(uint32_t dma_periph, dma_channel_enum channelx, dma_single_data_parameter_struct *init_struct) +{ + uint32_t ctl; + + /* select single data mode */ + DMA_CHFCTL(dma_periph, channelx) &= ~DMA_CHXFCTL_MDMEN; + + /* configure peripheral base address */ + DMA_CHPADDR(dma_periph, channelx) = init_struct->periph_addr; + + /* configure memory base address */ + DMA_CHM0ADDR(dma_periph, channelx) = init_struct->memory0_addr; + + /* configure the number of remaining data to be transferred */ + DMA_CHCNT(dma_periph, channelx) = init_struct->number; + + /* configure peripheral and memory transfer width,channel priotity,transfer mode */ + ctl = DMA_CHCTL(dma_periph, channelx); + ctl &= ~(DMA_CHXCTL_PWIDTH | DMA_CHXCTL_MWIDTH | DMA_CHXCTL_PRIO | DMA_CHXCTL_TM); + ctl |= (init_struct->periph_memory_width | (init_struct->periph_memory_width << 2) | init_struct->priority | init_struct->direction); + DMA_CHCTL(dma_periph, channelx) = ctl; + + /* configure peripheral increasing mode */ + if(DMA_PERIPH_INCREASE_ENABLE == init_struct->periph_inc) { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_PNAGA; + } else if(DMA_PERIPH_INCREASE_DISABLE == init_struct->periph_inc) { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_PNAGA; + } else { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_PAIF; + } + + /* configure memory increasing mode */ + if(DMA_MEMORY_INCREASE_ENABLE == init_struct->memory_inc) { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_MNAGA; + } else { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_MNAGA; + } + + /* configure DMA circular mode */ + if(DMA_CIRCULAR_MODE_ENABLE == init_struct->circular_mode) { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_CMEN; + } else { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_CMEN; + } +} + +/*! + \brief initialize DMA multi data mode + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel is initialized + \arg DMA_CHx(x=0..7) + \param[in] dma_multi_data_parameter_struct: the data needed to initialize DMA multi data mode + periph_addr: peripheral base address + periph_width: DMA_PERIPH_WIDTH_8BIT,DMA_PERIPH_WIDTH_16BIT,DMA_PERIPH_WIDTH_32BIT + periph_inc: DMA_PERIPH_INCREASE_ENABLE,DMA_PERIPH_INCREASE_DISABLE,DMA_PERIPH_INCREASE_FIX + memory0_addr: memory0 base address + memory_width: DMA_MEMORY_WIDTH_8BIT,DMA_MEMORY_WIDTH_16BIT,DMA_MEMORY_WIDTH_32BIT + memory_inc: DMA_MEMORY_INCREASE_ENABLE,DMA_MEMORY_INCREASE_DISABLE + memory_burst_width: DMA_MEMORY_BURST_SINGLE,DMA_MEMORY_BURST_4_BEAT,DMA_MEMORY_BURST_8_BEAT,DMA_MEMORY_BURST_16_BEAT + periph_burst_width: DMA_PERIPH_BURST_SINGLE,DMA_PERIPH_BURST_4_BEAT,DMA_PERIPH_BURST_8_BEAT,DMA_PERIPH_BURST_16_BEAT + critical_value: DMA_FIFO_1_WORD,DMA_FIFO_2_WORD,DMA_FIFO_3_WORD,DMA_FIFO_4_WORD + circular_mode: DMA_CIRCULAR_MODE_ENABLE,DMA_CIRCULAR_MODE_DISABLE + direction: DMA_PERIPH_TO_MEMORY,DMA_MEMORY_TO_PERIPH,DMA_MEMORY_TO_MEMORY + number: the number of remaining data to be transferred by the DMA + priority: DMA_PRIORITY_LOW,DMA_PRIORITY_MEDIUM,DMA_PRIORITY_HIGH,DMA_PRIORITY_ULTRA_HIGH + \param[out] none + \retval none +*/ +void dma_multi_data_mode_init(uint32_t dma_periph, dma_channel_enum channelx, dma_multi_data_parameter_struct *init_struct) +{ + uint32_t ctl; + + /* select multi data mode and configure FIFO critical value */ + DMA_CHFCTL(dma_periph, channelx) |= (DMA_CHXFCTL_MDMEN | init_struct->critical_value); + + /* configure peripheral base address */ + DMA_CHPADDR(dma_periph, channelx) = init_struct->periph_addr; + + /* configure memory base address */ + DMA_CHM0ADDR(dma_periph, channelx) = init_struct->memory0_addr; + + /* configure the number of remaining data to be transferred */ + DMA_CHCNT(dma_periph, channelx) = init_struct->number; + + /* configure peripheral and memory transfer width,channel priotity,transfer mode,peripheral and memory burst transfer width */ + ctl = DMA_CHCTL(dma_periph, channelx); + ctl &= ~(DMA_CHXCTL_PWIDTH | DMA_CHXCTL_MWIDTH | DMA_CHXCTL_PRIO | DMA_CHXCTL_TM | DMA_CHXCTL_PBURST | DMA_CHXCTL_MBURST); + ctl |= (init_struct->periph_width | (init_struct->memory_width) | init_struct->priority | init_struct->direction | init_struct->memory_burst_width | + init_struct->periph_burst_width); + DMA_CHCTL(dma_periph, channelx) = ctl; + + /* configure peripheral increasing mode */ + if(DMA_PERIPH_INCREASE_ENABLE == init_struct->periph_inc) { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_PNAGA; + } else if(DMA_PERIPH_INCREASE_DISABLE == init_struct->periph_inc) { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_PNAGA; + } else { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_PAIF; + } + + /* configure memory increasing mode */ + if(DMA_MEMORY_INCREASE_ENABLE == init_struct->memory_inc) { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_MNAGA; + } else { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_MNAGA; + } + + /* configure DMA circular mode */ + if(DMA_CIRCULAR_MODE_ENABLE == init_struct->circular_mode) { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_CMEN; + } else { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_CMEN; + } +} + +/*! + \brief set DMA peripheral base address + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel to set peripheral base address + \arg DMA_CHx(x=0..7) + \param[in] address: peripheral base address + \param[out] none + \retval none +*/ +void dma_periph_address_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t address) +{ + DMA_CHPADDR(dma_periph, channelx) = address; +} + +/*! + \brief set DMA Memory0 base address + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel to set Memory base address + \arg DMA_CHx(x=0..7) + \param[in] memory_flag: DMA_MEMORY_x(x=0,1) + \param[in] address: Memory base address + \param[out] none + \retval none +*/ +void dma_memory_address_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t memory_flag, uint32_t address) +{ + if(memory_flag) { + DMA_CHM1ADDR(dma_periph, channelx) = address; + } else { + DMA_CHM0ADDR(dma_periph, channelx) = address; + } +} + +/*! + \brief set the number of remaining data to be transferred by the DMA + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel to set number + \arg DMA_CHx(x=0..7) + \param[in] number: the number of remaining data to be transferred by the DMA + \param[out] none + \retval none +*/ +void dma_transfer_number_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t number) +{ + DMA_CHCNT(dma_periph, channelx) = number; +} + +/*! + \brief get the number of remaining data to be transferred by the DMA + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel to set number + \arg DMA_CHx(x=0..7) + \param[out] none + \retval uint32_t: the number of remaining data to be transferred by the DMA +*/ +uint32_t dma_transfer_number_get(uint32_t dma_periph, dma_channel_enum channelx) +{ + return (uint32_t)DMA_CHCNT(dma_periph, channelx); +} + +/*! + \brief configure priority level of DMA channel + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] priority: priority Level of this channel + only one parameter can be selected which is shown as below: + \arg DMA_PRIORITY_LOW: low priority + \arg DMA_PRIORITY_MEDIUM: medium priority + \arg DMA_PRIORITY_HIGH: high priority + \arg DMA_PRIORITY_ULTRA_HIGH: ultra high priority + \param[out] none + \retval none +*/ +void dma_priority_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t priority) +{ + uint32_t ctl; + /* acquire DMA_CHxCTL register */ + ctl = DMA_CHCTL(dma_periph, channelx); + /* assign regiser */ + ctl &= ~DMA_CHXCTL_PRIO; + ctl |= priority; + DMA_CHCTL(dma_periph, channelx) = ctl; +} + +/*! + \brief configure transfer burst beats of memory + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] mbeat: transfer burst beats + \arg DMA_MEMORY_BURST_SINGLE: memory transfer single burst + \arg DMA_MEMORY_BURST_4_BEAT: memory transfer 4-beat burst + \arg DMA_MEMORY_BURST_8_BEAT: memory transfer 8-beat burst + \arg DMA_MEMORY_BURST_16_BEAT: memory transfer 16-beat burst + \param[out] none + \retval none +*/ +void dma_memory_burst_beats_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t mbeat) +{ + uint32_t ctl; + /* acquire DMA_CHxCTL register */ + ctl = DMA_CHCTL(dma_periph, channelx); + /* assign regiser */ + ctl &= ~DMA_CHXCTL_MBURST; + ctl |= mbeat; + DMA_CHCTL(dma_periph, channelx) = ctl; +} + +/*! + \brief configure transfer burst beats of peripheral + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] pbeat: transfer burst beats + only one parameter can be selected which is shown as below: + \arg DMA_PERIPH_BURST_SINGLE: peripheral transfer single burst + \arg DMA_PERIPH_BURST_4_BEAT: peripheral transfer 4-beat burst + \arg DMA_PERIPH_BURST_8_BEAT: peripheral transfer 8-beat burst + \arg DMA_PERIPH_BURST_16_BEAT: peripheral transfer 16-beat burst + \param[out] none + \retval none +*/ +void dma_periph_burst_beats_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t pbeat) +{ + uint32_t ctl; + /* acquire DMA_CHxCTL register */ + ctl = DMA_CHCTL(dma_periph, channelx); + /* assign regiser */ + ctl &= ~DMA_CHXCTL_PBURST; + ctl |= pbeat; + DMA_CHCTL(dma_periph, channelx) = ctl; +} + +/*! + \brief configure transfer data size of memory + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] msize: transfer data size of memory + only one parameter can be selected which is shown as below: + \arg DMA_MEMORY_WIDTH_8BIT: transfer data size of memory is 8-bit + \arg DMA_MEMORY_WIDTH_16BIT: transfer data size of memory is 16-bit + \arg DMA_MEMORY_WIDTH_32BIT: transfer data size of memory is 32-bit + \param[out] none + \retval none +*/ +void dma_memory_width_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t msize) +{ + uint32_t ctl; + /* acquire DMA_CHxCTL register */ + ctl = DMA_CHCTL(dma_periph, channelx); + /* assign regiser */ + ctl &= ~DMA_CHXCTL_MWIDTH; + ctl |= msize; + DMA_CHCTL(dma_periph, channelx) = ctl; +} + +/*! + \brief configure transfer data size of peripheral + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] msize: transfer data size of peripheral + only one parameter can be selected which is shown as below: + \arg DMA_PERIPHERAL_WIDTH_8BIT: transfer data size of peripheral is 8-bit + \arg DMA_PERIPHERAL_WIDTH_16BIT: transfer data size of peripheral is 16-bit + \arg DMA_PERIPHERAL_WIDTH_32BIT: transfer data size of peripheral is 32-bit + \param[out] none + \retval none +*/ +void dma_periph_width_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t psize) +{ + uint32_t ctl; + /* acquire DMA_CHxCTL register */ + ctl = DMA_CHCTL(dma_periph, channelx); + /* assign regiser */ + ctl &= ~DMA_CHXCTL_PWIDTH; + ctl |= psize; + DMA_CHCTL(dma_periph, channelx) = ctl; +} + +/*! + \brief configure memory address generation generation_algorithm + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] generation_algorithm: the address generation algorithm + only one parameter can be selected which is shown as below: + \arg DMA_MEMORY_INCREASE_ENABLE: next address of memory is increasing address mode + \arg DMA_MEMORY_INCREASE_DISABLE: next address of memory is fixed address mode + \param[out] none + \retval none +*/ +void dma_memory_address_generation_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t generation_algorithm) +{ + if(DMA_MEMORY_INCREASE_ENABLE == generation_algorithm) { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_MNAGA; + } else { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_MNAGA; + } +} + +/*! + \brief configure peripheral address generation_algorithm + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] generation_algorithm: the address generation algorithm + only one parameter can be selected which is shown as below: + \arg DMA_PERIPH_INCREASE_ENABLE: next address of peripheral is increasing address mode + \arg DMA_PERIPH_INCREASE_DISABLE: next address of peripheral is fixed address mode + \arg DMA_PERIPH_INCREASE_FIX: increasing steps of peripheral address is fixed + \param[out] none + \retval none +*/ +void dma_peripheral_address_generation_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t generation_algorithm) +{ + if(DMA_PERIPH_INCREASE_ENABLE == generation_algorithm) { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_PNAGA; + } else if(DMA_PERIPH_INCREASE_DISABLE == generation_algorithm) { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_PNAGA; + } else { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_PNAGA; + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_PAIF; + } +} + +/*! + \brief enable DMA circulation mode + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[out] none + \retval none +*/ +void dma_circulation_enable(uint32_t dma_periph, dma_channel_enum channelx) +{ + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_CMEN; +} + +/*! + \brief disable DMA circulation mode + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[out] none + \retval none +*/ +void dma_circulation_disable(uint32_t dma_periph, dma_channel_enum channelx) +{ + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_CMEN; +} + +/*! + \brief enable DMA channel + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[out] none + \retval none +*/ +void dma_channel_enable(uint32_t dma_periph, dma_channel_enum channelx) +{ + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_CHEN; +} + +/*! + \brief disable DMA channel + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[out] none + \retval none +*/ +void dma_channel_disable(uint32_t dma_periph, dma_channel_enum channelx) +{ + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_CHEN; +} + +/*! + \brief configure the direction of data transfer on the channel + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] direction: specify the direction of data transfer + only one parameter can be selected which is shown as below: + \arg DMA_PERIPH_TO_MEMORY: read from peripheral and write to memory + \arg DMA_MEMORY_TO_PERIPH: read from memory and write to peripheral + \arg DMA_MEMORY_TO_MEMORY: read from memory and write to memory + \param[out] none + \retval none +*/ +void dma_transfer_direction_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t direction) +{ + uint32_t ctl; + /* acquire DMA_CHxCTL register */ + ctl = DMA_CHCTL(dma_periph, channelx); + /* assign regiser */ + ctl &= ~DMA_CHXCTL_TM; + ctl |= direction; + + DMA_CHCTL(dma_periph, channelx) = ctl; +} + +/*! + \brief DMA switch buffer mode config + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] memory1_addr: memory1 base address + \param[in] memory_select: DMA_MEMORY_0 or DMA_MEMORY_1 + \param[out] none + \retval none +*/ +void dma_switch_buffer_mode_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t memory1_addr, uint32_t memory_select) +{ + /* configure memory1 base address */ + DMA_CHM1ADDR(dma_periph, channelx) = memory1_addr; + + if(DMA_MEMORY_0 == memory_select) { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_MBS; + } else { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_MBS; + } +} + +/*! + \brief DMA using memory get + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[out] none + \retval the using memory +*/ +uint32_t dma_using_memory_get(uint32_t dma_periph, dma_channel_enum channelx) +{ + if((DMA_CHCTL(dma_periph, channelx)) & DMA_CHXCTL_MBS) { + return DMA_MEMORY_1; + } else { + return DMA_MEMORY_0; + } +} + +/*! + \brief DMA channel peripheral select + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] sub_periph: specify DMA channel peripheral + \arg DMA_SUBPERIx(x=0..7) + \param[out] none + \retval none +*/ +void dma_channel_subperipheral_select(uint32_t dma_periph, dma_channel_enum channelx, dma_subperipheral_enum sub_periph) +{ + uint32_t ctl; + /* acquire DMA_CHxCTL register */ + ctl = DMA_CHCTL(dma_periph, channelx); + /* assign regiser */ + ctl &= ~DMA_CHXCTL_PERIEN; + ctl |= ((uint32_t)sub_periph << CHXCTL_PERIEN_OFFSET); + + DMA_CHCTL(dma_periph, channelx) = ctl; +} + +/*! + \brief DMA flow controller configure + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] controller: specify DMA flow controler + only one parameter can be selected which is shown as below: + \arg DMA_FLOW_CONTROLLER_DMA: DMA is the flow controller + \arg DMA_FLOW_CONTROLLER_PERI: peripheral is the flow controller + \param[out] none + \retval none +*/ +void dma_flow_controller_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t controller) +{ + if(DMA_FLOW_CONTROLLER_DMA == controller) { + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_TFCS; + } else { + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_TFCS; + } +} + +/*! + \brief DMA switch buffer mode enable + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] newvalue: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void dma_switch_buffer_mode_enable(uint32_t dma_periph, dma_channel_enum channelx, ControlStatus newvalue) +{ + if(ENABLE == newvalue) { + /* switch buffer mode enable */ + DMA_CHCTL(dma_periph, channelx) |= DMA_CHXCTL_SBMEN; + } else { + /* switch buffer mode disable */ + DMA_CHCTL(dma_periph, channelx) &= ~DMA_CHXCTL_SBMEN; + } +} + +/*! + \brief DMA FIFO status get + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[out] none + \retval the using memory +*/ +uint32_t dma_fifo_status_get(uint32_t dma_periph, dma_channel_enum channelx) +{ + return (DMA_CHFCTL(dma_periph, channelx) & DMA_CHXFCTL_FCNT); +} + +/*! + \brief get DMA flag is set or not + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel to get flag + \arg DMA_CHx(x=0..7) + \param[in] flag: specify get which flag + only one parameter can be selected which is shown as below: + \arg DMA_FLAG_FEE: FIFO error and exception flag + \arg DMA_FLAG_SDE: single data mode exception flag + \arg DMA_FLAG_TAE: transfer access error flag + \arg DMA_FLAG_HTF: half transfer finish flag + \arg DMA_FLAG_FTF: full transger finish flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus dma_flag_get(uint32_t dma_periph, dma_channel_enum channelx, uint32_t flag) +{ + if(channelx < DMA_CH4) { + if(DMA_INTF0(dma_periph) & DMA_FLAG_ADD(flag, channelx)) { + return SET; + } else { + return RESET; + } + } else { + channelx -= (dma_channel_enum)4; + if(DMA_INTF1(dma_periph) & DMA_FLAG_ADD(flag, channelx)) { + return SET; + } else { + return RESET; + } + } +} + +/*! + \brief clear DMA a channel flag + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel to get flag + \arg DMA_CHx(x=0..7) + \param[in] flag: specify get which flag + only one parameter can be selected which is shown as below: + \arg DMA_FLAG_FEE: FIFO error and exception flag + \arg DMA_FLAG_SDE: single data mode exception flag + \arg DMA_FLAG_TAE: transfer access error flag + \arg DMA_FLAG_HTF: half transfer finish flag + \arg DMA_FLAG_FTF: full transger finish flag + \param[out] none + \retval none +*/ +void dma_flag_clear(uint32_t dma_periph, dma_channel_enum channelx, uint32_t flag) +{ + if(channelx < DMA_CH4) { + DMA_INTC0(dma_periph) |= DMA_FLAG_ADD(flag, channelx); + } else { + channelx -= (dma_channel_enum)4; + DMA_INTC1(dma_periph) |= DMA_FLAG_ADD(flag, channelx); + } +} + +/*! + \brief enable DMA interrupt + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] interrupt: specify which interrupt to enbale + only one parameters can be selected which are shown as below: + \arg DMA_INT_SDE: single data mode exception interrupt enable + \arg DMA_INT_TAE: tranfer access error interrupt enable + \arg DMA_INT_HTF: half transfer finish interrupt enable + \arg DMA_INT_FTF: full transfer finish interrupt enable + \arg DMA_INT_FEE: FIFO exception interrupt enable + \param[out] none + \retval none +*/ +void dma_interrupt_enable(uint32_t dma_periph, dma_channel_enum channelx, uint32_t interrupt) +{ + if(DMA_INT_FEE != interrupt) { + DMA_CHCTL(dma_periph, channelx) |= interrupt; + } else { + DMA_CHFCTL(dma_periph, channelx) |= interrupt; + } +} + +/*! + \brief disable DMA interrupt + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel + \arg DMA_CHx(x=0..7) + \param[in] interrupt: specify which interrupt to disbale + only one parameters can be selected which are shown as below: + \arg DMA_INT_SDE: single data mode exception interrupt enable + \arg DMA_INT_TAE: tranfer access error interrupt enable + \arg DMA_INT_HTF: half transfer finish interrupt enable + \arg DMA_INT_FTF: full transfer finish interrupt enable + \arg DMA_INT_FEE: FIFO exception interrupt enable + \param[out] none + \retval none +*/ +void dma_interrupt_disable(uint32_t dma_periph, dma_channel_enum channelx, uint32_t interrupt) +{ + if(DMA_INT_FEE != interrupt) { + DMA_CHCTL(dma_periph, channelx) &= ~interrupt; + } else { + DMA_CHFCTL(dma_periph, channelx) &= ~interrupt; + } +} + +/*! + \brief get DMA interrupt flag is set or not + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel to get interrupt flag + \arg DMA_CHx(x=0..7) + \param[in] interrupt: specify get which flag + only one parameter can be selected which is shown as below: + \arg DMA_INT_FLAG_FEE: FIFO error and exception interrupt flag + \arg DMA_INT_FLAG_SDE: single data mode exception interrupt flag + \arg DMA_INT_FLAG_TAE: transfer access error interrupt flag + \arg DMA_INT_FLAG_HTF: half transfer finish interrupt flag + \arg DMA_INT_FLAG_FTF: full transger finish interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus dma_interrupt_flag_get(uint32_t dma_periph, dma_channel_enum channelx, uint32_t interrupt) +{ + uint32_t interrupt_enable = 0U, interrupt_flag = 0U; + dma_channel_enum channel_flag_offset = channelx; + if(channelx < DMA_CH4) { + switch(interrupt) { + case DMA_INTF_FEEIF: + interrupt_flag = DMA_INTF0(dma_periph) & DMA_FLAG_ADD(interrupt, channelx); + interrupt_enable = DMA_CHFCTL(dma_periph, channelx) & DMA_CHXFCTL_FEEIE; + break; + case DMA_INTF_SDEIF: + interrupt_flag = DMA_INTF0(dma_periph) & DMA_FLAG_ADD(interrupt, channelx); + interrupt_enable = DMA_CHCTL(dma_periph, channelx) & DMA_CHXCTL_SDEIE; + break; + case DMA_INTF_TAEIF: + interrupt_flag = DMA_INTF0(dma_periph) & DMA_FLAG_ADD(interrupt, channelx); + interrupt_enable = DMA_CHCTL(dma_periph, channelx) & DMA_CHXCTL_TAEIE; + break; + case DMA_INTF_HTFIF: + interrupt_flag = DMA_INTF0(dma_periph) & DMA_FLAG_ADD(interrupt, channelx); + interrupt_enable = DMA_CHCTL(dma_periph, channelx) & DMA_CHXCTL_HTFIE; + break; + case DMA_INTF_FTFIF: + interrupt_flag = (DMA_INTF0(dma_periph) & DMA_FLAG_ADD(interrupt, channelx)); + interrupt_enable = (DMA_CHCTL(dma_periph, channelx) & DMA_CHXCTL_FTFIE); + break; + default: + break; + } + } else { + channel_flag_offset -= (dma_channel_enum)4; + switch(interrupt) { + case DMA_INTF_FEEIF: + interrupt_flag = DMA_INTF1(dma_periph) & DMA_FLAG_ADD(interrupt, channel_flag_offset); + interrupt_enable = DMA_CHFCTL(dma_periph, channelx) & DMA_CHXFCTL_FEEIE; + break; + case DMA_INTF_SDEIF: + interrupt_flag = DMA_INTF1(dma_periph) & DMA_FLAG_ADD(interrupt, channel_flag_offset); + interrupt_enable = DMA_CHCTL(dma_periph, channelx) & DMA_CHXCTL_SDEIE; + break; + case DMA_INTF_TAEIF: + interrupt_flag = DMA_INTF1(dma_periph) & DMA_FLAG_ADD(interrupt, channel_flag_offset); + interrupt_enable = DMA_CHCTL(dma_periph, channelx) & DMA_CHXCTL_TAEIE; + break; + case DMA_INTF_HTFIF: + interrupt_flag = DMA_INTF1(dma_periph) & DMA_FLAG_ADD(interrupt, channel_flag_offset); + interrupt_enable = DMA_CHCTL(dma_periph, channelx) & DMA_CHXCTL_HTFIE; + break; + case DMA_INTF_FTFIF: + interrupt_flag = DMA_INTF1(dma_periph) & DMA_FLAG_ADD(interrupt, channel_flag_offset); + interrupt_enable = DMA_CHCTL(dma_periph, channelx) & DMA_CHXCTL_FTFIE; + break; + default: + break; + } + } + + if(interrupt_flag && interrupt_enable) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear DMA a channel interrupt flag + \param[in] dma_periph: DMAx(x=0,1) + \arg DMAx(x=0,1) + \param[in] channelx: specify which DMA channel to clear interrupt flag + \arg DMA_CHx(x=0..7) + \param[in] interrupt: specify get which flag + only one parameter can be selected which is shown as below: + \arg DMA_INT_FLAG_FEE: FIFO error and exception interrupt flag + \arg DMA_INT_FLAG_SDE: single data mode exception interrupt flag + \arg DMA_INT_FLAG_TAE: transfer access error interrupt flag + \arg DMA_INT_FLAG_HTF: half transfer finish interrupt flag + \arg DMA_INT_FLAG_FTF: full transger finish interrupt flag + \param[out] none + \retval none +*/ +void dma_interrupt_flag_clear(uint32_t dma_periph, dma_channel_enum channelx, uint32_t interrupt) +{ + if(channelx < DMA_CH4) { + DMA_INTC0(dma_periph) |= DMA_FLAG_ADD(interrupt, channelx); + } else { + channelx -= (dma_channel_enum)4; + DMA_INTC1(dma_periph) |= DMA_FLAG_ADD(interrupt, channelx); + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_enet.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_enet.c new file mode 100644 index 0000000..087dc22 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_enet.c @@ -0,0 +1,3701 @@ +/*! + \file gd32f5xx_enet.c + \brief ENET driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + 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 the copyright holder 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 "gd32f5xx_enet.h" +#include + +#if defined (__CC_ARM) /*!< ARM compiler */ +__align(4) +enet_descriptors_struct rxdesc_tab[ENET_RXBUF_NUM]; /*!< ENET RxDMA descriptor */ +__align(4) +enet_descriptors_struct txdesc_tab[ENET_TXBUF_NUM]; /*!< ENET TxDMA descriptor */ +__align(4) +uint8_t rx_buff[ENET_RXBUF_NUM][ENET_RXBUF_SIZE]; /*!< ENET receive buffer */ +__align(4) +uint8_t tx_buff[ENET_TXBUF_NUM][ENET_TXBUF_SIZE]; /*!< ENET transmit buffer */ + +#elif defined ( __ICCARM__ ) /*!< IAR compiler */ +#pragma data_alignment=4 +enet_descriptors_struct rxdesc_tab[ENET_RXBUF_NUM]; /*!< ENET RxDMA descriptor */ +#pragma data_alignment=4 +enet_descriptors_struct txdesc_tab[ENET_TXBUF_NUM]; /*!< ENET TxDMA descriptor */ +#pragma data_alignment=4 +uint8_t rx_buff[ENET_RXBUF_NUM][ENET_RXBUF_SIZE]; /*!< ENET receive buffer */ +#pragma data_alignment=4 +uint8_t tx_buff[ENET_TXBUF_NUM][ENET_TXBUF_SIZE]; /*!< ENET transmit buffer */ + +#elif defined (__GNUC__) /* GNU Compiler */ +enet_descriptors_struct rxdesc_tab[ENET_RXBUF_NUM] __attribute__((aligned(4))); /*!< ENET RxDMA descriptor */ +enet_descriptors_struct txdesc_tab[ENET_TXBUF_NUM] __attribute__((aligned(4))); /*!< ENET TxDMA descriptor */ +uint8_t rx_buff[ENET_RXBUF_NUM][ENET_RXBUF_SIZE] __attribute__((aligned(4))); /*!< ENET receive buffer */ +uint8_t tx_buff[ENET_TXBUF_NUM][ENET_TXBUF_SIZE] __attribute__((aligned(4))); /*!< ENET transmit buffer */ + +#endif /* __CC_ARM */ + +/* global transmit and receive descriptors pointers */ +enet_descriptors_struct *dma_current_txdesc; +enet_descriptors_struct *dma_current_rxdesc; + +/* structure pointer of ptp descriptor for normal mode */ +enet_descriptors_struct *dma_current_ptp_txdesc = NULL; +enet_descriptors_struct *dma_current_ptp_rxdesc = NULL; + +/* init structure parameters for ENET initialization */ +static enet_initpara_struct enet_initpara = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; +static uint32_t enet_unknow_err = 0U; +/* array of register offset for debug information get */ +static const uint16_t enet_reg_tab[] = { + 0x0000, 0x0004, 0x0008, 0x000C, 0x0010, 0x0014, 0x0018, 0x001C, 0x0028, 0x002C, 0x0034, + + 0x0038, 0x003C, 0x0040, 0x0044, 0x0048, 0x004C, 0x0050, 0x0054, 0x0058, 0x005C, 0x1080, + + 0x0100, 0x0104, 0x0108, 0x010C, 0x0110, 0x014C, 0x0150, 0x0168, 0x0194, 0x0198, 0x01C4, + + 0x0700, 0x0704, 0x0708, 0x070C, 0x0710, 0x0714, 0x0718, 0x071C, 0x0720, 0x0728, 0x072C, + + 0x1000, 0x1004, 0x1008, 0x100C, 0x1010, 0x1014, 0x1018, 0x101C, 0x1020, 0x1024, 0x1048, + + 0x104C, 0x1050, 0x1054 +}; + +/* initialize ENET peripheral with generally concerned parameters, call it by enet_init() */ +static void enet_default_init(void); +#ifndef USE_DELAY +/* insert a delay time */ +static void enet_delay(uint32_t ncount); +#endif /* USE_DELAY */ + +/*! + \brief deinitialize the ENET, and reset structure parameters for ENET initialization + \param[in] none + \param[out] none + \retval none +*/ +void enet_deinit(void) +{ + rcu_periph_reset_enable(RCU_ENETRST); + rcu_periph_reset_disable(RCU_ENETRST); + enet_initpara_reset(); +} + +/*! + \brief configure the parameters which are usually less cared for initialization + note -- this function must be called before enet_init(), otherwise + configuration will be no effect + \param[in] option: different function option, which is related to several parameters, + only one parameter can be selected which is shown as below, refer to enet_option_enum + \arg FORWARD_OPTION: choose to configure the frame forward related parameters + \arg DMABUS_OPTION: choose to configure the DMA bus mode related parameters + \arg DMA_MAXBURST_OPTION: choose to configure the DMA max burst related parameters + \arg DMA_ARBITRATION_OPTION: choose to configure the DMA arbitration related parameters + \arg STORE_OPTION: choose to configure the store forward mode related parameters + \arg DMA_OPTION: choose to configure the DMA descriptor related parameters + \arg VLAN_OPTION: choose to configure vlan related parameters + \arg FLOWCTL_OPTION: choose to configure flow control related parameters + \arg HASHH_OPTION: choose to configure hash high + \arg HASHL_OPTION: choose to configure hash low + \arg FILTER_OPTION: choose to configure frame filter related parameters + \arg HALFDUPLEX_OPTION: choose to configure halfduplex mode related parameters + \arg TIMER_OPTION: choose to configure time counter related parameters + \arg INTERFRAMEGAP_OPTION: choose to configure the inter frame gap related parameters + \param[in] para: the related parameters according to the option + all the related parameters should be configured which are shown as below + FORWARD_OPTION related parameters: + - ENET_AUTO_PADCRC_DROP_ENABLE/ ENET_AUTO_PADCRC_DROP_DISABLE ; + - ENET_TYPEFRAME_CRC_DROP_ENABLE/ ENET_TYPEFRAME_CRC_DROP_DISABLE ; + - ENET_FORWARD_ERRFRAMES_ENABLE/ ENET_FORWARD_ERRFRAMES_DISABLE ; + - ENET_FORWARD_UNDERSZ_GOODFRAMES_ENABLE/ ENET_FORWARD_UNDERSZ_GOODFRAMES_DISABLE . + DMABUS_OPTION related parameters: + - ENET_ADDRESS_ALIGN_ENABLE/ ENET_ADDRESS_ALIGN_DISABLE ; + - ENET_FIXED_BURST_ENABLE/ ENET_FIXED_BURST_DISABLE ; + - ENET_MIXED_BURST_ENABLE/ ENET_MIXED_BURST_DISABLE ; + DMA_MAXBURST_OPTION related parameters: + - ENET_RXDP_1BEAT/ ENET_RXDP_2BEAT/ ENET_RXDP_4BEAT/ + ENET_RXDP_8BEAT/ ENET_RXDP_16BEAT/ ENET_RXDP_32BEAT/ + ENET_RXDP_4xPGBL_4BEAT/ ENET_RXDP_4xPGBL_8BEAT/ + ENET_RXDP_4xPGBL_16BEAT/ ENET_RXDP_4xPGBL_32BEAT/ + ENET_RXDP_4xPGBL_64BEAT/ ENET_RXDP_4xPGBL_128BEAT ; + - ENET_PGBL_1BEAT/ ENET_PGBL_2BEAT/ ENET_PGBL_4BEAT/ + ENET_PGBL_8BEAT/ ENET_PGBL_16BEAT/ ENET_PGBL_32BEAT/ + ENET_PGBL_4xPGBL_4BEAT/ ENET_PGBL_4xPGBL_8BEAT/ + ENET_PGBL_4xPGBL_16BEAT/ ENET_PGBL_4xPGBL_32BEAT/ + ENET_PGBL_4xPGBL_64BEAT/ ENET_PGBL_4xPGBL_128BEAT ; + - ENET_RXTX_DIFFERENT_PGBL/ ENET_RXTX_SAME_PGBL ; + DMA_ARBITRATION_OPTION related parameters: + - ENET_ARBITRATION_RXPRIORTX + - ENET_ARBITRATION_RXTX_1_1/ ENET_ARBITRATION_RXTX_2_1/ + ENET_ARBITRATION_RXTX_3_1/ ENET_ARBITRATION_RXTX_4_1/. + STORE_OPTION related parameters: + - ENET_RX_MODE_STOREFORWARD/ ENET_RX_MODE_CUTTHROUGH ; + - ENET_TX_MODE_STOREFORWARD/ ENET_TX_MODE_CUTTHROUGH ; + - ENET_RX_THRESHOLD_64BYTES/ ENET_RX_THRESHOLD_32BYTES/ + ENET_RX_THRESHOLD_96BYTES/ ENET_RX_THRESHOLD_128BYTES ; + - ENET_TX_THRESHOLD_64BYTES/ ENET_TX_THRESHOLD_128BYTES/ + ENET_TX_THRESHOLD_192BYTES/ ENET_TX_THRESHOLD_256BYTES/ + ENET_TX_THRESHOLD_40BYTES/ ENET_TX_THRESHOLD_32BYTES/ + ENET_TX_THRESHOLD_24BYTES/ ENET_TX_THRESHOLD_16BYTES . + DMA_OPTION related parameters: + - ENET_FLUSH_RXFRAME_ENABLE/ ENET_FLUSH_RXFRAME_DISABLE ; + - ENET_SECONDFRAME_OPT_ENABLE/ ENET_SECONDFRAME_OPT_DISABLE ; + - ENET_ENHANCED_DESCRIPTOR/ ENET_NORMAL_DESCRIPTOR . + VLAN_OPTION related parameters: + - ENET_VLANTAGCOMPARISON_12BIT/ ENET_VLANTAGCOMPARISON_16BIT ; + - MAC_VLT_VLTI(regval) . + FLOWCTL_OPTION related parameters: + - MAC_FCTL_PTM(regval) ; + - ENET_ZERO_QUANTA_PAUSE_ENABLE/ ENET_ZERO_QUANTA_PAUSE_DISABLE ; + - ENET_PAUSETIME_MINUS4/ ENET_PAUSETIME_MINUS28/ + ENET_PAUSETIME_MINUS144/ENET_PAUSETIME_MINUS256 ; + - ENET_MAC0_AND_UNIQUE_ADDRESS_PAUSEDETECT/ ENET_UNIQUE_PAUSEDETECT ; + - ENET_RX_FLOWCONTROL_ENABLE/ ENET_RX_FLOWCONTROL_DISABLE ; + - ENET_TX_FLOWCONTROL_ENABLE/ ENET_TX_FLOWCONTROL_DISABLE ; + - ENET_ACTIVE_THRESHOLD_256BYTES/ ENET_ACTIVE_THRESHOLD_512BYTES ; + - ENET_ACTIVE_THRESHOLD_768BYTES/ ENET_ACTIVE_THRESHOLD_1024BYTES ; + - ENET_ACTIVE_THRESHOLD_1280BYTES/ ENET_ACTIVE_THRESHOLD_1536BYTES ; + - ENET_ACTIVE_THRESHOLD_1792BYTES ; + - ENET_DEACTIVE_THRESHOLD_256BYTES/ ENET_DEACTIVE_THRESHOLD_512BYTES ; + - ENET_DEACTIVE_THRESHOLD_768BYTES/ ENET_DEACTIVE_THRESHOLD_1024BYTES ; + - ENET_DEACTIVE_THRESHOLD_1280BYTES/ ENET_DEACTIVE_THRESHOLD_1536BYTES ; + - ENET_DEACTIVE_THRESHOLD_1792BYTES . + HASHH_OPTION related parameters: + - 0x0~0xFFFF FFFFU + HASHL_OPTION related parameters: + - 0x0~0xFFFF FFFFU + FILTER_OPTION related parameters: + - ENET_SRC_FILTER_NORMAL_ENABLE/ ENET_SRC_FILTER_INVERSE_ENABLE/ + ENET_SRC_FILTER_DISABLE ; + - ENET_DEST_FILTER_INVERSE_ENABLE/ ENET_DEST_FILTER_INVERSE_DISABLE ; + - ENET_MULTICAST_FILTER_HASH_OR_PERFECT/ ENET_MULTICAST_FILTER_HASH/ + ENET_MULTICAST_FILTER_PERFECT/ ENET_MULTICAST_FILTER_NONE ; + - ENET_UNICAST_FILTER_EITHER/ ENET_UNICAST_FILTER_HASH/ + ENET_UNICAST_FILTER_PERFECT ; + - ENET_PCFRM_PREVENT_ALL/ ENET_PCFRM_PREVENT_PAUSEFRAME/ + ENET_PCFRM_FORWARD_ALL/ ENET_PCFRM_FORWARD_FILTERED . + HALFDUPLEX_OPTION related parameters: + - ENET_CARRIERSENSE_ENABLE/ ENET_CARRIERSENSE_DISABLE ; + - ENET_RECEIVEOWN_ENABLE/ ENET_RECEIVEOWN_DISABLE ; + - ENET_RETRYTRANSMISSION_ENABLE/ ENET_RETRYTRANSMISSION_DISABLE ; + - ENET_BACKOFFLIMIT_10/ ENET_BACKOFFLIMIT_8/ + ENET_BACKOFFLIMIT_4/ ENET_BACKOFFLIMIT_1 ; + - ENET_DEFERRALCHECK_ENABLE/ ENET_DEFERRALCHECK_DISABLE . + TIMER_OPTION related parameters: + - ENET_WATCHDOG_ENABLE/ ENET_WATCHDOG_DISABLE ; + - ENET_JABBER_ENABLE/ ENET_JABBER_DISABLE ; + INTERFRAMEGAP_OPTION related parameters: + - ENET_INTERFRAMEGAP_96BIT/ ENET_INTERFRAMEGAP_88BIT/ + ENET_INTERFRAMEGAP_80BIT/ ENET_INTERFRAMEGAP_72BIT/ + ENET_INTERFRAMEGAP_64BIT/ ENET_INTERFRAMEGAP_56BIT/ + ENET_INTERFRAMEGAP_48BIT/ ENET_INTERFRAMEGAP_40BIT . + \param[out] none + \retval none +*/ +void enet_initpara_config(enet_option_enum option, uint32_t para) +{ + switch(option) { + case FORWARD_OPTION: + /* choose to configure forward_frame, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)FORWARD_OPTION; + enet_initpara.forward_frame = para; + break; + case DMABUS_OPTION: + /* choose to configure dmabus_mode, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)DMABUS_OPTION; + enet_initpara.dmabus_mode = para; + break; + case DMA_MAXBURST_OPTION: + /* choose to configure dma_maxburst, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)DMA_MAXBURST_OPTION; + enet_initpara.dma_maxburst = para; + break; + case DMA_ARBITRATION_OPTION: + /* choose to configure dma_arbitration, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)DMA_ARBITRATION_OPTION; + enet_initpara.dma_arbitration = para; + break; + case STORE_OPTION: + /* choose to configure store_forward_mode, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)STORE_OPTION; + enet_initpara.store_forward_mode = para; + break; + case DMA_OPTION: + /* choose to configure dma_function, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)DMA_OPTION; + +#ifndef SELECT_DESCRIPTORS_ENHANCED_MODE + para &= ~ENET_ENHANCED_DESCRIPTOR; +#endif /* SELECT_DESCRIPTORS_ENHANCED_MODE */ + + enet_initpara.dma_function = para; + break; + case VLAN_OPTION: + /* choose to configure vlan_config, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)VLAN_OPTION; + enet_initpara.vlan_config = para; + break; + case FLOWCTL_OPTION: + /* choose to configure flow_control, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)FLOWCTL_OPTION; + enet_initpara.flow_control = para; + break; + case HASHH_OPTION: + /* choose to configure hashtable_high, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)HASHH_OPTION; + enet_initpara.hashtable_high = para; + break; + case HASHL_OPTION: + /* choose to configure hashtable_low, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)HASHL_OPTION; + enet_initpara.hashtable_low = para; + break; + case FILTER_OPTION: + /* choose to configure framesfilter_mode, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)FILTER_OPTION; + enet_initpara.framesfilter_mode = para; + break; + case HALFDUPLEX_OPTION: + /* choose to configure halfduplex_param, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)HALFDUPLEX_OPTION; + enet_initpara.halfduplex_param = para; + break; + case TIMER_OPTION: + /* choose to configure timer_config, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)TIMER_OPTION; + enet_initpara.timer_config = para; + break; + case INTERFRAMEGAP_OPTION: + /* choose to configure interframegap, and save the configuration parameters */ + enet_initpara.option_enable |= (uint32_t)INTERFRAMEGAP_OPTION; + enet_initpara.interframegap = para; + break; + default: + break; + } +} + +/*! + \brief initialize ENET peripheral with generally concerned parameters and the less cared + parameters + \param[in] mediamode: PHY mode and mac loopback configurations, only one parameter can be selected + which is shown as below, refer to enet_mediamode_enum + \arg ENET_AUTO_NEGOTIATION: PHY auto negotiation + \arg ENET_100M_FULLDUPLEX: 100Mbit/s, full-duplex + \arg ENET_100M_HALFDUPLEX: 100Mbit/s, half-duplex + \arg ENET_10M_FULLDUPLEX: 10Mbit/s, full-duplex + \arg ENET_10M_HALFDUPLEX: 10Mbit/s, half-duplex + \arg ENET_LOOPBACKMODE: MAC in loopback mode at the MII + \param[in] checksum: IP frame checksum offload function, only one parameter can be selected + which is shown as below, refer to enet_mediamode_enum + \arg ENET_NO_AUTOCHECKSUM: disable IP frame checksum function + \arg ENET_AUTOCHECKSUM_DROP_FAILFRAMES: enable IP frame checksum function + \arg ENET_AUTOCHECKSUM_ACCEPT_FAILFRAMES: enable IP frame checksum function, and the received frame + with only payload error but no other errors will not be dropped + \param[in] recept: frame filter function, only one parameter can be selected + which is shown as below, refer to enet_frmrecept_enum + \arg ENET_PROMISCUOUS_MODE: promiscuous mode enabled + \arg ENET_RECEIVEALL: all received frame are forwarded to application + \arg ENET_BROADCAST_FRAMES_PASS: the address filters pass all received broadcast frames + \arg ENET_BROADCAST_FRAMES_DROP: the address filters filter all incoming broadcast frames + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus enet_init(enet_mediamode_enum mediamode, enet_chksumconf_enum checksum, enet_frmrecept_enum recept) +{ + uint32_t reg_value = 0U, reg_temp = 0U, temp = 0U; + uint32_t media_temp = 0U; + uint32_t timeout = 0U; + uint16_t phy_value = 0U; + ErrStatus phy_state = ERROR, enet_state = ERROR; + + /* PHY interface configuration, configure SMI clock and reset PHY chip */ + if(ERROR == enet_phy_config()) { + _ENET_DELAY_(PHY_RESETDELAY); + if(ERROR == enet_phy_config()) { + return enet_state; + } + } + /* initialize ENET peripheral with generally concerned parameters */ + enet_default_init(); + + /* 1st, configure mediamode */ + media_temp = (uint32_t)mediamode; + /* if is PHY auto negotiation */ + if((uint32_t)ENET_AUTO_NEGOTIATION == media_temp) { + /* wait for PHY_LINKED_STATUS bit be set */ + do { + enet_phy_write_read(ENET_PHY_READ, PHY_ADDRESS, PHY_REG_BSR, &phy_value); + phy_value &= PHY_LINKED_STATUS; + timeout++; + } while((RESET == phy_value) && (timeout < PHY_READ_TO)); + /* return ERROR due to timeout */ + if(PHY_READ_TO == timeout) { + return enet_state; + } + /* reset timeout counter */ + timeout = 0U; + + /* enable auto-negotiation */ + phy_value = PHY_AUTONEGOTIATION; + phy_state = enet_phy_write_read(ENET_PHY_WRITE, PHY_ADDRESS, PHY_REG_BCR, &phy_value); + if(!phy_state) { + /* return ERROR due to write timeout */ + return enet_state; + } + + /* wait for the PHY_AUTONEGO_COMPLETE bit be set */ + do { + enet_phy_write_read(ENET_PHY_READ, PHY_ADDRESS, PHY_REG_BSR, &phy_value); + phy_value &= PHY_AUTONEGO_COMPLETE; + timeout++; + } while((RESET == phy_value) && (timeout < (uint32_t)PHY_READ_TO)); + /* return ERROR due to timeout */ + if(PHY_READ_TO == timeout) { + return enet_state; + } + /* reset timeout counter */ + timeout = 0U; + + /* read the result of the auto-negotiation */ + enet_phy_write_read(ENET_PHY_READ, PHY_ADDRESS, PHY_SR, &phy_value); + /* configure the duplex mode of MAC following the auto-negotiation result */ + if((uint16_t)RESET != (phy_value & PHY_DUPLEX_STATUS)) { + media_temp = ENET_MODE_FULLDUPLEX; + } else { + media_temp = ENET_MODE_HALFDUPLEX; + } + /* configure the communication speed of MAC following the auto-negotiation result */ + if((uint16_t)RESET != (phy_value & PHY_SPEED_STATUS)) { + media_temp |= ENET_SPEEDMODE_10M; + } else { + media_temp |= ENET_SPEEDMODE_100M; + } + } else { + phy_value = (uint16_t)((media_temp & ENET_MAC_CFG_DPM) >> 3); + phy_value |= (uint16_t)((media_temp & ENET_MAC_CFG_SPD) >> 1); + phy_state = enet_phy_write_read(ENET_PHY_WRITE, PHY_ADDRESS, PHY_REG_BCR, &phy_value); + if(!phy_state) { + /* return ERROR due to write timeout */ + return enet_state; + } + /* PHY configuration need some time */ + _ENET_DELAY_(PHY_CONFIGDELAY); + } + /* after configuring the PHY, use mediamode to configure registers */ + reg_value = ENET_MAC_CFG; + /* configure ENET_MAC_CFG register */ + reg_value &= (~(ENET_MAC_CFG_SPD | ENET_MAC_CFG_DPM | ENET_MAC_CFG_LBM)); + reg_value |= media_temp; + ENET_MAC_CFG = reg_value; + + + /* 2st, configure checksum */ + if(RESET != ((uint32_t)checksum & ENET_CHECKSUMOFFLOAD_ENABLE)) { + ENET_MAC_CFG |= ENET_CHECKSUMOFFLOAD_ENABLE; + + reg_value = ENET_DMA_CTL; + /* configure ENET_DMA_CTL register */ + reg_value &= ~ENET_DMA_CTL_DTCERFD; + reg_value |= ((uint32_t)checksum & ENET_DMA_CTL_DTCERFD); + ENET_DMA_CTL = reg_value; + } + + /* 3rd, configure recept */ + ENET_MAC_FRMF |= (uint32_t)recept; + + /* 4th, configure different function options */ + /* configure forward_frame related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)FORWARD_OPTION)) { + reg_temp = enet_initpara.forward_frame; + + reg_value = ENET_MAC_CFG; + temp = reg_temp; + /* configure ENET_MAC_CFG register */ + reg_value &= (~(ENET_MAC_CFG_TFCD | ENET_MAC_CFG_APCD)); + temp &= (ENET_MAC_CFG_TFCD | ENET_MAC_CFG_APCD); + reg_value |= temp; + ENET_MAC_CFG = reg_value; + + reg_value = ENET_DMA_CTL; + temp = reg_temp; + /* configure ENET_DMA_CTL register */ + reg_value &= (~(ENET_DMA_CTL_FERF | ENET_DMA_CTL_FUF)); + temp &= ((ENET_DMA_CTL_FERF | ENET_DMA_CTL_FUF) << 2); + reg_value |= (temp >> 2); + ENET_DMA_CTL = reg_value; + } + + /* configure dmabus_mode related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)DMABUS_OPTION)) { + temp = enet_initpara.dmabus_mode; + + reg_value = ENET_DMA_BCTL; + /* configure ENET_DMA_BCTL register */ + reg_value &= ~(ENET_DMA_BCTL_AA | ENET_DMA_BCTL_FB \ + | ENET_DMA_BCTL_FPBL | ENET_DMA_BCTL_MB); + reg_value |= temp; + ENET_DMA_BCTL = reg_value; + } + + /* configure dma_maxburst related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)DMA_MAXBURST_OPTION)) { + temp = enet_initpara.dma_maxburst; + + reg_value = ENET_DMA_BCTL; + /* configure ENET_DMA_BCTL register */ + reg_value &= ~(ENET_DMA_BCTL_RXDP | ENET_DMA_BCTL_PGBL | ENET_DMA_BCTL_UIP); + reg_value |= temp; + ENET_DMA_BCTL = reg_value; + } + + /* configure dma_arbitration related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)DMA_ARBITRATION_OPTION)) { + temp = enet_initpara.dma_arbitration; + + reg_value = ENET_DMA_BCTL; + /* configure ENET_DMA_BCTL register */ + reg_value &= ~(ENET_DMA_BCTL_RTPR | ENET_DMA_BCTL_DAB); + reg_value |= temp; + ENET_DMA_BCTL = reg_value; + } + + /* configure store_forward_mode related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)STORE_OPTION)) { + temp = enet_initpara.store_forward_mode; + + reg_value = ENET_DMA_CTL; + /* configure ENET_DMA_CTL register */ + reg_value &= ~(ENET_DMA_CTL_RSFD | ENET_DMA_CTL_TSFD | ENET_DMA_CTL_RTHC | ENET_DMA_CTL_TTHC); + reg_value |= temp; + ENET_DMA_CTL = reg_value; + } + + /* configure dma_function related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)DMA_OPTION)) { + reg_temp = enet_initpara.dma_function; + + reg_value = ENET_DMA_CTL; + temp = reg_temp; + /* configure ENET_DMA_CTL register */ + reg_value &= (~(ENET_DMA_CTL_DAFRF | ENET_DMA_CTL_OSF)); + temp &= (ENET_DMA_CTL_DAFRF | ENET_DMA_CTL_OSF); + reg_value |= temp; + ENET_DMA_CTL = reg_value; + + reg_value = ENET_DMA_BCTL; + temp = reg_temp; + /* configure ENET_DMA_BCTL register */ + reg_value &= (~ENET_DMA_BCTL_DFM); + temp &= ENET_DMA_BCTL_DFM; + reg_value |= temp; + ENET_DMA_BCTL = reg_value; + } + + /* configure vlan_config related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)VLAN_OPTION)) { + reg_temp = enet_initpara.vlan_config; + + reg_value = ENET_MAC_VLT; + /* configure ENET_MAC_VLT register */ + reg_value &= ~(ENET_MAC_VLT_VLTI | ENET_MAC_VLT_VLTC); + reg_value |= reg_temp; + ENET_MAC_VLT = reg_value; + } + + /* configure flow_control related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)FLOWCTL_OPTION)) { + reg_temp = enet_initpara.flow_control; + + reg_value = ENET_MAC_FCTL; + temp = reg_temp; + /* configure ENET_MAC_FCTL register */ + reg_value &= ~(ENET_MAC_FCTL_PTM | ENET_MAC_FCTL_DZQP | ENET_MAC_FCTL_PLTS \ + | ENET_MAC_FCTL_UPFDT | ENET_MAC_FCTL_RFCEN | ENET_MAC_FCTL_TFCEN); + temp &= (ENET_MAC_FCTL_PTM | ENET_MAC_FCTL_DZQP | ENET_MAC_FCTL_PLTS \ + | ENET_MAC_FCTL_UPFDT | ENET_MAC_FCTL_RFCEN | ENET_MAC_FCTL_TFCEN); + reg_value |= temp; + ENET_MAC_FCTL = reg_value; + + reg_value = ENET_MAC_FCTH; + temp = reg_temp; + /* configure ENET_MAC_FCTH register */ + reg_value &= ~(ENET_MAC_FCTH_RFA | ENET_MAC_FCTH_RFD); + temp &= ((ENET_MAC_FCTH_RFA | ENET_MAC_FCTH_RFD) << 8); + reg_value |= (temp >> 8); + ENET_MAC_FCTH = reg_value; + } + + /* configure hashtable_high related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)HASHH_OPTION)) { + ENET_MAC_HLH = enet_initpara.hashtable_high; + } + + /* configure hashtable_low related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)HASHL_OPTION)) { + ENET_MAC_HLL = enet_initpara.hashtable_low; + } + + /* configure framesfilter_mode related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)FILTER_OPTION)) { + reg_temp = enet_initpara.framesfilter_mode; + + reg_value = ENET_MAC_FRMF; + /* configure ENET_MAC_FRMF register */ + reg_value &= ~(ENET_MAC_FRMF_SAFLT | ENET_MAC_FRMF_SAIFLT | ENET_MAC_FRMF_DAIFLT \ + | ENET_MAC_FRMF_HMF | ENET_MAC_FRMF_HPFLT | ENET_MAC_FRMF_MFD \ + | ENET_MAC_FRMF_HUF | ENET_MAC_FRMF_PCFRM); + reg_value |= reg_temp; + ENET_MAC_FRMF = reg_value; + } + + /* configure halfduplex_param related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)HALFDUPLEX_OPTION)) { + reg_temp = enet_initpara.halfduplex_param; + + reg_value = ENET_MAC_CFG; + /* configure ENET_MAC_CFG register */ + reg_value &= ~(ENET_MAC_CFG_CSD | ENET_MAC_CFG_ROD | ENET_MAC_CFG_RTD \ + | ENET_MAC_CFG_BOL | ENET_MAC_CFG_DFC); + reg_value |= reg_temp; + ENET_MAC_CFG = reg_value; + } + + /* configure timer_config related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)TIMER_OPTION)) { + reg_temp = enet_initpara.timer_config; + + reg_value = ENET_MAC_CFG; + /* configure ENET_MAC_CFG register */ + reg_value &= ~(ENET_MAC_CFG_WDD | ENET_MAC_CFG_JBD); + reg_value |= reg_temp; + ENET_MAC_CFG = reg_value; + } + + /* configure interframegap related registers */ + if(RESET != (enet_initpara.option_enable & (uint32_t)INTERFRAMEGAP_OPTION)) { + reg_temp = enet_initpara.interframegap; + + reg_value = ENET_MAC_CFG; + /* configure ENET_MAC_CFG register */ + reg_value &= ~ENET_MAC_CFG_IGBS; + reg_value |= reg_temp; + ENET_MAC_CFG = reg_value; + } + + enet_state = SUCCESS; + return enet_state; +} + +/*! + \brief reset all core internal registers located in CLK_TX and CLK_RX + \param[in] none + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_software_reset(void) +{ + uint32_t timeout = 0U; + ErrStatus enet_state = ERROR; + uint32_t dma_flag; + + /* reset all core internal registers located in CLK_TX and CLK_RX */ + ENET_DMA_BCTL |= ENET_DMA_BCTL_SWR; + + /* wait for reset operation complete */ + do { + dma_flag = (ENET_DMA_BCTL & ENET_DMA_BCTL_SWR); + timeout++; + } while((RESET != dma_flag) && (ENET_DELAY_TO != timeout)); + + /* reset operation complete */ + if(RESET == (ENET_DMA_BCTL & ENET_DMA_BCTL_SWR)) { + enet_state = SUCCESS; + } + + return enet_state; +} + +/*! + \brief check receive frame valid and return frame size + \param[in] none + \param[out] none + \retval size of received frame: 0x0 - 0x3FFF +*/ +uint32_t enet_rxframe_size_get(void) +{ + uint32_t size = 0U; + uint32_t status; + + /* get rdes0 information of current RxDMA descriptor */ + status = dma_current_rxdesc->status; + + /* if the desciptor is owned by DMA */ + if((uint32_t)RESET != (status & ENET_RDES0_DAV)) { + return 0U; + } + + /* if has any error, or the frame uses two or more descriptors */ + if((((uint32_t)RESET) != (status & ENET_RDES0_ERRS)) || + (((uint32_t)RESET) == (status & ENET_RDES0_LDES)) || + (((uint32_t)RESET) == (status & ENET_RDES0_FDES))) { + /* drop current receive frame */ + enet_rxframe_drop(); + + return 1U; + } +#ifdef SELECT_DESCRIPTORS_ENHANCED_MODE + /* if is an ethernet-type frame, and IP frame payload error occurred */ + if(((uint32_t)RESET) != (dma_current_rxdesc->status & ENET_RDES0_FRMT) && + ((uint32_t)RESET) != (dma_current_rxdesc->extended_status & ENET_RDES4_IPPLDERR)) { + /* drop current receive frame */ + enet_rxframe_drop(); + + return 1U; + } +#else + /* if is an ethernet-type frame, and IP frame payload error occurred */ + if((((uint32_t)RESET) != (status & ENET_RDES0_FRMT)) && + (((uint32_t)RESET) != (status & ENET_RDES0_PCERR))) { + /* drop current receive frame */ + enet_rxframe_drop(); + + return 1U; + } +#endif + /* if CPU owns current descriptor, no error occured, the frame uses only one descriptor */ + if((((uint32_t)RESET) == (status & ENET_RDES0_DAV)) && + (((uint32_t)RESET) == (status & ENET_RDES0_ERRS)) && + (((uint32_t)RESET) != (status & ENET_RDES0_LDES)) && + (((uint32_t)RESET) != (status & ENET_RDES0_FDES))) { + /* get the size of the received data including CRC */ + size = GET_RDES0_FRML(status); + /* substract the CRC size */ + size = size - 4U; + + /* if is a type frame, and CRC is not included in forwarding frame */ + if((RESET != (ENET_MAC_CFG & ENET_MAC_CFG_TFCD)) && (RESET != (status & ENET_RDES0_FRMT))) { + size = size + 4U; + } + } else { + enet_unknow_err++; + enet_rxframe_drop(); + + return 1U; + } + + /* return packet size */ + return size; +} + +/*! + \brief initialize the DMA Tx/Rx descriptors's parameters in chain mode + \param[in] direction: the descriptors which users want to init, refer to enet_dmadirection_enum + only one parameter can be selected which is shown as below + \arg ENET_DMA_TX: DMA Tx descriptors + \arg ENET_DMA_RX: DMA Rx descriptors + \param[out] none + \retval none +*/ +void enet_descriptors_chain_init(enet_dmadirection_enum direction) +{ + uint32_t num = 0U, count = 0U, maxsize = 0U; + uint32_t desc_status = 0U, desc_bufsize = 0U; + enet_descriptors_struct *desc, *desc_tab; + uint8_t *buf; + + /* if want to initialize DMA Tx descriptors */ + if(ENET_DMA_TX == direction) { + /* save a copy of the DMA Tx descriptors */ + desc_tab = txdesc_tab; + buf = &tx_buff[0][0]; + count = ENET_TXBUF_NUM; + maxsize = ENET_TXBUF_SIZE; + + /* select chain mode */ + desc_status = ENET_TDES0_TCHM; + + /* configure DMA Tx descriptor table address register */ + ENET_DMA_TDTADDR = (uint32_t)desc_tab; + dma_current_txdesc = desc_tab; + } else { + /* if want to initialize DMA Rx descriptors */ + /* save a copy of the DMA Rx descriptors */ + desc_tab = rxdesc_tab; + buf = &rx_buff[0][0]; + count = ENET_RXBUF_NUM; + maxsize = ENET_RXBUF_SIZE; + + /* enable receiving */ + desc_status = ENET_RDES0_DAV; + /* select receive chained mode and set buffer1 size */ + desc_bufsize = ENET_RDES1_RCHM | (uint32_t)ENET_RXBUF_SIZE; + + /* configure DMA Rx descriptor table address register */ + ENET_DMA_RDTADDR = (uint32_t)desc_tab; + dma_current_rxdesc = desc_tab; + } + dma_current_ptp_rxdesc = NULL; + dma_current_ptp_txdesc = NULL; + + /* configure each descriptor */ + for(num = 0U; num < count; num++) { + /* get the pointer to the next descriptor of the descriptor table */ + desc = desc_tab + num; + + /* configure descriptors */ + desc->status = desc_status; + desc->control_buffer_size = desc_bufsize; + desc->buffer1_addr = (uint32_t)(&buf[num * maxsize]); + + /* if is not the last descriptor */ + if(num < (count - 1U)) { + /* configure the next descriptor address */ + desc->buffer2_next_desc_addr = (uint32_t)(desc_tab + num + 1U); + } else { + /* when it is the last descriptor, the next descriptor address + equals to first descriptor address in descriptor table */ + desc->buffer2_next_desc_addr = (uint32_t) desc_tab; + } + } +} + +/*! + \brief initialize the DMA Tx/Rx descriptors's parameters in ring mode + \param[in] direction: the descriptors which users want to init, refer to enet_dmadirection_enum + only one parameter can be selected which is shown as below + \arg ENET_DMA_TX: DMA Tx descriptors + \arg ENET_DMA_RX: DMA Rx descriptors + \param[out] none + \retval none +*/ +void enet_descriptors_ring_init(enet_dmadirection_enum direction) +{ + uint32_t num = 0U, count = 0U, maxsize = 0U; + uint32_t desc_status = 0U, desc_bufsize = 0U; + enet_descriptors_struct *desc; + enet_descriptors_struct *desc_tab; + uint8_t *buf; + + /* configure descriptor skip length */ + ENET_DMA_BCTL &= ~ENET_DMA_BCTL_DPSL; + ENET_DMA_BCTL |= DMA_BCTL_DPSL(0); + + /* if want to initialize DMA Tx descriptors */ + if(ENET_DMA_TX == direction) { + /* save a copy of the DMA Tx descriptors */ + desc_tab = txdesc_tab; + buf = &tx_buff[0][0]; + count = ENET_TXBUF_NUM; + maxsize = ENET_TXBUF_SIZE; + + /* configure DMA Tx descriptor table address register */ + ENET_DMA_TDTADDR = (uint32_t)desc_tab; + dma_current_txdesc = desc_tab; + } else { + /* if want to initialize DMA Rx descriptors */ + /* save a copy of the DMA Rx descriptors */ + desc_tab = rxdesc_tab; + buf = &rx_buff[0][0]; + count = ENET_RXBUF_NUM; + maxsize = ENET_RXBUF_SIZE; + + /* enable receiving */ + desc_status = ENET_RDES0_DAV; + /* set buffer1 size */ + desc_bufsize = ENET_RXBUF_SIZE; + + /* configure DMA Rx descriptor table address register */ + ENET_DMA_RDTADDR = (uint32_t)desc_tab; + dma_current_rxdesc = desc_tab; + } + dma_current_ptp_rxdesc = NULL; + dma_current_ptp_txdesc = NULL; + + /* configure each descriptor */ + for(num = 0U; num < count; num++) { + /* get the pointer to the next descriptor of the descriptor table */ + desc = desc_tab + num; + + /* configure descriptors */ + desc->status = desc_status; + desc->control_buffer_size = desc_bufsize; + desc->buffer1_addr = (uint32_t)(&buf[num * maxsize]); + + /* when it is the last descriptor */ + if(num == (count - 1U)) { + if(ENET_DMA_TX == direction) { + /* configure transmit end of ring mode */ + desc->status |= ENET_TDES0_TERM; + } else { + /* configure receive end of ring mode */ + desc->control_buffer_size |= ENET_RDES1_RERM; + } + } + } +} + +/*! + \brief handle current received frame data to application buffer + \param[in] bufsize: the size of buffer which is the parameter in function + \param[out] buffer: pointer to the received frame data + note -- if the input is NULL, user should copy data in application by himself + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_frame_receive(uint8_t *buffer, uint32_t bufsize) +{ + uint32_t offset = 0U, size = 0U; + + /* the descriptor is busy due to own by the DMA */ + if((uint32_t)RESET != (dma_current_rxdesc->status & ENET_RDES0_DAV)) { + return ERROR; + } + + + /* if buffer pointer is null, indicates that users has copied data in application */ + if(NULL != buffer) { + /* if no error occurs, and the frame uses only one descriptor */ + if((((uint32_t)RESET) == (dma_current_rxdesc->status & ENET_RDES0_ERRS)) && + (((uint32_t)RESET) != (dma_current_rxdesc->status & ENET_RDES0_LDES)) && + (((uint32_t)RESET) != (dma_current_rxdesc->status & ENET_RDES0_FDES))) { + /* get the frame length except CRC */ + size = GET_RDES0_FRML(dma_current_rxdesc->status); + size = size - 4U; + + /* if is a type frame, and CRC is not included in forwarding frame */ + if((RESET != (ENET_MAC_CFG & ENET_MAC_CFG_TFCD)) && (RESET != (dma_current_rxdesc->status & ENET_RDES0_FRMT))) { + size = size + 4U; + } + + /* to avoid situation that the frame size exceeds the buffer length */ + if(size > bufsize) { + return ERROR; + } + + /* copy data from Rx buffer to application buffer */ + for(offset = 0U; offset < size; offset++) { + (*(buffer + offset)) = (*(__IO uint8_t *)(uint32_t)((dma_current_rxdesc->buffer1_addr) + offset)); + } + + } else { + /* return ERROR */ + return ERROR; + } + } + /* enable reception, descriptor is owned by DMA */ + dma_current_rxdesc->status = ENET_RDES0_DAV; + + /* check Rx buffer unavailable flag status */ + if((uint32_t)RESET != (ENET_DMA_STAT & ENET_DMA_STAT_RBU)) { + /* clear RBU flag */ + ENET_DMA_STAT = ENET_DMA_STAT_RBU; + /* resume DMA reception by writing to the RPEN register*/ + ENET_DMA_RPEN = 0U; + } + + /* update the current RxDMA descriptor pointer to the next decriptor in RxDMA decriptor table */ + /* chained mode */ + if((uint32_t)RESET != (dma_current_rxdesc->control_buffer_size & ENET_RDES1_RCHM)) { + dma_current_rxdesc = (enet_descriptors_struct *)(dma_current_rxdesc->buffer2_next_desc_addr); + } else { + /* ring mode */ + if((uint32_t)RESET != (dma_current_rxdesc->control_buffer_size & ENET_RDES1_RERM)) { + /* if is the last descriptor in table, the next descriptor is the table header */ + dma_current_rxdesc = (enet_descriptors_struct *)(ENET_DMA_RDTADDR); + } else { + /* the next descriptor is the current address, add the descriptor size, and descriptor skip length */ + dma_current_rxdesc = (enet_descriptors_struct *)(uint32_t)((uint32_t)dma_current_rxdesc + ETH_DMARXDESC_SIZE + + (GET_DMA_BCTL_DPSL(ENET_DMA_BCTL))); + } + } + + return SUCCESS; +} + +/*! + \brief handle application buffer data to transmit it + \param[in] buffer: pointer to the frame data to be transmitted, + note -- if the input is NULL, user should handle the data in application by himself + \param[in] length: the length of frame data to be transmitted + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_frame_transmit(uint8_t *buffer, uint32_t length) +{ + uint32_t offset = 0U; + uint32_t dma_tbu_flag, dma_tu_flag; + + /* the descriptor is busy due to own by the DMA */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_DAV)) { + return ERROR; + } + + /* only frame length no more than ENET_MAX_FRAME_SIZE is allowed */ + if(length > ENET_MAX_FRAME_SIZE) { + return ERROR; + } + + /* if buffer pointer is null, indicates that users has handled data in application */ + if(NULL != buffer) { + /* copy frame data from application buffer to Tx buffer */ + for(offset = 0U; offset < length; offset++) { + (*(__IO uint8_t *)(uint32_t)((dma_current_txdesc->buffer1_addr) + offset)) = (*(buffer + offset)); + } + } + + /* set the frame length */ + dma_current_txdesc->control_buffer_size = length; + /* set the segment of frame, frame is transmitted in one descriptor */ + dma_current_txdesc->status |= ENET_TDES0_LSG | ENET_TDES0_FSG; + /* enable the DMA transmission */ + dma_current_txdesc->status |= ENET_TDES0_DAV; + + /* check Tx buffer unavailable flag status */ + dma_tbu_flag = (ENET_DMA_STAT & ENET_DMA_STAT_TBU); + dma_tu_flag = (ENET_DMA_STAT & ENET_DMA_STAT_TU); + + if((RESET != dma_tbu_flag) || (RESET != dma_tu_flag)) { + /* clear TBU and TU flag */ + ENET_DMA_STAT = (dma_tbu_flag | dma_tu_flag); + /* resume DMA transmission by writing to the TPEN register*/ + ENET_DMA_TPEN = 0U; + } + + /* update the current TxDMA descriptor pointer to the next decriptor in TxDMA decriptor table*/ + /* chained mode */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_TCHM)) { + dma_current_txdesc = (enet_descriptors_struct *)(dma_current_txdesc->buffer2_next_desc_addr); + } else { + /* ring mode */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_TERM)) { + /* if is the last descriptor in table, the next descriptor is the table header */ + dma_current_txdesc = (enet_descriptors_struct *)(ENET_DMA_TDTADDR); + } else { + /* the next descriptor is the current address, add the descriptor size, and descriptor skip length */ + dma_current_txdesc = (enet_descriptors_struct *)(uint32_t)((uint32_t)dma_current_txdesc + ETH_DMATXDESC_SIZE + + (GET_DMA_BCTL_DPSL(ENET_DMA_BCTL))); + } + } + + return SUCCESS; +} + +/*! + \brief configure the transmit IP frame checksum offload calculation and insertion + \param[in] desc: the descriptor pointer which users want to configure + \param[in] checksum: IP frame checksum configuration + only one parameter can be selected which is shown as below + \arg ENET_CHECKSUM_DISABLE: checksum insertion disabled + \arg ENET_CHECKSUM_IPV4HEADER: only IP header checksum calculation and insertion are enabled + \arg ENET_CHECKSUM_TCPUDPICMP_SEGMENT: TCP/UDP/ICMP checksum insertion calculated but pseudo-header + \arg ENET_CHECKSUM_TCPUDPICMP_FULL: TCP/UDP/ICMP checksum insertion fully calculated + \param[out] none + \retval ErrStatus: ERROR, SUCCESS +*/ +ErrStatus enet_transmit_checksum_config(enet_descriptors_struct *desc, uint32_t checksum) +{ + if(NULL != desc) { + desc->status &= ~ENET_TDES0_CM; + desc->status |= checksum; + return SUCCESS; + } else { + return ERROR; + } +} + +/*! + \brief ENET Tx and Rx function enable (include MAC and DMA module) + \param[in] none + \param[out] none + \retval none +*/ +void enet_enable(void) +{ + enet_tx_enable(); + enet_rx_enable(); +} + +/*! + \brief ENET Tx and Rx function disable (include MAC and DMA module) + \param[in] none + \param[out] none + \retval none +*/ +void enet_disable(void) +{ + enet_tx_disable(); + enet_rx_disable(); +} + +/*! + \brief configure MAC address + \param[in] mac_addr: select which MAC address will be set, + only one parameter can be selected which is shown as below + \arg ENET_MAC_ADDRESS0: set MAC address 0 filter + \arg ENET_MAC_ADDRESS1: set MAC address 1 filter + \arg ENET_MAC_ADDRESS2: set MAC address 2 filter + \arg ENET_MAC_ADDRESS3: set MAC address 3 filter + \param[in] paddr: the buffer pointer which stores the MAC address + (little-ending store, such as MAC address is aa:bb:cc:dd:ee:22, the buffer is {22, ee, dd, cc, bb, aa}) + \param[out] none + \retval none +*/ +void enet_mac_address_set(enet_macaddress_enum mac_addr, uint8_t paddr[]) +{ + REG32(ENET_ADDRH_BASE + (uint32_t)mac_addr) = ENET_SET_MACADDRH(paddr); + REG32(ENET_ADDRL_BASE + (uint32_t)mac_addr) = ENET_SET_MACADDRL(paddr); +} + +/*! + \brief get MAC address + \param[in] mac_addr: select which MAC address will be get, refer to enet_macaddress_enum + only one parameter can be selected which is shown as below + \arg ENET_MAC_ADDRESS0: get MAC address 0 filter + \arg ENET_MAC_ADDRESS1: get MAC address 1 filter + \arg ENET_MAC_ADDRESS2: get MAC address 2 filter + \arg ENET_MAC_ADDRESS3: get MAC address 3 filter + \param[out] paddr: the buffer pointer which is stored the MAC address + (little-ending store, such as mac address is aa:bb:cc:dd:ee:22, the buffer is {22, ee, dd, cc, bb, aa}) + \param[in] bufsize: refer to the size of the buffer which stores the MAC address + \arg 6 - 255 + \retval ErrStatus: ERROR, SUCCESS +*/ +ErrStatus enet_mac_address_get(enet_macaddress_enum mac_addr, uint8_t paddr[], uint8_t bufsize) +{ + if(bufsize < 6U) { + return ERROR; + } + paddr[0] = ENET_GET_MACADDR(mac_addr, 0U); + paddr[1] = ENET_GET_MACADDR(mac_addr, 1U); + paddr[2] = ENET_GET_MACADDR(mac_addr, 2U); + paddr[3] = ENET_GET_MACADDR(mac_addr, 3U); + paddr[4] = ENET_GET_MACADDR(mac_addr, 4U); + paddr[5] = ENET_GET_MACADDR(mac_addr, 5U); + return SUCCESS; +} + +/*! + \brief get the ENET MAC/MSC/PTP/DMA status flag + \param[in] enet_flag: ENET status flag, refer to enet_flag_enum, + only one parameter can be selected which is shown as below + \arg ENET_MAC_FLAG_MPKR: magic packet received flag + \arg ENET_MAC_FLAG_WUFR: wakeup frame received flag + \arg ENET_MAC_FLAG_FLOWCONTROL: flow control status flag + \arg ENET_MAC_FLAG_WUM: WUM status flag + \arg ENET_MAC_FLAG_MSC: MSC status flag + \arg ENET_MAC_FLAG_MSCR: MSC receive status flag + \arg ENET_MAC_FLAG_MSCT: MSC transmit status flag + \arg ENET_MAC_FLAG_TMST: time stamp trigger status flag + \arg ENET_PTP_FLAG_TSSCO: timestamp second counter overflow flag + \arg ENET_PTP_FLAG_TTM: target time match flag + \arg ENET_MSC_FLAG_RFCE: received frames CRC error flag + \arg ENET_MSC_FLAG_RFAE: received frames alignment error flag + \arg ENET_MSC_FLAG_RGUF: received good unicast frames flag + \arg ENET_MSC_FLAG_TGFSC: transmitted good frames single collision flag + \arg ENET_MSC_FLAG_TGFMSC: transmitted good frames more single collision flag + \arg ENET_MSC_FLAG_TGF: transmitted good frames flag + \arg ENET_DMA_FLAG_TS: transmit status flag + \arg ENET_DMA_FLAG_TPS: transmit process stopped status flag + \arg ENET_DMA_FLAG_TBU: transmit buffer unavailable status flag + \arg ENET_DMA_FLAG_TJT: transmit jabber timeout status flag + \arg ENET_DMA_FLAG_RO: receive overflow status flag + \arg ENET_DMA_FLAG_TU: transmit underflow status flag + \arg ENET_DMA_FLAG_RS: receive status flag + \arg ENET_DMA_FLAG_RBU: receive buffer unavailable status flag + \arg ENET_DMA_FLAG_RPS: receive process stopped status flag + \arg ENET_DMA_FLAG_RWT: receive watchdog timeout status flag + \arg ENET_DMA_FLAG_ET: early transmit status flag + \arg ENET_DMA_FLAG_FBE: fatal bus error status flag + \arg ENET_DMA_FLAG_ER: early receive status flag + \arg ENET_DMA_FLAG_AI: abnormal interrupt summary flag + \arg ENET_DMA_FLAG_NI: normal interrupt summary flag + \arg ENET_DMA_FLAG_EB_DMA_ERROR: DMA error flag + \arg ENET_DMA_FLAG_EB_TRANSFER_ERROR: transfer error flag + \arg ENET_DMA_FLAG_EB_ACCESS_ERROR: access error flag + \arg ENET_DMA_FLAG_MSC: MSC status flag + \arg ENET_DMA_FLAG_WUM: WUM status flag + \arg ENET_DMA_FLAG_TST: timestamp trigger status flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus enet_flag_get(enet_flag_enum enet_flag) +{ + if(RESET != (ENET_REG_VAL(enet_flag) & BIT(ENET_BIT_POS(enet_flag)))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear the ENET DMA status flag + \param[in] enet_flag: ENET DMA flag clear, refer to enet_flag_clear_enum + only one parameter can be selected which is shown as below + \arg ENET_DMA_FLAG_TS_CLR: transmit status flag clear + \arg ENET_DMA_FLAG_TPS_CLR: transmit process stopped status flag clear + \arg ENET_DMA_FLAG_TBU_CLR: transmit buffer unavailable status flag clear + \arg ENET_DMA_FLAG_TJT_CLR: transmit jabber timeout status flag clear + \arg ENET_DMA_FLAG_RO_CLR: receive overflow status flag clear + \arg ENET_DMA_FLAG_TU_CLR: transmit underflow status flag clear + \arg ENET_DMA_FLAG_RS_CLR: receive status flag clear + \arg ENET_DMA_FLAG_RBU_CLR: receive buffer unavailable status flag clear + \arg ENET_DMA_FLAG_RPS_CLR: receive process stopped status flag clear + \arg ENET_DMA_FLAG_RWT_CLR: receive watchdog timeout status flag clear + \arg ENET_DMA_FLAG_ET_CLR: early transmit status flag clear + \arg ENET_DMA_FLAG_FBE_CLR: fatal bus error status flag clear + \arg ENET_DMA_FLAG_ER_CLR: early receive status flag clear + \arg ENET_DMA_FLAG_AI_CLR: abnormal interrupt summary flag clear + \arg ENET_DMA_FLAG_NI_CLR: normal interrupt summary flag clear + \param[out] none + \retval none +*/ +void enet_flag_clear(enet_flag_clear_enum enet_flag) +{ + /* write 1 to the corresponding bit in ENET_DMA_STAT, to clear it */ + ENET_REG_VAL(enet_flag) = BIT(ENET_BIT_POS(enet_flag)); +} + +/*! + \brief enable ENET MAC/MSC/DMA interrupt + \param[in] enet_int: ENET interrupt,, refer to enet_int_enum + only one parameter can be selected which is shown as below + \arg ENET_MAC_INT_WUMIM: WUM interrupt mask + \arg ENET_MAC_INT_TMSTIM: timestamp trigger interrupt mask + \arg ENET_MSC_INT_RFCEIM: received frame CRC error interrupt mask + \arg ENET_MSC_INT_RFAEIM: received frames alignment error interrupt mask + \arg ENET_MSC_INT_RGUFIM: received good unicast frames interrupt mask + \arg ENET_MSC_INT_TGFSCIM: transmitted good frames single collision interrupt mask + \arg ENET_MSC_INT_TGFMSCIM: transmitted good frames more single collision interrupt mask + \arg ENET_MSC_INT_TGFIM: transmitted good frames interrupt mask + \arg ENET_DMA_INT_TIE: transmit interrupt enable + \arg ENET_DMA_INT_TPSIE: transmit process stopped interrupt enable + \arg ENET_DMA_INT_TBUIE: transmit buffer unavailable interrupt enable + \arg ENET_DMA_INT_TJTIE: transmit jabber timeout interrupt enable + \arg ENET_DMA_INT_ROIE: receive overflow interrupt enable + \arg ENET_DMA_INT_TUIE: transmit underflow interrupt enable + \arg ENET_DMA_INT_RIE: receive interrupt enable + \arg ENET_DMA_INT_RBUIE: receive buffer unavailable interrupt enable + \arg ENET_DMA_INT_RPSIE: receive process stopped interrupt enable + \arg ENET_DMA_INT_RWTIE: receive watchdog timeout interrupt enable + \arg ENET_DMA_INT_ETIE: early transmit interrupt enable + \arg ENET_DMA_INT_FBEIE: fatal bus error interrupt enable + \arg ENET_DMA_INT_ERIE: early receive interrupt enable + \arg ENET_DMA_INT_AIE: abnormal interrupt summary enable + \arg ENET_DMA_INT_NIE: normal interrupt summary enable + \param[out] none + \retval none +*/ +void enet_interrupt_enable(enet_int_enum enet_int) +{ + if(DMA_INTEN_REG_OFFSET == ((uint32_t)enet_int >> 6)) { + /* ENET_DMA_INTEN register interrupt */ + ENET_REG_VAL(enet_int) |= BIT(ENET_BIT_POS(enet_int)); + } else { + /* other INTMSK register interrupt */ + ENET_REG_VAL(enet_int) &= ~BIT(ENET_BIT_POS(enet_int)); + } +} + +/*! + \brief disable ENET MAC/MSC/DMA interrupt + \param[in] enet_int: ENET interrupt, + only one parameter can be selected which is shown as below + \arg ENET_MAC_INT_WUMIM: WUM interrupt mask + \arg ENET_MAC_INT_TMSTIM: timestamp trigger interrupt mask + \arg ENET_MSC_INT_RFCEIM: received frame CRC error interrupt mask + \arg ENET_MSC_INT_RFAEIM: received frames alignment error interrupt mask + \arg ENET_MSC_INT_RGUFIM: received good unicast frames interrupt mask + \arg ENET_MSC_INT_TGFSCIM: transmitted good frames single collision interrupt mask + \arg ENET_MSC_INT_TGFMSCIM: transmitted good frames more single collision interrupt mask + \arg ENET_MSC_INT_TGFIM: transmitted good frames interrupt mask + \arg ENET_DMA_INT_TIE: transmit interrupt enable + \arg ENET_DMA_INT_TPSIE: transmit process stopped interrupt enable + \arg ENET_DMA_INT_TBUIE: transmit buffer unavailable interrupt enable + \arg ENET_DMA_INT_TJTIE: transmit jabber timeout interrupt enable + \arg ENET_DMA_INT_ROIE: receive overflow interrupt enable + \arg ENET_DMA_INT_TUIE: transmit underflow interrupt enable + \arg ENET_DMA_INT_RIE: receive interrupt enable + \arg ENET_DMA_INT_RBUIE: receive buffer unavailable interrupt enable + \arg ENET_DMA_INT_RPSIE: receive process stopped interrupt enable + \arg ENET_DMA_INT_RWTIE: receive watchdog timeout interrupt enable + \arg ENET_DMA_INT_ETIE: early transmit interrupt enable + \arg ENET_DMA_INT_FBEIE: fatal bus error interrupt enable + \arg ENET_DMA_INT_ERIE: early receive interrupt enable + \arg ENET_DMA_INT_AIE: abnormal interrupt summary enable + \arg ENET_DMA_INT_NIE: normal interrupt summary enable + \param[out] none + \retval none +*/ +void enet_interrupt_disable(enet_int_enum enet_int) +{ + if(DMA_INTEN_REG_OFFSET == ((uint32_t)enet_int >> 6)) { + /* ENET_DMA_INTEN register interrupt */ + ENET_REG_VAL(enet_int) &= ~BIT(ENET_BIT_POS(enet_int)); + } else { + /* other INTMSK register interrupt */ + ENET_REG_VAL(enet_int) |= BIT(ENET_BIT_POS(enet_int)); + } +} + +/*! + \brief get ENET MAC/MSC/DMA interrupt flag + \param[in] int_flag: ENET interrupt flag, + only one parameter can be selected which is shown as below + \arg ENET_MAC_INT_FLAG_WUM: WUM status flag + \arg ENET_MAC_INT_FLAG_MSC: MSC status flag + \arg ENET_MAC_INT_FLAG_MSCR: MSC receive status flag + \arg ENET_MAC_INT_FLAG_MSCT: MSC transmit status flag + \arg ENET_MAC_INT_FLAG_TMST: time stamp trigger status flag + \arg ENET_MSC_INT_FLAG_RFCE: received frames CRC error flag + \arg ENET_MSC_INT_FLAG_RFAE: received frames alignment error flag + \arg ENET_MSC_INT_FLAG_RGUF: received good unicast frames flag + \arg ENET_MSC_INT_FLAG_TGFSC: transmitted good frames single collision flag + \arg ENET_MSC_INT_FLAG_TGFMSC: transmitted good frames more single collision flag + \arg ENET_MSC_INT_FLAG_TGF: transmitted good frames flag + \arg ENET_DMA_INT_FLAG_TS: transmit status flag + \arg ENET_DMA_INT_FLAG_TPS: transmit process stopped status flag + \arg ENET_DMA_INT_FLAG_TBU: transmit buffer unavailable status flag + \arg ENET_DMA_INT_FLAG_TJT: transmit jabber timeout status flag + \arg ENET_DMA_INT_FLAG_RO: receive overflow status flag + \arg ENET_DMA_INT_FLAG_TU: transmit underflow status flag + \arg ENET_DMA_INT_FLAG_RS: receive status flag + \arg ENET_DMA_INT_FLAG_RBU: receive buffer unavailable status flag + \arg ENET_DMA_INT_FLAG_RPS: receive process stopped status flag + \arg ENET_DMA_INT_FLAG_RWT: receive watchdog timeout status flag + \arg ENET_DMA_INT_FLAG_ET: early transmit status flag + \arg ENET_DMA_INT_FLAG_FBE: fatal bus error status flag + \arg ENET_DMA_INT_FLAG_ER: early receive status flag + \arg ENET_DMA_INT_FLAG_AI: abnormal interrupt summary flag + \arg ENET_DMA_INT_FLAG_NI: normal interrupt summary flag + \arg ENET_DMA_INT_FLAG_MSC: MSC status flag + \arg ENET_DMA_INT_FLAG_WUM: WUM status flag + \arg ENET_DMA_INT_FLAG_TST: timestamp trigger status flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus enet_interrupt_flag_get(enet_int_flag_enum int_flag) +{ + if(RESET != (ENET_REG_VAL(int_flag) & BIT(ENET_BIT_POS(int_flag)))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear ENET DMA interrupt flag + \param[in] int_flag_clear: clear ENET interrupt flag, + only one parameter can be selected which is shown as below + \arg ENET_DMA_INT_FLAG_TS_CLR: transmit status flag + \arg ENET_DMA_INT_FLAG_TPS_CLR: transmit process stopped status flag + \arg ENET_DMA_INT_FLAG_TBU_CLR: transmit buffer unavailable status flag + \arg ENET_DMA_INT_FLAG_TJT_CLR: transmit jabber timeout status flag + \arg ENET_DMA_INT_FLAG_RO_CLR: receive overflow status flag + \arg ENET_DMA_INT_FLAG_TU_CLR: transmit underflow status flag + \arg ENET_DMA_INT_FLAG_RS_CLR: receive status flag + \arg ENET_DMA_INT_FLAG_RBU_CLR: receive buffer unavailable status flag + \arg ENET_DMA_INT_FLAG_RPS_CLR: receive process stopped status flag + \arg ENET_DMA_INT_FLAG_RWT_CLR: receive watchdog timeout status flag + \arg ENET_DMA_INT_FLAG_ET_CLR: early transmit status flag + \arg ENET_DMA_INT_FLAG_FBE_CLR: fatal bus error status flag + \arg ENET_DMA_INT_FLAG_ER_CLR: early receive status flag + \arg ENET_DMA_INT_FLAG_AI_CLR: abnormal interrupt summary flag + \arg ENET_DMA_INT_FLAG_NI_CLR: normal interrupt summary flag + \param[out] none + \retval none +*/ +void enet_interrupt_flag_clear(enet_int_flag_clear_enum int_flag_clear) +{ + /* write 1 to the corresponding bit in ENET_DMA_STAT, to clear it */ + ENET_REG_VAL(int_flag_clear) = BIT(ENET_BIT_POS(int_flag_clear)); +} + +/*! + \brief ENET Tx function enable (include MAC and DMA module) + \param[in] none + \param[out] none + \retval none +*/ +void enet_tx_enable(void) +{ + ENET_MAC_CFG |= ENET_MAC_CFG_TEN; + enet_txfifo_flush(); + ENET_DMA_CTL |= ENET_DMA_CTL_STE; +} + +/*! + \brief ENET Tx function disable (include MAC and DMA module) + \param[in] none + \param[out] none + \retval none +*/ +void enet_tx_disable(void) +{ + ENET_DMA_CTL &= ~ENET_DMA_CTL_STE; + enet_txfifo_flush(); + ENET_MAC_CFG &= ~ENET_MAC_CFG_TEN; +} + +/*! + \brief ENET Rx function enable (include MAC and DMA module) + \param[in] none + \param[out] none + \retval none +*/ +void enet_rx_enable(void) +{ + ENET_MAC_CFG |= ENET_MAC_CFG_REN; + ENET_DMA_CTL |= ENET_DMA_CTL_SRE; +} + +/*! + \brief ENET Rx function disable (include MAC and DMA module) + \param[in] none + \param[out] none + \retval none +*/ +void enet_rx_disable(void) +{ + ENET_DMA_CTL &= ~ENET_DMA_CTL_SRE; + ENET_MAC_CFG &= ~ENET_MAC_CFG_REN; +} + +/*! + \brief put registers value into the application buffer + \param[in] type: register type which will be get, refer to enet_registers_type_enum, + only one parameter can be selected which is shown as below + \arg ALL_MAC_REG: get the registers within the offset scope between ENET_MAC_CFG and ENET_MAC_FCTH + \arg ALL_MSC_REG: get the registers within the offset scope between ENET_MSC_CTL and ENET_MSC_RGUFCNT + \arg ALL_PTP_REG: get the registers within the offset scope between ENET_PTP_TSCTL and ENET_PTP_PPSCTL + \arg ALL_DMA_REG: get the registers within the offset scope between ENET_DMA_BCTL and ENET_DMA_CRBADDR + \param[in] num: the number of registers that the user want to get + \param[out] preg: the application buffer pointer for storing the register value + \retval none +*/ +void enet_registers_get(enet_registers_type_enum type, uint32_t *preg, uint32_t num) +{ + uint32_t offset = 0U, max = 0U, limit = 0U; + + offset = (uint32_t)type; + max = (uint32_t)type + num; + limit = sizeof(enet_reg_tab) / sizeof(uint16_t); + + /* prevent element in this array is out of range */ + if(max > limit) { + max = limit; + } + + for(; offset < max; offset++) { + /* get value of the corresponding register */ + *preg = REG32((ENET) + enet_reg_tab[offset]); + preg++; + } +} + +/*! + \brief get the enet debug status from the debug register + \param[in] mac_debug: enet debug status + only one parameter can be selected which is shown as below + \arg ENET_MAC_RECEIVER_NOT_IDLE: MAC receiver is not in idle state + \arg ENET_RX_ASYNCHRONOUS_FIFO_STATE: Rx asynchronous FIFO status + \arg ENET_RXFIFO_WRITING: RxFIFO is doing write operation + \arg ENET_RXFIFO_READ_STATUS: RxFIFO read operation status + \arg ENET_RXFIFO_STATE: RxFIFO state + \arg ENET_MAC_TRANSMITTER_NOT_IDLE: MAC transmitter is not in idle state + \arg ENET_MAC_TRANSMITTER_STATUS: status of MAC transmitter + \arg ENET_PAUSE_CONDITION_STATUS: pause condition status + \arg ENET_TXFIFO_READ_STATUS: TxFIFO read operation status + \arg ENET_TXFIFO_WRITING: TxFIFO is doing write operation + \arg ENET_TXFIFO_NOT_EMPTY: TxFIFO is not empty + \arg ENET_TXFIFO_FULL: TxFIFO is full + \param[out] none + \retval value of the status users want to get +*/ +uint32_t enet_debug_status_get(uint32_t mac_debug) +{ + uint32_t temp_state = 0U; + + switch(mac_debug) { + case ENET_RX_ASYNCHRONOUS_FIFO_STATE: + temp_state = GET_MAC_DBG_RXAFS(ENET_MAC_DBG); + break; + case ENET_RXFIFO_READ_STATUS: + temp_state = GET_MAC_DBG_RXFRS(ENET_MAC_DBG); + break; + case ENET_RXFIFO_STATE: + temp_state = GET_MAC_DBG_RXFS(ENET_MAC_DBG); + break; + case ENET_MAC_TRANSMITTER_STATUS: + temp_state = GET_MAC_DBG_SOMT(ENET_MAC_DBG); + break; + case ENET_TXFIFO_READ_STATUS: + temp_state = GET_MAC_DBG_TXFRS(ENET_MAC_DBG); + break; + default: + if(RESET != (ENET_MAC_DBG & mac_debug)) { + temp_state = 0x1U; + } + break; + } + return temp_state; +} + +/*! + \brief enable the MAC address filter + \param[in] mac_addr: select which MAC address will be enable + \arg ENET_MAC_ADDRESS1: enable MAC address 1 filter + \arg ENET_MAC_ADDRESS2: enable MAC address 2 filter + \arg ENET_MAC_ADDRESS3: enable MAC address 3 filter + \param[out] none + \retval none +*/ +void enet_address_filter_enable(enet_macaddress_enum mac_addr) +{ + REG32(ENET_ADDRH_BASE + mac_addr) |= ENET_MAC_ADDR1H_AFE; +} + +/*! + \brief disable the MAC address filter + \param[in] mac_addr: select which MAC address will be disable, + only one parameter can be selected which is shown as below + \arg ENET_MAC_ADDRESS1: disable MAC address 1 filter + \arg ENET_MAC_ADDRESS2: disable MAC address 2 filter + \arg ENET_MAC_ADDRESS3: disable MAC address 3 filter + \param[out] none + \retval none +*/ +void enet_address_filter_disable(enet_macaddress_enum mac_addr) +{ + REG32(ENET_ADDRH_BASE + mac_addr) &= ~ENET_MAC_ADDR1H_AFE; +} + +/*! + \brief configure the MAC address filter + \param[in] mac_addr: select which MAC address will be configured, + only one parameter can be selected which is shown as below + \arg ENET_MAC_ADDRESS1: configure MAC address 1 filter + \arg ENET_MAC_ADDRESS2: configure MAC address 2 filter + \arg ENET_MAC_ADDRESS3: configure MAC address 3 filter + \param[in] addr_mask: select which MAC address bytes will be mask, + one or more parameters can be selected which are shown as below + \arg ENET_ADDRESS_MASK_BYTE0: mask ENET_MAC_ADDR1L[7:0] bits + \arg ENET_ADDRESS_MASK_BYTE1: mask ENET_MAC_ADDR1L[15:8] bits + \arg ENET_ADDRESS_MASK_BYTE2: mask ENET_MAC_ADDR1L[23:16] bits + \arg ENET_ADDRESS_MASK_BYTE3: mask ENET_MAC_ADDR1L [31:24] bits + \arg ENET_ADDRESS_MASK_BYTE4: mask ENET_MAC_ADDR1H [7:0] bits + \arg ENET_ADDRESS_MASK_BYTE5: mask ENET_MAC_ADDR1H [15:8] bits + \param[in] filter_type: select which MAC address filter type will be selected, + only one parameter can be selected which is shown as below + \arg ENET_ADDRESS_FILTER_SA: The MAC address is used to compared with the SA field of the received frame + \arg ENET_ADDRESS_FILTER_DA: The MAC address is used to compared with the DA field of the received frame + \param[out] none + \retval none +*/ +void enet_address_filter_config(enet_macaddress_enum mac_addr, uint32_t addr_mask, uint32_t filter_type) +{ + uint32_t reg; + + /* get the address filter register value which is to be configured */ + reg = REG32(ENET_ADDRH_BASE + mac_addr); + + /* clear and configure the address filter register */ + reg &= ~(ENET_MAC_ADDR1H_MB | ENET_MAC_ADDR1H_SAF); + reg |= (addr_mask | filter_type); + REG32(ENET_ADDRH_BASE + mac_addr) = reg; +} + +/*! + \brief PHY interface configuration (configure SMI clock and reset PHY chip) + \param[in] none + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_phy_config(void) +{ + uint32_t ahbclk; + uint32_t reg; + uint16_t phy_value; + ErrStatus enet_state = ERROR; + + /* clear the previous MDC clock */ + reg = ENET_MAC_PHY_CTL; + reg &= ~ENET_MAC_PHY_CTL_CLR; + + /* get the HCLK frequency */ + ahbclk = rcu_clock_freq_get(CK_AHB); + + /* configure MDC clock according to HCLK frequency range */ + if(ENET_RANGE(ahbclk, 20000000U, 35000000U)) { + reg |= ENET_MDC_HCLK_DIV16; + } else if(ENET_RANGE(ahbclk, 35000000U, 60000000U)) { + reg |= ENET_MDC_HCLK_DIV26; + } else if(ENET_RANGE(ahbclk, 60000000U, 100000000U)) { + reg |= ENET_MDC_HCLK_DIV42; + } else if(ENET_RANGE(ahbclk, 100000000U, 150000000U)) { + reg |= ENET_MDC_HCLK_DIV62; + } else if((ENET_RANGE(ahbclk, 150000000U, 200000000U)) || (200000000U == ahbclk)) { + reg |= ENET_MDC_HCLK_DIV102; + } else { + return enet_state; + } + ENET_MAC_PHY_CTL = reg; + + /* reset PHY */ + phy_value = PHY_RESET; + if(ERROR == (enet_phy_write_read(ENET_PHY_WRITE, PHY_ADDRESS, PHY_REG_BCR, &phy_value))) { + return enet_state; + } + /* PHY reset need some time */ + _ENET_DELAY_(ENET_DELAY_TO); + + /* check whether PHY reset is complete */ + if(ERROR == (enet_phy_write_read(ENET_PHY_READ, PHY_ADDRESS, PHY_REG_BCR, &phy_value))) { + return enet_state; + } + + /* PHY reset complete */ + if(RESET == (phy_value & PHY_RESET)) { + enet_state = SUCCESS; + } + + return enet_state; +} + +/*! + \brief write to / read from a PHY register + \param[in] direction: only one parameter can be selected which is shown as below, refer to enet_phydirection_enum + \arg ENET_PHY_WRITE: write data to phy register + \arg ENET_PHY_READ: read data from phy register + \param[in] phy_address: 0x0 - 0x1F + \param[in] phy_reg: 0x0 - 0x1F + \param[in] pvalue: the value will be written to the PHY register in ENET_PHY_WRITE direction + \param[out] pvalue: the value will be read from the PHY register in ENET_PHY_READ direction + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_phy_write_read(enet_phydirection_enum direction, uint16_t phy_address, uint16_t phy_reg, + uint16_t *pvalue) +{ + uint32_t reg, phy_flag; + uint32_t timeout = 0U; + ErrStatus enet_state = ERROR; + + /* configure ENET_MAC_PHY_CTL with write/read operation */ + reg = ENET_MAC_PHY_CTL; + reg &= ~(ENET_MAC_PHY_CTL_PB | ENET_MAC_PHY_CTL_PW | ENET_MAC_PHY_CTL_PR | ENET_MAC_PHY_CTL_PA); + reg |= (direction | MAC_PHY_CTL_PR(phy_reg) | MAC_PHY_CTL_PA(phy_address) | ENET_MAC_PHY_CTL_PB); + + /* if do the write operation, write value to the register */ + if(ENET_PHY_WRITE == direction) { + ENET_MAC_PHY_DATA = *pvalue; + } + + /* do PHY write/read operation, and wait the operation complete */ + ENET_MAC_PHY_CTL = reg; + do { + phy_flag = (ENET_MAC_PHY_CTL & ENET_MAC_PHY_CTL_PB); + timeout++; + } while((RESET != phy_flag) && (ENET_DELAY_TO != timeout)); + + /* write/read operation complete */ + if(RESET == (ENET_MAC_PHY_CTL & ENET_MAC_PHY_CTL_PB)) { + enet_state = SUCCESS; + } + + /* if do the read operation, get value from the register */ + if(ENET_PHY_READ == direction) { + *pvalue = (uint16_t)ENET_MAC_PHY_DATA; + } + + return enet_state; +} + +/*! + \brief enable the loopback function of PHY chip + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus enet_phyloopback_enable(void) +{ + uint16_t temp_phy = 0U; + ErrStatus phy_state = ERROR; + + /* get the PHY configuration to update it */ + enet_phy_write_read(ENET_PHY_READ, PHY_ADDRESS, PHY_REG_BCR, &temp_phy); + + /* enable the PHY loopback mode */ + temp_phy |= PHY_LOOPBACK; + + /* update the PHY control register with the new configuration */ + phy_state = enet_phy_write_read(ENET_PHY_WRITE, PHY_ADDRESS, PHY_REG_BCR, &temp_phy); + + return phy_state; +} + +/*! + \brief disable the loopback function of PHY chip + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus enet_phyloopback_disable(void) +{ + uint16_t temp_phy = 0U; + ErrStatus phy_state = ERROR; + + /* get the PHY configuration to update it */ + enet_phy_write_read(ENET_PHY_READ, PHY_ADDRESS, PHY_REG_BCR, &temp_phy); + + /* disable the PHY loopback mode */ + temp_phy &= (uint16_t)~PHY_LOOPBACK; + + /* update the PHY control register with the new configuration */ + phy_state = enet_phy_write_read(ENET_PHY_WRITE, PHY_ADDRESS, PHY_REG_BCR, &temp_phy); + + return phy_state; +} + +/*! + \brief enable ENET forward feature + \param[in] feature: the feature of ENET forward mode + one or more parameters can be selected which are shown as below + \arg ENET_AUTO_PADCRC_DROP: the function of the MAC strips the Pad/FCS field on received frames + \arg ENET_TYPEFRAME_CRC_DROP: the function that FCS field(last 4 bytes) of frame will be dropped before forwarding + \arg ENET_FORWARD_ERRFRAMES: the function that all frame received with error except runt error are forwarded to memory + \arg ENET_FORWARD_UNDERSZ_GOODFRAMES: the function that forwarding undersized good frames + \param[out] none + \retval none +*/ +void enet_forward_feature_enable(uint32_t feature) +{ + uint32_t mask; + + mask = (feature & (~(ENET_FORWARD_ERRFRAMES | ENET_FORWARD_UNDERSZ_GOODFRAMES))); + ENET_MAC_CFG |= mask; + + mask = (feature & (~(ENET_AUTO_PADCRC_DROP | ENET_TYPEFRAME_CRC_DROP))); + ENET_DMA_CTL |= (mask >> 2); +} + +/*! + \brief disable ENET forward feature + \param[in] feature: the feature of ENET forward mode + one or more parameters can be selected which are shown as below + \arg ENET_AUTO_PADCRC_DROP: the function of the MAC strips the Pad/FCS field on received frames + \arg ENET_TYPEFRAME_CRC_DROP: the function that FCS field(last 4 bytes) of frame will be dropped before forwarding + \arg ENET_FORWARD_ERRFRAMES: the function that all frame received with error except runt error are forwarded to memory + \arg ENET_FORWARD_UNDERSZ_GOODFRAMES: the function that forwarding undersized good frames + \param[out] none + \retval none +*/ +void enet_forward_feature_disable(uint32_t feature) +{ + uint32_t mask; + + mask = (feature & (~(ENET_FORWARD_ERRFRAMES | ENET_FORWARD_UNDERSZ_GOODFRAMES))); + ENET_MAC_CFG &= ~mask; + + mask = (feature & (~(ENET_AUTO_PADCRC_DROP | ENET_TYPEFRAME_CRC_DROP))); + ENET_DMA_CTL &= ~(mask >> 2); +} + +/*! + \brief enable ENET fliter feature + \param[in] feature: the feature of ENET fliter mode + one or more parameters can be selected which are shown as below + \arg ENET_SRC_FILTER: filter source address function + \arg ENET_SRC_FILTER_INVERSE: inverse source address filtering result function + \arg ENET_DEST_FILTER_INVERSE: inverse DA filtering result function + \arg ENET_MULTICAST_FILTER_PASS: pass all multicast frames function + \arg ENET_MULTICAST_FILTER_HASH_MODE: HASH multicast filter function + \arg ENET_UNICAST_FILTER_HASH_MODE: HASH unicast filter function + \arg ENET_FILTER_MODE_EITHER: HASH or perfect filter function + \param[out] none + \retval none +*/ +void enet_fliter_feature_enable(uint32_t feature) +{ + ENET_MAC_FRMF |= feature; +} + +/*! + \brief disable ENET fliter feature + \param[in] feature: the feature of ENET fliter mode + one or more parameters can be selected which are shown as below + \arg ENET_SRC_FILTER: filter source address function + \arg ENET_SRC_FILTER_INVERSE: inverse source address filtering result function + \arg ENET_DEST_FILTER_INVERSE: inverse DA filtering result function + \arg ENET_MULTICAST_FILTER_PASS: pass all multicast frames function + \arg ENET_MULTICAST_FILTER_HASH_MODE: HASH multicast filter function + \arg ENET_UNICAST_FILTER_HASH_MODE: HASH unicast filter function + \arg ENET_FILTER_MODE_EITHER: HASH or perfect filter function + \param[out] none + \retval none +*/ +void enet_fliter_feature_disable(uint32_t feature) +{ + ENET_MAC_FRMF &= ~feature; +} + +/*! + \brief generate the pause frame, ENET will send pause frame after enable transmit flow control + this function only use in full-dulex mode + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus enet_pauseframe_generate(void) +{ + ErrStatus enet_state = ERROR; + uint32_t temp = 0U; + + /* in full-duplex mode, must make sure this bit is 0 before writing register */ + temp = ENET_MAC_FCTL & ENET_MAC_FCTL_FLCBBKPA; + if(RESET == temp) { + ENET_MAC_FCTL |= ENET_MAC_FCTL_FLCBBKPA; + enet_state = SUCCESS; + } + return enet_state; +} + +/*! + \brief configure the pause frame detect type + \param[in] detect: pause frame detect type + only one parameter can be selected which is shown as below + \arg ENET_MAC0_AND_UNIQUE_ADDRESS_PAUSEDETECT: besides the unique multicast address, MAC can also + use the MAC0 address to detecting pause frame + \arg ENET_UNIQUE_PAUSEDETECT: only the unique multicast address for pause frame which is specified + in IEEE802.3 can be detected + \param[out] none + \retval none +*/ +void enet_pauseframe_detect_config(uint32_t detect) +{ + ENET_MAC_FCTL &= ~ENET_MAC_FCTL_UPFDT; + ENET_MAC_FCTL |= detect; +} + +/*! + \brief configure the pause frame parameters + \param[in] pausetime: pause time in transmit pause control frame + \param[in] pause_threshold: the threshold of the pause timer for retransmitting frames automatically, + this value must make sure to be less than configured pause time, only one parameter can be + selected which is shown as below + \arg ENET_PAUSETIME_MINUS4: pause time minus 4 slot times + \arg ENET_PAUSETIME_MINUS28: pause time minus 28 slot times + \arg ENET_PAUSETIME_MINUS144: pause time minus 144 slot times + \arg ENET_PAUSETIME_MINUS256: pause time minus 256 slot times + \param[out] none + \retval none +*/ +void enet_pauseframe_config(uint32_t pausetime, uint32_t pause_threshold) +{ + ENET_MAC_FCTL &= ~(ENET_MAC_FCTL_PTM | ENET_MAC_FCTL_PLTS); + ENET_MAC_FCTL |= (MAC_FCTL_PTM(pausetime) | pause_threshold); +} + +/*! + \brief configure the threshold of the flow control(deactive and active threshold) + \param[in] deactive: the threshold of the deactive flow control, this value + should always be less than active flow control value, only one + parameter can be selected which is shown as below + \arg ENET_DEACTIVE_THRESHOLD_256BYTES: threshold level is 256 bytes + \arg ENET_DEACTIVE_THRESHOLD_512BYTES: threshold level is 512 bytes + \arg ENET_DEACTIVE_THRESHOLD_768BYTES: threshold level is 768 bytes + \arg ENET_DEACTIVE_THRESHOLD_1024BYTES: threshold level is 1024 bytes + \arg ENET_DEACTIVE_THRESHOLD_1280BYTES: threshold level is 1280 bytes + \arg ENET_DEACTIVE_THRESHOLD_1536BYTES: threshold level is 1536 bytes + \arg ENET_DEACTIVE_THRESHOLD_1792BYTES: threshold level is 1792 bytes + \param[in] active: the threshold of the active flow control, only one parameter + can be selected which is shown as below + \arg ENET_ACTIVE_THRESHOLD_256BYTES: threshold level is 256 bytes + \arg ENET_ACTIVE_THRESHOLD_512BYTES: threshold level is 512 bytes + \arg ENET_ACTIVE_THRESHOLD_768BYTES: threshold level is 768 bytes + \arg ENET_ACTIVE_THRESHOLD_1024BYTES: threshold level is 1024 bytes + \arg ENET_ACTIVE_THRESHOLD_1280BYTES: threshold level is 1280 bytes + \arg ENET_ACTIVE_THRESHOLD_1536BYTES: threshold level is 1536 bytes + \arg ENET_ACTIVE_THRESHOLD_1792BYTES: threshold level is 1792 bytes + \param[out] none + \retval none +*/ +void enet_flowcontrol_threshold_config(uint32_t deactive, uint32_t active) +{ + ENET_MAC_FCTH = ((deactive | active) >> 8); +} + +/*! + \brief enable ENET flow control feature + \param[in] feature: the feature of ENET flow control mode + one or more parameters can be selected which are shown as below + \arg ENET_ZERO_QUANTA_PAUSE: the automatic zero-quanta generation function + \arg ENET_TX_FLOWCONTROL: the flow control operation in the MAC + \arg ENET_RX_FLOWCONTROL: decoding function for the received pause frame and process it + \arg ENET_BACK_PRESSURE: back pressure operation in the MAC(only use in half-dulex mode) + \param[out] none + \retval none +*/ +void enet_flowcontrol_feature_enable(uint32_t feature) +{ + if(RESET != (feature & ENET_ZERO_QUANTA_PAUSE)) { + ENET_MAC_FCTL &= ~ENET_ZERO_QUANTA_PAUSE; + } + feature &= ~ENET_ZERO_QUANTA_PAUSE; + ENET_MAC_FCTL |= feature; +} + +/*! + \brief disable ENET flow control feature + \param[in] feature: the feature of ENET flow control mode + one or more parameters can be selected which are shown as below + \arg ENET_ZERO_QUANTA_PAUSE: the automatic zero-quanta generation function + \arg ENET_TX_FLOWCONTROL: the flow control operation in the MAC + \arg ENET_RX_FLOWCONTROL: decoding function for the received pause frame and process it + \arg ENET_BACK_PRESSURE: back pressure operation in the MAC(only use in half-dulex mode) + \param[out] none + \retval none +*/ +void enet_flowcontrol_feature_disable(uint32_t feature) +{ + if(RESET != (feature & ENET_ZERO_QUANTA_PAUSE)) { + ENET_MAC_FCTL |= ENET_ZERO_QUANTA_PAUSE; + } + feature &= ~ENET_ZERO_QUANTA_PAUSE; + ENET_MAC_FCTL &= ~feature; +} + +/*! + \brief get the dma transmit/receive process state + \param[in] direction: choose the direction of dma process which users want to check, + refer to enet_dmadirection_enum, only one parameter can be selected which is shown as below + \arg ENET_DMA_TX: dma transmit process + \arg ENET_DMA_RX: dma receive process + \param[out] none + \retval state of dma process, the value range shows below: + ENET_RX_STATE_STOPPED, ENET_RX_STATE_FETCHING, ENET_RX_STATE_WAITING, + ENET_RX_STATE_SUSPENDED, ENET_RX_STATE_CLOSING, ENET_RX_STATE_QUEUING, + ENET_TX_STATE_STOPPED, ENET_TX_STATE_FETCHING, ENET_TX_STATE_WAITING, + ENET_TX_STATE_READING, ENET_TX_STATE_SUSPENDED, ENET_TX_STATE_CLOSING +*/ +uint32_t enet_dmaprocess_state_get(enet_dmadirection_enum direction) +{ + uint32_t reval; + reval = (uint32_t)(ENET_DMA_STAT & (uint32_t)direction); + return reval; +} + +/*! + \brief poll the DMA transmission/reception enable by writing any value to the + ENET_DMA_TPEN/ENET_DMA_RPEN register, this will make the DMA to resume transmission/reception + \param[in] direction: choose the direction of DMA process which users want to resume, + refer to enet_dmadirection_enum, only one parameter can be selected which is shown as below + \arg ENET_DMA_TX: DMA transmit process + \arg ENET_DMA_RX: DMA receive process + \param[out] none + \retval none +*/ +void enet_dmaprocess_resume(enet_dmadirection_enum direction) +{ + if(ENET_DMA_TX == direction) { + ENET_DMA_TPEN = 0U; + } else { + ENET_DMA_RPEN = 0U; + } +} + +/*! + \brief check and recover the Rx process + \param[in] none + \param[out] none + \retval none +*/ +void enet_rxprocess_check_recovery(void) +{ + uint32_t status; + + /* get DAV information of current RxDMA descriptor */ + status = dma_current_rxdesc->status; + status &= ENET_RDES0_DAV; + + /* if current descriptor is owned by DMA, but the descriptor address mismatches with + receive descriptor address pointer updated by RxDMA controller */ + if((ENET_DMA_CRDADDR != ((uint32_t)dma_current_rxdesc)) && + (ENET_RDES0_DAV == status)) { + dma_current_rxdesc = (enet_descriptors_struct *)ENET_DMA_CRDADDR; + } +} + +/*! + \brief flush the ENET transmit FIFO, and wait until the flush operation completes + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus enet_txfifo_flush(void) +{ + uint32_t flush_state; + uint32_t timeout = 0U; + ErrStatus enet_state = ERROR; + + /* set the FTF bit for flushing transmit FIFO */ + ENET_DMA_CTL |= ENET_DMA_CTL_FTF; + /* wait until the flush operation completes */ + do { + flush_state = ENET_DMA_CTL & ENET_DMA_CTL_FTF; + timeout++; + } while((RESET != flush_state) && (timeout < ENET_DELAY_TO)); + /* return ERROR due to timeout */ + if(RESET == flush_state) { + enet_state = SUCCESS; + } + + return enet_state; +} + +/*! + \brief get the transmit/receive address of current descriptor, or current buffer, or descriptor table + \param[in] addr_get: choose the address which users want to get, refer to enet_desc_reg_enum + only one parameter can be selected which is shown as below + \arg ENET_RX_DESC_TABLE: the start address of the receive descriptor table + \arg ENET_RX_CURRENT_DESC: the start descriptor address of the current receive descriptor read by + the RxDMA controller + \arg ENET_RX_CURRENT_BUFFER: the current receive buffer address being read by the RxDMA controller + \arg ENET_TX_DESC_TABLE: the start address of the transmit descriptor table + \arg ENET_TX_CURRENT_DESC: the start descriptor address of the current transmit descriptor read by + the TxDMA controller + \arg ENET_TX_CURRENT_BUFFER: the current transmit buffer address being read by the TxDMA controller + \param[out] none + \retval address value +*/ +uint32_t enet_current_desc_address_get(enet_desc_reg_enum addr_get) +{ + uint32_t reval = 0U; + + reval = REG32((ENET) + (uint32_t)addr_get); + return reval; +} + +/*! + \brief get the Tx or Rx descriptor information + \param[in] desc: the descriptor pointer which users want to get information + \param[in] info_get: the descriptor information type which is selected, + only one parameter can be selected which is shown as below + \arg RXDESC_BUFFER_1_SIZE: receive buffer 1 size + \arg RXDESC_BUFFER_2_SIZE: receive buffer 2 size + \arg RXDESC_FRAME_LENGTH: the byte length of the received frame that was transferred to the buffer + \arg TXDESC_COLLISION_COUNT: the number of collisions occurred before the frame was transmitted + \arg RXDESC_BUFFER_1_ADDR: the buffer1 address of the Rx frame + \arg TXDESC_BUFFER_1_ADDR: the buffer1 address of the Tx frame + \param[out] none + \retval descriptor information, if value is 0xFFFFFFFFU, means the false input parameter +*/ +uint32_t enet_desc_information_get(enet_descriptors_struct *desc, enet_descstate_enum info_get) +{ + uint32_t reval = 0xFFFFFFFFU; + + switch(info_get) { + case RXDESC_BUFFER_1_SIZE: + reval = GET_RDES1_RB1S(desc->control_buffer_size); + break; + case RXDESC_BUFFER_2_SIZE: + reval = GET_RDES1_RB2S(desc->control_buffer_size); + break; + case RXDESC_FRAME_LENGTH: + reval = GET_RDES0_FRML(desc->status); + if(reval > 4U) { + reval = reval - 4U; + + /* if is a type frame, and CRC is not included in forwarding frame */ + if((RESET != (ENET_MAC_CFG & ENET_MAC_CFG_TFCD)) && (RESET != (desc->status & ENET_RDES0_FRMT))) { + reval = reval + 4U; + } + } else { + reval = 0U; + } + + break; + case RXDESC_BUFFER_1_ADDR: + reval = desc->buffer1_addr; + break; + case TXDESC_BUFFER_1_ADDR: + reval = desc->buffer1_addr; + break; + case TXDESC_COLLISION_COUNT: + reval = GET_TDES0_COCNT(desc->status); + break; + default: + break; + } + return reval; +} + +/*! + \brief get the number of missed frames during receiving + \param[in] none + \param[out] rxfifo_drop: pointer to the number of frames dropped by RxFIFO + \param[out] rxdma_drop: pointer to the number of frames missed by the RxDMA controller + \retval none +*/ +void enet_missed_frame_counter_get(uint32_t *rxfifo_drop, uint32_t *rxdma_drop) +{ + uint32_t temp_counter = 0U; + + temp_counter = ENET_DMA_MFBOCNT; + *rxfifo_drop = GET_DMA_MFBOCNT_MSFA(temp_counter); + *rxdma_drop = GET_DMA_MFBOCNT_MSFC(temp_counter); +} + +/*! + \brief get the bit flag of ENET DMA descriptor + \param[in] desc: the descriptor pointer which users want to get flag + \param[in] desc_flag: the bit flag of ENET DMA descriptor + only one parameter can be selected which is shown as below + \arg ENET_TDES0_DB: deferred + \arg ENET_TDES0_UFE: underflow error + \arg ENET_TDES0_EXD: excessive deferral + \arg ENET_TDES0_VFRM: VLAN frame + \arg ENET_TDES0_ECO: excessive collision + \arg ENET_TDES0_LCO: late collision + \arg ENET_TDES0_NCA: no carrier + \arg ENET_TDES0_LCA: loss of carrier + \arg ENET_TDES0_IPPE: IP payload error + \arg ENET_TDES0_FRMF: frame flushed + \arg ENET_TDES0_JT: jabber timeout + \arg ENET_TDES0_ES: error summary + \arg ENET_TDES0_IPHE: IP header error + \arg ENET_TDES0_TTMSS: transmit timestamp status + \arg ENET_TDES0_TCHM: the second address chained mode + \arg ENET_TDES0_TERM: transmit end of ring mode + \arg ENET_TDES0_TTSEN: transmit timestamp function enable + \arg ENET_TDES0_DPAD: disable adding pad + \arg ENET_TDES0_DCRC: disable CRC + \arg ENET_TDES0_FSG: first segment + \arg ENET_TDES0_LSG: last segment + \arg ENET_TDES0_INTC: interrupt on completion + \arg ENET_TDES0_DAV: DAV bit + + \arg ENET_RDES0_PCERR: payload checksum error + \arg ENET_RDES0_EXSV: extended status valid + \arg ENET_RDES0_CERR: CRC error + \arg ENET_RDES0_DBERR: dribble bit error + \arg ENET_RDES0_RERR: receive error + \arg ENET_RDES0_RWDT: receive watchdog timeout + \arg ENET_RDES0_FRMT: frame type + \arg ENET_RDES0_LCO: late collision + \arg ENET_RDES0_IPHERR: IP frame header error + \arg ENET_RDES0_TSV: timestamp valid + \arg ENET_RDES0_LDES: last descriptor + \arg ENET_RDES0_FDES: first descriptor + \arg ENET_RDES0_VTAG: VLAN tag + \arg ENET_RDES0_OERR: overflow error + \arg ENET_RDES0_LERR: length error + \arg ENET_RDES0_SAFF: SA filter fail + \arg ENET_RDES0_DERR: descriptor error + \arg ENET_RDES0_ERRS: error summary + \arg ENET_RDES0_DAFF: destination address filter fail + \arg ENET_RDES0_DAV: descriptor available + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus enet_desc_flag_get(enet_descriptors_struct *desc, uint32_t desc_flag) +{ + FlagStatus enet_flag = RESET; + + if((uint32_t)RESET != (desc->status & desc_flag)) { + enet_flag = SET; + } + + return enet_flag; +} + +/*! + \brief set the bit flag of ENET DMA descriptor + \param[in] desc: the descriptor pointer which users want to set flag + \param[in] desc_flag: the bit flag of ENET DMA descriptor + only one parameter can be selected which is shown as below + \arg ENET_TDES0_VFRM: VLAN frame + \arg ENET_TDES0_FRMF: frame flushed + \arg ENET_TDES0_TCHM: the second address chained mode + \arg ENET_TDES0_TERM: transmit end of ring mode + \arg ENET_TDES0_TTSEN: transmit timestamp function enable + \arg ENET_TDES0_DPAD: disable adding pad + \arg ENET_TDES0_DCRC: disable CRC + \arg ENET_TDES0_FSG: first segment + \arg ENET_TDES0_LSG: last segment + \arg ENET_TDES0_INTC: interrupt on completion + \arg ENET_TDES0_DAV: DAV bit + \arg ENET_RDES0_DAV: descriptor available + \param[out] none + \retval none +*/ +void enet_desc_flag_set(enet_descriptors_struct *desc, uint32_t desc_flag) +{ + desc->status |= desc_flag; +} + +/*! + \brief clear the bit flag of ENET DMA descriptor + \param[in] desc: the descriptor pointer which users want to clear flag + \param[in] desc_flag: the bit flag of ENET DMA descriptor + only one parameter can be selected which is shown as below + \arg ENET_TDES0_VFRM: VLAN frame + \arg ENET_TDES0_FRMF: frame flushed + \arg ENET_TDES0_TCHM: the second address chained mode + \arg ENET_TDES0_TERM: transmit end of ring mode + \arg ENET_TDES0_TTSEN: transmit timestamp function enable + \arg ENET_TDES0_DPAD: disable adding pad + \arg ENET_TDES0_DCRC: disable CRC + \arg ENET_TDES0_FSG: first segment + \arg ENET_TDES0_LSG: last segment + \arg ENET_TDES0_INTC: interrupt on completion + \arg ENET_TDES0_DAV: DAV bit + \arg ENET_RDES0_DAV: descriptor available + \param[out] none + \retval none +*/ +void enet_desc_flag_clear(enet_descriptors_struct *desc, uint32_t desc_flag) +{ + desc->status &= ~desc_flag; +} + +/*! + \brief when receiving completed, set RS bit in ENET_DMA_STAT register will immediately set + \param[in] desc: the descriptor pointer which users want to configure + \param[out] none + \retval none +*/ +void enet_rx_desc_immediate_receive_complete_interrupt(enet_descriptors_struct *desc) +{ + desc->control_buffer_size &= ~ENET_RDES1_DINTC; +} + +/*! + \brief when receiving completed, set RS bit in ENET_DMA_STAT register will is set after a configurable delay time + \param[in] desc: the descriptor pointer which users want to configure + \param[in] delay_time: delay a time of 256*delay_time HCLK, this value must be between 0 and 0xFF + \param[out] none + \retval none +*/ +void enet_rx_desc_delay_receive_complete_interrupt(enet_descriptors_struct *desc, uint32_t delay_time) +{ + desc->control_buffer_size |= ENET_RDES1_DINTC; + ENET_DMA_RSWDC = DMA_RSWDC_WDCFRS(delay_time); +} + +/*! + \brief drop current receive frame + \param[in] none + \param[out] none + \retval none +*/ +void enet_rxframe_drop(void) +{ + /* enable reception, descriptor is owned by DMA */ + dma_current_rxdesc->status = ENET_RDES0_DAV; + + /* chained mode */ + if((uint32_t)RESET != (dma_current_rxdesc->control_buffer_size & ENET_RDES1_RCHM)) { + if(NULL != dma_current_ptp_rxdesc) { + dma_current_rxdesc = (enet_descriptors_struct *)(dma_current_ptp_rxdesc->buffer2_next_desc_addr); + /* if it is the last ptp descriptor */ + if(0U != dma_current_ptp_rxdesc->status) { + /* pointer back to the first ptp descriptor address in the desc_ptptab list address */ + dma_current_ptp_rxdesc = (enet_descriptors_struct *)(dma_current_ptp_rxdesc->status); + } else { + /* ponter to the next ptp descriptor */ + dma_current_ptp_rxdesc++; + } + } else { + dma_current_rxdesc = (enet_descriptors_struct *)(dma_current_rxdesc->buffer2_next_desc_addr); + } + + } else { + /* ring mode */ + if((uint32_t)RESET != (dma_current_rxdesc->control_buffer_size & ENET_RDES1_RERM)) { + /* if is the last descriptor in table, the next descriptor is the table header */ + dma_current_rxdesc = (enet_descriptors_struct *)(ENET_DMA_RDTADDR); + if(NULL != dma_current_ptp_rxdesc) { + dma_current_ptp_rxdesc = (enet_descriptors_struct *)(dma_current_ptp_rxdesc->status); + } + } else { + /* the next descriptor is the current address, add the descriptor size, and descriptor skip length */ + dma_current_rxdesc = (enet_descriptors_struct *)(uint32_t)((uint32_t)dma_current_rxdesc + ETH_DMARXDESC_SIZE + + GET_DMA_BCTL_DPSL(ENET_DMA_BCTL)); + if(NULL != dma_current_ptp_rxdesc) { + dma_current_ptp_rxdesc++; + } + } + } +} + +/*! + \brief enable DMA feature + \param[in] feature: the feature of DMA mode + one or more parameters can be selected which are shown as below + \arg ENET_NO_FLUSH_RXFRAME: RxDMA does not flushes frames function + \arg ENET_SECONDFRAME_OPT: TxDMA controller operate on second frame function + \param[out] none + \retval none +*/ +void enet_dma_feature_enable(uint32_t feature) +{ + ENET_DMA_CTL |= feature; +} + +/*! + \brief disable DMA feature + \param[in] feature: the feature of DMA mode + one or more parameters can be selected which are shown as below + \arg ENET_NO_FLUSH_RXFRAME: RxDMA does not flushes frames function + \arg ENET_SECONDFRAME_OPT: TxDMA controller operate on second frame function + \param[out] none + \retval none +*/ +void enet_dma_feature_disable(uint32_t feature) +{ + ENET_DMA_CTL &= ~feature; +} + +#ifdef SELECT_DESCRIPTORS_ENHANCED_MODE +/*! + \brief get the bit of extended status flag in ENET DMA descriptor + \param[in] desc: the descriptor pointer which users want to get the extended status flag + \param[in] desc_status: the extended status want to get + only one parameter can be selected which is shown as below + \arg ENET_RDES4_IPPLDT: IP frame payload type + \arg ENET_RDES4_IPHERR: IP frame header error + \arg ENET_RDES4_IPPLDERR: IP frame payload error + \arg ENET_RDES4_IPCKSB: IP frame checksum bypassed + \arg ENET_RDES4_IPF4: IP frame in version 4 + \arg ENET_RDES4_IPF6: IP frame in version 6 + \arg ENET_RDES4_PTPMT: PTP message type + \arg ENET_RDES4_PTPOEF: PTP on ethernet frame + \arg ENET_RDES4_PTPVF: PTP version format + \param[out] none + \retval value of extended status +*/ +uint32_t enet_rx_desc_enhanced_status_get(enet_descriptors_struct *desc, uint32_t desc_status) +{ + uint32_t reval = 0xFFFFFFFFU; + + switch(desc_status) { + case ENET_RDES4_IPPLDT: + reval = GET_RDES4_IPPLDT(desc->extended_status); + break; + case ENET_RDES4_PTPMT: + reval = GET_RDES4_PTPMT(desc->extended_status); + break; + default: + if((uint32_t)RESET != (desc->extended_status & desc_status)) { + reval = 1U; + } else { + reval = 0U; + } + } + + return reval; +} + +/*! + \brief configure descriptor to work in enhanced mode + \param[in] none + \param[out] none + \retval none +*/ +void enet_desc_select_enhanced_mode(void) +{ + ENET_DMA_BCTL |= ENET_DMA_BCTL_DFM; +} + +/*! + \brief initialize the DMA Tx/Rx descriptors's parameters in enhanced chain mode with ptp function + \param[in] direction: the descriptors which users want to init, refer to enet_dmadirection_enum + only one parameter can be selected which is shown as below + \arg ENET_DMA_TX: DMA Tx descriptors + \arg ENET_DMA_RX: DMA Rx descriptors + \param[out] none + \retval none +*/ +void enet_ptp_enhanced_descriptors_chain_init(enet_dmadirection_enum direction) +{ + uint32_t num = 0U, count = 0U, maxsize = 0U; + uint32_t desc_status = 0U, desc_bufsize = 0U; + enet_descriptors_struct *desc, *desc_tab; + uint8_t *buf; + + /* if want to initialize DMA Tx descriptors */ + if(ENET_DMA_TX == direction) { + /* save a copy of the DMA Tx descriptors */ + desc_tab = txdesc_tab; + buf = &tx_buff[0][0]; + count = ENET_TXBUF_NUM; + maxsize = ENET_TXBUF_SIZE; + + /* select chain mode, and enable transmit timestamp function */ + desc_status = ENET_TDES0_TCHM | ENET_TDES0_TTSEN; + + /* configure DMA Tx descriptor table address register */ + ENET_DMA_TDTADDR = (uint32_t)desc_tab; + dma_current_txdesc = desc_tab; + } else { + /* if want to initialize DMA Rx descriptors */ + /* save a copy of the DMA Rx descriptors */ + desc_tab = rxdesc_tab; + buf = &rx_buff[0][0]; + count = ENET_RXBUF_NUM; + maxsize = ENET_RXBUF_SIZE; + + /* enable receiving */ + desc_status = ENET_RDES0_DAV; + /* select receive chained mode and set buffer1 size */ + desc_bufsize = ENET_RDES1_RCHM | (uint32_t)ENET_RXBUF_SIZE; + + /* configure DMA Rx descriptor table address register */ + ENET_DMA_RDTADDR = (uint32_t)desc_tab; + dma_current_rxdesc = desc_tab; + } + + /* configuration each descriptor */ + for(num = 0U; num < count; num++) { + /* get the pointer to the next descriptor of the descriptor table */ + desc = desc_tab + num; + + /* configure descriptors */ + desc->status = desc_status; + desc->control_buffer_size = desc_bufsize; + desc->buffer1_addr = (uint32_t)(&buf[num * maxsize]); + + /* if is not the last descriptor */ + if(num < (count - 1U)) { + /* configure the next descriptor address */ + desc->buffer2_next_desc_addr = (uint32_t)(desc_tab + num + 1U); + } else { + /* when it is the last descriptor, the next descriptor address + equals to first descriptor address in descriptor table */ + desc->buffer2_next_desc_addr = (uint32_t)desc_tab; + } + } +} + +/*! + \brief initialize the DMA Tx/Rx descriptors's parameters in enhanced ring mode with ptp function + \param[in] direction: the descriptors which users want to init, refer to enet_dmadirection_enum + only one parameter can be selected which is shown as below + \arg ENET_DMA_TX: DMA Tx descriptors + \arg ENET_DMA_RX: DMA Rx descriptors + \param[out] none + \retval none +*/ +void enet_ptp_enhanced_descriptors_ring_init(enet_dmadirection_enum direction) +{ + uint32_t num = 0U, count = 0U, maxsize = 0U; + uint32_t desc_status = 0U, desc_bufsize = 0U; + enet_descriptors_struct *desc; + enet_descriptors_struct *desc_tab; + uint8_t *buf; + + /* configure descriptor skip length */ + ENET_DMA_BCTL &= ~ENET_DMA_BCTL_DPSL; + ENET_DMA_BCTL |= DMA_BCTL_DPSL(0); + + /* if want to initialize DMA Tx descriptors */ + if(ENET_DMA_TX == direction) { + /* save a copy of the DMA Tx descriptors */ + desc_tab = txdesc_tab; + buf = &tx_buff[0][0]; + count = ENET_TXBUF_NUM; + maxsize = ENET_TXBUF_SIZE; + + /* select ring mode, and enable transmit timestamp function */ + desc_status = ENET_TDES0_TTSEN; + + /* configure DMA Tx descriptor table address register */ + ENET_DMA_TDTADDR = (uint32_t)desc_tab; + dma_current_txdesc = desc_tab; + } else { + /* if want to initialize DMA Rx descriptors */ + /* save a copy of the DMA Rx descriptors */ + desc_tab = rxdesc_tab; + buf = &rx_buff[0][0]; + count = ENET_RXBUF_NUM; + maxsize = ENET_RXBUF_SIZE; + + /* enable receiving */ + desc_status = ENET_RDES0_DAV; + /* set buffer1 size */ + desc_bufsize = ENET_RXBUF_SIZE; + + /* configure DMA Rx descriptor table address register */ + ENET_DMA_RDTADDR = (uint32_t)desc_tab; + dma_current_rxdesc = desc_tab; + } + + /* configure each descriptor */ + for(num = 0U; num < count; num++) { + /* get the pointer to the next descriptor of the descriptor table */ + desc = desc_tab + num; + + /* configure descriptors */ + desc->status = desc_status; + desc->control_buffer_size = desc_bufsize; + desc->buffer1_addr = (uint32_t)(&buf[num * maxsize]); + + /* when it is the last descriptor */ + if(num == (count - 1U)) { + if(ENET_DMA_TX == direction) { + /* configure transmit end of ring mode */ + desc->status |= ENET_TDES0_TERM; + } else { + /* configure receive end of ring mode */ + desc->control_buffer_size |= ENET_RDES1_RERM; + } + } + } +} + +/*! + \brief receive a packet data with timestamp values to application buffer, when the DMA is in enhanced mode + \param[in] bufsize: the size of buffer which is the parameter in function + \param[out] buffer: pointer to the application buffer + note -- if the input is NULL, user should copy data in application by himself + \param[out] timestamp: pointer to the table which stores the timestamp high and low + note -- if the input is NULL, timestamp is ignored + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_ptpframe_receive_enhanced_mode(uint8_t *buffer, uint32_t bufsize, uint32_t timestamp[]) +{ + uint32_t offset = 0U, size = 0U; + uint32_t timeout = 0U; + uint32_t rdes0_tsv_flag; + + /* the descriptor is busy due to own by the DMA */ + if((uint32_t)RESET != (dma_current_rxdesc->status & ENET_RDES0_DAV)) { + return ERROR; + } + + /* if buffer pointer is null, indicates that users has copied data in application */ + if(NULL != buffer) { + /* if no error occurs, and the frame uses only one descriptor */ + if(((uint32_t)RESET == (dma_current_rxdesc->status & ENET_RDES0_ERRS)) && + ((uint32_t)RESET != (dma_current_rxdesc->status & ENET_RDES0_LDES)) && + ((uint32_t)RESET != (dma_current_rxdesc->status & ENET_RDES0_FDES))) { + /* get the frame length except CRC */ + size = GET_RDES0_FRML(dma_current_rxdesc->status) - 4U; + + /* if is a type frame, and CRC is not included in forwarding frame */ + if((RESET != (ENET_MAC_CFG & ENET_MAC_CFG_TFCD)) && (RESET != (dma_current_rxdesc->status & ENET_RDES0_FRMT))) { + size = size + 4U; + } + + /* to avoid situation that the frame size exceeds the buffer length */ + if(size > bufsize) { + return ERROR; + } + + /* copy data from Rx buffer to application buffer */ + for(offset = 0; offset < size; offset++) { + (*(buffer + offset)) = (*(__IO uint8_t *)((dma_current_rxdesc->buffer1_addr) + offset)); + } + } else { + return ERROR; + } + } + + /* if timestamp pointer is null, indicates that users don't care timestamp in application */ + if(NULL != timestamp) { + /* wait for ENET_RDES0_TSV flag to be set, the timestamp value is taken and + write to the RDES6 and RDES7 */ + do { + rdes0_tsv_flag = (dma_current_rxdesc->status & ENET_RDES0_TSV); + timeout++; + } while((RESET == rdes0_tsv_flag) && (timeout < ENET_DELAY_TO)); + + /* return ERROR due to timeout */ + if(ENET_DELAY_TO == timeout) { + return ERROR; + } + + /* clear the ENET_RDES0_TSV flag */ + dma_current_rxdesc->status &= ~ENET_RDES0_TSV; + /* get the timestamp value of the received frame */ + timestamp[0] = dma_current_rxdesc->timestamp_low; + timestamp[1] = dma_current_rxdesc->timestamp_high; + } + + /* enable reception, descriptor is owned by DMA */ + dma_current_rxdesc->status = ENET_RDES0_DAV; + + /* check Rx buffer unavailable flag status */ + if((uint32_t)RESET != (ENET_DMA_STAT & ENET_DMA_STAT_RBU)) { + /* Clear RBU flag */ + ENET_DMA_STAT = ENET_DMA_STAT_RBU; + /* resume DMA reception by writing to the RPEN register*/ + ENET_DMA_RPEN = 0; + } + + /* update the current RxDMA descriptor pointer to the next decriptor in RxDMA decriptor table */ + /* chained mode */ + if((uint32_t)RESET != (dma_current_rxdesc->control_buffer_size & ENET_RDES1_RCHM)) { + dma_current_rxdesc = (enet_descriptors_struct *)(dma_current_rxdesc->buffer2_next_desc_addr); + } else { + /* ring mode */ + if((uint32_t)RESET != (dma_current_rxdesc->control_buffer_size & ENET_RDES1_RERM)) { + /* if is the last descriptor in table, the next descriptor is the table header */ + dma_current_rxdesc = (enet_descriptors_struct *)(ENET_DMA_RDTADDR); + } else { + /* the next descriptor is the current address, add the descriptor size, and descriptor skip length */ + dma_current_rxdesc = (enet_descriptors_struct *)((uint32_t)dma_current_rxdesc + ETH_DMARXDESC_SIZE + GET_DMA_BCTL_DPSL( + ENET_DMA_BCTL)); + } + } + + return SUCCESS; +} + +/*! + \brief send data with timestamp values in application buffer as a transmit packet, when the DMA is in enhanced mode + \param[in] buffer: pointer on the application buffer + note -- if the input is NULL, user should copy data in application by himself + \param[in] length: the length of frame data to be transmitted + \param[out] timestamp: pointer to the table which stores the timestamp high and low + note -- if the input is NULL, timestamp is ignored + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_ptpframe_transmit_enhanced_mode(uint8_t *buffer, uint32_t length, uint32_t timestamp[]) +{ + uint32_t offset = 0; + uint32_t dma_tbu_flag, dma_tu_flag; + uint32_t tdes0_ttmss_flag; + uint32_t timeout = 0; + + /* the descriptor is busy due to own by the DMA */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_DAV)) { + return ERROR; + } + + /* only frame length no more than ENET_MAX_FRAME_SIZE is allowed */ + if(length > ENET_MAX_FRAME_SIZE) { + return ERROR; + } + + /* if buffer pointer is null, indicates that users has handled data in application */ + if(NULL != buffer) { + /* copy frame data from application buffer to Tx buffer */ + for(offset = 0; offset < length; offset++) { + (*(__IO uint8_t *)((dma_current_txdesc->buffer1_addr) + offset)) = (*(buffer + offset)); + } + } + /* set the frame length */ + dma_current_txdesc->control_buffer_size = length; + /* set the segment of frame, frame is transmitted in one descriptor */ + dma_current_txdesc->status |= ENET_TDES0_LSG | ENET_TDES0_FSG; + /* enable the DMA transmission */ + dma_current_txdesc->status |= ENET_TDES0_DAV; + + /* check Tx buffer unavailable flag status */ + dma_tbu_flag = (ENET_DMA_STAT & ENET_DMA_STAT_TBU); + dma_tu_flag = (ENET_DMA_STAT & ENET_DMA_STAT_TU); + + if((RESET != dma_tbu_flag) || (RESET != dma_tu_flag)) { + /* Clear TBU and TU flag */ + ENET_DMA_STAT = (dma_tbu_flag | dma_tu_flag); + /* resume DMA transmission by writing to the TPEN register*/ + ENET_DMA_TPEN = 0; + } + + /* if timestamp pointer is null, indicates that users don't care timestamp in application */ + if(NULL != timestamp) { + /* wait for ENET_TDES0_TTMSS flag to be set, a timestamp was captured */ + do { + tdes0_ttmss_flag = (dma_current_txdesc->status & ENET_TDES0_TTMSS); + timeout++; + } while((RESET == tdes0_ttmss_flag) && (timeout < ENET_DELAY_TO)); + + /* return ERROR due to timeout */ + if(ENET_DELAY_TO == timeout) { + return ERROR; + } + + /* clear the ENET_TDES0_TTMSS flag */ + dma_current_txdesc->status &= ~ENET_TDES0_TTMSS; + /* get the timestamp value of the transmit frame */ + timestamp[0] = dma_current_txdesc->timestamp_low; + timestamp[1] = dma_current_txdesc->timestamp_high; + } + + /* update the current TxDMA descriptor pointer to the next decriptor in TxDMA decriptor table*/ + /* chained mode */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_TCHM)) { + dma_current_txdesc = (enet_descriptors_struct *)(dma_current_txdesc->buffer2_next_desc_addr); + } else { + /* ring mode */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_TERM)) { + /* if is the last descriptor in table, the next descriptor is the table header */ + dma_current_txdesc = (enet_descriptors_struct *)(ENET_DMA_TDTADDR); + } else { + /* the next descriptor is the current address, add the descriptor size, and descriptor skip length */ + dma_current_txdesc = (enet_descriptors_struct *)((uint32_t)dma_current_txdesc + ETH_DMATXDESC_SIZE + GET_DMA_BCTL_DPSL( + ENET_DMA_BCTL)); + } + } + + return SUCCESS; +} + +#else + +/*! + \brief configure descriptor to work in normal mode + \param[in] none + \param[out] none + \retval none +*/ +void enet_desc_select_normal_mode(void) +{ + ENET_DMA_BCTL &= ~ENET_DMA_BCTL_DFM; +} + +/*! + \brief initialize the DMA Tx/Rx descriptors's parameters in normal chain mode with PTP function + \param[in] direction: the descriptors which users want to init, refer to enet_dmadirection_enum + only one parameter can be selected which is shown as below + \arg ENET_DMA_TX: DMA Tx descriptors + \arg ENET_DMA_RX: DMA Rx descriptors + \param[in] desc_ptptab: pointer to the first descriptor address of PTP Rx descriptor table + \param[out] none + \retval none +*/ +void enet_ptp_normal_descriptors_chain_init(enet_dmadirection_enum direction, enet_descriptors_struct *desc_ptptab) +{ + uint32_t num = 0U, count = 0U, maxsize = 0U; + uint32_t desc_status = 0U, desc_bufsize = 0U; + enet_descriptors_struct *desc, *desc_tab; + uint8_t *buf; + + /* if want to initialize DMA Tx descriptors */ + if(ENET_DMA_TX == direction) { + /* save a copy of the DMA Tx descriptors */ + desc_tab = txdesc_tab; + buf = &tx_buff[0][0]; + count = ENET_TXBUF_NUM; + maxsize = ENET_TXBUF_SIZE; + + /* select chain mode, and enable transmit timestamp function */ + desc_status = ENET_TDES0_TCHM | ENET_TDES0_TTSEN; + + /* configure DMA Tx descriptor table address register */ + ENET_DMA_TDTADDR = (uint32_t)desc_tab; + dma_current_txdesc = desc_tab; + dma_current_ptp_txdesc = desc_ptptab; + } else { + /* if want to initialize DMA Rx descriptors */ + /* save a copy of the DMA Rx descriptors */ + desc_tab = rxdesc_tab; + buf = &rx_buff[0][0]; + count = ENET_RXBUF_NUM; + maxsize = ENET_RXBUF_SIZE; + + /* enable receiving */ + desc_status = ENET_RDES0_DAV; + /* select receive chained mode and set buffer1 size */ + desc_bufsize = ENET_RDES1_RCHM | (uint32_t)ENET_RXBUF_SIZE; + + /* configure DMA Rx descriptor table address register */ + ENET_DMA_RDTADDR = (uint32_t)desc_tab; + dma_current_rxdesc = desc_tab; + dma_current_ptp_rxdesc = desc_ptptab; + } + + /* configure each descriptor */ + for(num = 0U; num < count; num++) { + /* get the pointer to the next descriptor of the descriptor table */ + desc = desc_tab + num; + + /* configure descriptors */ + desc->status = desc_status; + desc->control_buffer_size = desc_bufsize; + desc->buffer1_addr = (uint32_t)(&buf[num * maxsize]); + + /* if is not the last descriptor */ + if(num < (count - 1U)) { + /* configure the next descriptor address */ + desc->buffer2_next_desc_addr = (uint32_t)(desc_tab + num + 1U); + } else { + /* when it is the last descriptor, the next descriptor address + equals to first descriptor address in descriptor table */ + desc->buffer2_next_desc_addr = (uint32_t)desc_tab; + } + /* set desc_ptptab equal to desc_tab */ + (&desc_ptptab[num])->buffer1_addr = desc->buffer1_addr; + (&desc_ptptab[num])->buffer2_next_desc_addr = desc->buffer2_next_desc_addr; + } + /* when it is the last ptp descriptor, preserve the first descriptor + address of desc_ptptab in ptp descriptor status */ + (&desc_ptptab[num - 1U])->status = (uint32_t)desc_ptptab; +} + +/*! + \brief initialize the DMA Tx/Rx descriptors's parameters in normal ring mode with PTP function + \param[in] direction: the descriptors which users want to init, refer to enet_dmadirection_enum + only one parameter can be selected which is shown as below + \arg ENET_DMA_TX: DMA Tx descriptors + \arg ENET_DMA_RX: DMA Rx descriptors + \param[in] desc_ptptab: pointer to the first descriptor address of PTP Rx descriptor table + \param[out] none + \retval none +*/ +void enet_ptp_normal_descriptors_ring_init(enet_dmadirection_enum direction, enet_descriptors_struct *desc_ptptab) +{ + uint32_t num = 0U, count = 0U, maxsize = 0U; + uint32_t desc_status = 0U, desc_bufsize = 0U; + enet_descriptors_struct *desc, *desc_tab; + uint8_t *buf; + + /* configure descriptor skip length */ + ENET_DMA_BCTL &= ~ENET_DMA_BCTL_DPSL; + ENET_DMA_BCTL |= DMA_BCTL_DPSL(0); + + /* if want to initialize DMA Tx descriptors */ + if(ENET_DMA_TX == direction) { + /* save a copy of the DMA Tx descriptors */ + desc_tab = txdesc_tab; + buf = &tx_buff[0][0]; + count = ENET_TXBUF_NUM; + maxsize = ENET_TXBUF_SIZE; + + /* select ring mode, and enable transmit timestamp function */ + desc_status = ENET_TDES0_TTSEN; + + /* configure DMA Tx descriptor table address register */ + ENET_DMA_TDTADDR = (uint32_t)desc_tab; + dma_current_txdesc = desc_tab; + dma_current_ptp_txdesc = desc_ptptab; + } else { + /* if want to initialize DMA Rx descriptors */ + /* save a copy of the DMA Rx descriptors */ + desc_tab = rxdesc_tab; + buf = &rx_buff[0][0]; + count = ENET_RXBUF_NUM; + maxsize = ENET_RXBUF_SIZE; + + /* enable receiving */ + desc_status = ENET_RDES0_DAV; + /* select receive ring mode and set buffer1 size */ + desc_bufsize = (uint32_t)ENET_RXBUF_SIZE; + + /* configure DMA Rx descriptor table address register */ + ENET_DMA_RDTADDR = (uint32_t)desc_tab; + dma_current_rxdesc = desc_tab; + dma_current_ptp_rxdesc = desc_ptptab; + } + + /* configure each descriptor */ + for(num = 0U; num < count; num++) { + /* get the pointer to the next descriptor of the descriptor table */ + desc = desc_tab + num; + + /* configure descriptors */ + desc->status = desc_status; + desc->control_buffer_size = desc_bufsize; + desc->buffer1_addr = (uint32_t)(&buf[num * maxsize]); + + /* when it is the last descriptor */ + if(num == (count - 1U)) { + if(ENET_DMA_TX == direction) { + /* configure transmit end of ring mode */ + desc->status |= ENET_TDES0_TERM; + } else { + /* configure receive end of ring mode */ + desc->control_buffer_size |= ENET_RDES1_RERM; + } + } + /* set desc_ptptab equal to desc_tab */ + (&desc_ptptab[num])->buffer1_addr = desc->buffer1_addr; + (&desc_ptptab[num])->buffer2_next_desc_addr = desc->buffer2_next_desc_addr; + } + /* when it is the last ptp descriptor, preserve the first descriptor + address of desc_ptptab in ptp descriptor status */ + (&desc_ptptab[num - 1U])->status = (uint32_t)desc_ptptab; +} + +/*! + \brief receive a packet data with timestamp values to application buffer, when the DMA is in normal mode + \param[in] bufsize: the size of buffer which is the parameter in function + \param[out] buffer: pointer to the application buffer + note -- if the input is NULL, user should copy data in application by himself + \param[out] timestamp: pointer to the table which stores the timestamp high and low + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_ptpframe_receive_normal_mode(uint8_t *buffer, uint32_t bufsize, uint32_t timestamp[]) +{ + uint32_t offset = 0U, size = 0U; + + /* the descriptor is busy due to own by the DMA */ + if((uint32_t)RESET != (dma_current_rxdesc->status & ENET_RDES0_DAV)) { + return ERROR; + } + + /* if buffer pointer is null, indicates that users has copied data in application */ + if(NULL != buffer) { + /* if no error occurs, and the frame uses only one descriptor */ + if(((uint32_t)RESET == (dma_current_rxdesc->status & ENET_RDES0_ERRS)) && + ((uint32_t)RESET != (dma_current_rxdesc->status & ENET_RDES0_LDES)) && + ((uint32_t)RESET != (dma_current_rxdesc->status & ENET_RDES0_FDES))) { + + /* get the frame length except CRC */ + size = GET_RDES0_FRML(dma_current_rxdesc->status) - 4U; + /* if is a type frame, and CRC is not included in forwarding frame */ + if((RESET != (ENET_MAC_CFG & ENET_MAC_CFG_TFCD)) && (RESET != (dma_current_rxdesc->status & ENET_RDES0_FRMT))) { + size = size + 4U; + } + + /* to avoid situation that the frame size exceeds the buffer length */ + if(size > bufsize) { + return ERROR; + } + + /* copy data from Rx buffer to application buffer */ + for(offset = 0U; offset < size; offset++) { + (*(buffer + offset)) = (*(__IO uint8_t *)(uint32_t)((dma_current_ptp_rxdesc->buffer1_addr) + offset)); + } + + } else { + return ERROR; + } + } + /* copy timestamp value from Rx descriptor to application array */ + timestamp[0] = dma_current_rxdesc->buffer1_addr; + timestamp[1] = dma_current_rxdesc->buffer2_next_desc_addr; + + dma_current_rxdesc->buffer1_addr = dma_current_ptp_rxdesc ->buffer1_addr ; + dma_current_rxdesc->buffer2_next_desc_addr = dma_current_ptp_rxdesc ->buffer2_next_desc_addr; + + /* enable reception, descriptor is owned by DMA */ + dma_current_rxdesc->status = ENET_RDES0_DAV; + + /* check Rx buffer unavailable flag status */ + if((uint32_t)RESET != (ENET_DMA_STAT & ENET_DMA_STAT_RBU)) { + /* clear RBU flag */ + ENET_DMA_STAT = ENET_DMA_STAT_RBU; + /* resume DMA reception by writing to the RPEN register*/ + ENET_DMA_RPEN = 0U; + } + + + /* update the current RxDMA descriptor pointer to the next decriptor in RxDMA decriptor table */ + /* chained mode */ + if((uint32_t)RESET != (dma_current_rxdesc->control_buffer_size & ENET_RDES1_RCHM)) { + dma_current_rxdesc = (enet_descriptors_struct *)(dma_current_ptp_rxdesc->buffer2_next_desc_addr); + /* if it is the last ptp descriptor */ + if(0U != dma_current_ptp_rxdesc->status) { + /* pointer back to the first ptp descriptor address in the desc_ptptab list address */ + dma_current_ptp_rxdesc = (enet_descriptors_struct *)(dma_current_ptp_rxdesc->status); + } else { + /* ponter to the next ptp descriptor */ + dma_current_ptp_rxdesc++; + } + } else { + /* ring mode */ + if((uint32_t)RESET != (dma_current_rxdesc->control_buffer_size & ENET_RDES1_RERM)) { + /* if is the last descriptor in table, the next descriptor is the table header */ + dma_current_rxdesc = (enet_descriptors_struct *)(ENET_DMA_RDTADDR); + /* RDES2 and RDES3 will not be covered by buffer address, so do not need to preserve a new table, + use the same table with RxDMA descriptor */ + dma_current_ptp_rxdesc = (enet_descriptors_struct *)(dma_current_ptp_rxdesc->status); + } else { + /* the next descriptor is the current address, add the descriptor size, and descriptor skip length */ + dma_current_rxdesc = (enet_descriptors_struct *)(uint32_t)((uint32_t)dma_current_rxdesc + ETH_DMARXDESC_SIZE + + GET_DMA_BCTL_DPSL(ENET_DMA_BCTL)); + dma_current_ptp_rxdesc ++; + } + } + + return SUCCESS; +} + +/*! + \brief send data with timestamp values in application buffer as a transmit packet, when the DMA is in normal mode + \param[in] buffer: pointer on the application buffer + note -- if the input is NULL, user should copy data in application by himself + \param[in] length: the length of frame data to be transmitted + \param[out] timestamp: pointer to the table which stores the timestamp high and low + note -- if the input is NULL, timestamp is ignored + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_ptpframe_transmit_normal_mode(uint8_t *buffer, uint32_t length, uint32_t timestamp[]) +{ + uint32_t offset = 0U, timeout = 0U; + uint32_t dma_tbu_flag, dma_tu_flag, tdes0_ttmss_flag; + + /* the descriptor is busy due to own by the DMA */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_DAV)) { + return ERROR; + } + + /* only frame length no more than ENET_MAX_FRAME_SIZE is allowed */ + if(length > ENET_MAX_FRAME_SIZE) { + return ERROR; + } + + /* if buffer pointer is null, indicates that users has handled data in application */ + if(NULL != buffer) { + /* copy frame data from application buffer to Tx buffer */ + for(offset = 0U; offset < length; offset++) { + (*(__IO uint8_t *)(uint32_t)((dma_current_ptp_txdesc->buffer1_addr) + offset)) = (*(buffer + offset)); + } + } + /* set the frame length */ + dma_current_txdesc->control_buffer_size = (length & (uint32_t)0x1FFF); + /* set the segment of frame, frame is transmitted in one descriptor */ + dma_current_txdesc->status |= ENET_TDES0_LSG | ENET_TDES0_FSG; + /* enable the DMA transmission */ + dma_current_txdesc->status |= ENET_TDES0_DAV; + + /* check Tx buffer unavailable flag status */ + dma_tbu_flag = (ENET_DMA_STAT & ENET_DMA_STAT_TBU); + dma_tu_flag = (ENET_DMA_STAT & ENET_DMA_STAT_TU); + + if((RESET != dma_tbu_flag) || (RESET != dma_tu_flag)) { + /* clear TBU and TU flag */ + ENET_DMA_STAT = (dma_tbu_flag | dma_tu_flag); + /* resume DMA transmission by writing to the TPEN register*/ + ENET_DMA_TPEN = 0U; + } + + /* if timestamp pointer is null, indicates that users don't care timestamp in application */ + if(NULL != timestamp) { + /* wait for ENET_TDES0_TTMSS flag to be set, a timestamp was captured */ + do { + tdes0_ttmss_flag = (dma_current_txdesc->status & ENET_TDES0_TTMSS); + timeout++; + } while((RESET == tdes0_ttmss_flag) && (timeout < ENET_DELAY_TO)); + + /* return ERROR due to timeout */ + if(ENET_DELAY_TO == timeout) { + return ERROR; + } + + /* clear the ENET_TDES0_TTMSS flag */ + dma_current_txdesc->status &= ~ENET_TDES0_TTMSS; + /* get the timestamp value of the transmit frame */ + timestamp[0] = dma_current_txdesc->buffer1_addr; + timestamp[1] = dma_current_txdesc->buffer2_next_desc_addr; + } + dma_current_txdesc->buffer1_addr = dma_current_ptp_txdesc ->buffer1_addr ; + dma_current_txdesc->buffer2_next_desc_addr = dma_current_ptp_txdesc ->buffer2_next_desc_addr; + + /* update the current TxDMA descriptor pointer to the next decriptor in TxDMA decriptor table */ + /* chained mode */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_TCHM)) { + dma_current_txdesc = (enet_descriptors_struct *)(dma_current_ptp_txdesc->buffer2_next_desc_addr); + /* if it is the last ptp descriptor */ + if(0U != dma_current_ptp_txdesc->status) { + /* pointer back to the first ptp descriptor address in the desc_ptptab list address */ + dma_current_ptp_txdesc = (enet_descriptors_struct *)(dma_current_ptp_txdesc->status); + } else { + /* ponter to the next ptp descriptor */ + dma_current_ptp_txdesc++; + } + } else { + /* ring mode */ + if((uint32_t)RESET != (dma_current_txdesc->status & ENET_TDES0_TERM)) { + /* if is the last descriptor in table, the next descriptor is the table header */ + dma_current_txdesc = (enet_descriptors_struct *)(ENET_DMA_TDTADDR); + /* TDES2 and TDES3 will not be covered by buffer address, so do not need to preserve a new table, + use the same table with TxDMA descriptor */ + dma_current_ptp_txdesc = (enet_descriptors_struct *)(dma_current_ptp_txdesc->status); + } else { + /* the next descriptor is the current address, add the descriptor size, and descriptor skip length */ + dma_current_txdesc = (enet_descriptors_struct *)(uint32_t)((uint32_t)dma_current_txdesc + ETH_DMATXDESC_SIZE + + GET_DMA_BCTL_DPSL(ENET_DMA_BCTL)); + dma_current_ptp_txdesc ++; + } + } + return SUCCESS; +} + +#endif /* SELECT_DESCRIPTORS_ENHANCED_MODE */ + +/*! + \brief wakeup frame filter register pointer reset + \param[in] none + \param[out] none + \retval none +*/ +void enet_wum_filter_register_pointer_reset(void) +{ + ENET_MAC_WUM |= ENET_MAC_WUM_WUFFRPR; +} + +/*! + \brief set the remote wakeup frame registers + \param[in] pdata: pointer to buffer data which is written to remote wakeup frame registers (8 words total) + \param[out] none + \retval none +*/ +void enet_wum_filter_config(uint32_t pdata[]) +{ + uint32_t num = 0U; + + /* configure ENET_MAC_RWFF register */ + for(num = 0U; num < ETH_WAKEUP_REGISTER_LENGTH; num++) { + ENET_MAC_RWFF = pdata[num]; + } +} + +/*! + \brief enable wakeup management features + \param[in] feature: the wake up type which is selected + one or more parameters can be selected which are shown as below + \arg ENET_WUM_POWER_DOWN: power down mode + \arg ENET_WUM_MAGIC_PACKET_FRAME: enable a wakeup event due to magic packet reception + \arg ENET_WUM_WAKE_UP_FRAME: enable a wakeup event due to wakeup frame reception + \arg ENET_WUM_GLOBAL_UNICAST: any received unicast frame passed filter is considered to be a wakeup frame + \param[out] none + \retval none +*/ +void enet_wum_feature_enable(uint32_t feature) +{ + ENET_MAC_WUM |= feature; +} + +/*! + \brief disable wakeup management features + \param[in] feature: the wake up type which is selected + one or more parameters can be selected which are shown as below + \arg ENET_WUM_MAGIC_PACKET_FRAME: enable a wakeup event due to magic packet reception + \arg ENET_WUM_WAKE_UP_FRAME: enable a wakeup event due to wakeup frame reception + \arg ENET_WUM_GLOBAL_UNICAST: any received unicast frame passed filter is considered to be a wakeup frame + \param[out] none + \retval none +*/ +void enet_wum_feature_disable(uint32_t feature) +{ + ENET_MAC_WUM &= (~feature); +} + +/*! + \brief reset the MAC statistics counters + \param[in] none + \param[out] none + \retval none +*/ +void enet_msc_counters_reset(void) +{ + /* reset all counters */ + ENET_MSC_CTL |= ENET_MSC_CTL_CTR; +} + +/*! + \brief enable the MAC statistics counter features + \param[in] feature: the feature of MAC statistics counter + one or more parameters can be selected which are shown as below + \arg ENET_MSC_COUNTER_STOP_ROLLOVER: counter stop rollover + \arg ENET_MSC_RESET_ON_READ: reset on read + \arg ENET_MSC_COUNTERS_FREEZE: MSC counter freeze + \param[out] none + \retval none +*/ +void enet_msc_feature_enable(uint32_t feature) +{ + ENET_MSC_CTL |= feature; +} + +/*! + \brief disable the MAC statistics counter features + \param[in] feature: the feature of MAC statistics counter + one or more parameters can be selected which are shown as below + \arg ENET_MSC_COUNTER_STOP_ROLLOVER: counter stop rollover + \arg ENET_MSC_RESET_ON_READ: reset on read + \arg ENET_MSC_COUNTERS_FREEZE: MSC counter freeze + \param[out] none + \retval none +*/ +void enet_msc_feature_disable(uint32_t feature) +{ + ENET_MSC_CTL &= (~feature); +} + +/*! + \brief configure MAC statistics counters preset mode + \param[in] mode: MSC counters preset mode, refer to enet_msc_preset_enum + only one parameter can be selected which is shown as below + \arg ENET_MSC_PRESET_NONE: do not preset MSC counter + \arg ENET_MSC_PRESET_HALF: preset all MSC counters to almost-half(0x7FFF FFF0) value + \arg ENET_MSC_PRESET_FULL: preset all MSC counters to almost-full(0xFFFF FFF0) value + \param[out] none + \retval none +*/ +void enet_msc_counters_preset_config(enet_msc_preset_enum mode) +{ + ENET_MSC_CTL &= ENET_MSC_PRESET_MASK; + ENET_MSC_CTL |= (uint32_t)mode; +} + +/*! + \brief get MAC statistics counter + \param[in] counter: MSC counters which is selected, refer to enet_msc_counter_enum + only one parameter can be selected which is shown as below + \arg ENET_MSC_TX_SCCNT: MSC transmitted good frames after a single collision counter + \arg ENET_MSC_TX_MSCCNT: MSC transmitted good frames after more than a single collision counter + \arg ENET_MSC_TX_TGFCNT: MSC transmitted good frames counter + \arg ENET_MSC_RX_RFCECNT: MSC received frames with CRC error counter + \arg ENET_MSC_RX_RFAECNT: MSC received frames with alignment error counter + \arg ENET_MSC_RX_RGUFCNT: MSC received good unicast frames counter + \param[out] none + \retval the MSC counter value +*/ +uint32_t enet_msc_counters_get(enet_msc_counter_enum counter) +{ + uint32_t reval; + + reval = REG32((ENET + (uint32_t)counter)); + + return reval; +} + +/*! + \brief change subsecond to nanosecond + \param[in] subsecond: subsecond value + \param[out] none + \retval the nanosecond value +*/ +uint32_t enet_ptp_subsecond_2_nanosecond(uint32_t subsecond) +{ + uint64_t val = subsecond * 1000000000Ull; + val >>= 31; + return (uint32_t)val; +} + +/*! + \brief change nanosecond to subsecond + \param[in] nanosecond: nanosecond value + \param[out] none + \retval the subsecond value +*/ +uint32_t enet_ptp_nanosecond_2_subsecond(uint32_t nanosecond) +{ + uint64_t val = nanosecond * 0x80000000Ull; + val /= 1000000000U; + return (uint32_t)val; +} + +/*! + \brief enable the PTP features + \param[in] feature: the feature of ENET PTP mode + one or more parameters can be selected which are shown as below + \arg ENET_RXTX_TIMESTAMP: timestamp function for transmit and receive frames + \arg ENET_PTP_TIMESTAMP_INT: timestamp interrupt trigger + \arg ENET_ALL_RX_TIMESTAMP: all received frames are taken snapshot + \arg ENET_NONTYPE_FRAME_SNAPSHOT: take snapshot when received non type frame + \arg ENET_IPV6_FRAME_SNAPSHOT: take snapshot for IPv6 frame + \arg ENET_IPV4_FRAME_SNAPSHOT: take snapshot for IPv4 frame + \arg ENET_PTP_FRAME_USE_MACADDRESS_FILTER: use MAC address1-3 to filter the PTP frame + \param[out] none + \retval none +*/ +void enet_ptp_feature_enable(uint32_t feature) +{ + ENET_PTP_TSCTL |= feature; +} + +/*! + \brief disable the PTP features + \param[in] feature: the feature of ENET PTP mode + one or more parameters can be selected which are shown as below + \arg ENET_RXTX_TIMESTAMP: timestamp function for transmit and receive frames + \arg ENET_PTP_TIMESTAMP_INT: timestamp interrupt trigger + \arg ENET_ALL_RX_TIMESTAMP: all received frames are taken snapshot + \arg ENET_NONTYPE_FRAME_SNAPSHOT: take snapshot when received non type frame + \arg ENET_IPV6_FRAME_SNAPSHOT: take snapshot for IPv6 frame + \arg ENET_IPV4_FRAME_SNAPSHOT: take snapshot for IPv4 frame + \arg ENET_PTP_FRAME_USE_MACADDRESS_FILTER: use MAC address1-3 to filter the PTP frame + \param[out] none + \retval none +*/ +void enet_ptp_feature_disable(uint32_t feature) +{ + ENET_PTP_TSCTL &= ~feature; +} + +/*! + \brief configure the PTP timestamp function + \param[in] func: the function of PTP timestamp + only one parameter can be selected which is shown as below + \arg ENET_CKNT_ORDINARY: type of ordinary clock node type for timestamp + \arg ENET_CKNT_BOUNDARY: type of boundary clock node type for timestamp + \arg ENET_CKNT_END_TO_END: type of end-to-end transparent clock node type for timestamp + \arg ENET_CKNT_PEER_TO_PEER: type of peer-to-peer transparent clock node type for timestamp + \arg ENET_PTP_ADDEND_UPDATE: addend register update + \arg ENET_PTP_SYSTIME_UPDATE: timestamp update + \arg ENET_PTP_SYSTIME_INIT: timestamp initialize + \arg ENET_PTP_FINEMODE: the system timestamp uses the fine method for updating + \arg ENET_PTP_COARSEMODE: the system timestamp uses the coarse method for updating + \arg ENET_SUBSECOND_DIGITAL_ROLLOVER: digital rollover mode + \arg ENET_SUBSECOND_BINARY_ROLLOVER: binary rollover mode + \arg ENET_SNOOPING_PTP_VERSION_2: version 2 + \arg ENET_SNOOPING_PTP_VERSION_1: version 1 + \arg ENET_EVENT_TYPE_MESSAGES_SNAPSHOT: only event type messages are taken snapshot + \arg ENET_ALL_TYPE_MESSAGES_SNAPSHOT: all type messages are taken snapshot except announce, + management and signaling message + \arg ENET_MASTER_NODE_MESSAGE_SNAPSHOT: snapshot is only take for master node message + \arg ENET_SLAVE_NODE_MESSAGE_SNAPSHOT: snapshot is only taken for slave node message + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus enet_ptp_timestamp_function_config(enet_ptp_function_enum func) +{ + uint32_t temp_config = 0U, temp_state = 0U; + uint32_t timeout = 0U; + ErrStatus enet_state = SUCCESS; + + switch(func) { + case ENET_CKNT_ORDINARY: + case ENET_CKNT_BOUNDARY: + case ENET_CKNT_END_TO_END: + case ENET_CKNT_PEER_TO_PEER: + ENET_PTP_TSCTL &= ~ENET_PTP_TSCTL_CKNT; + ENET_PTP_TSCTL |= (uint32_t)func; + break; + case ENET_PTP_ADDEND_UPDATE: + /* this bit must be read as zero before application set it */ + do { + temp_state = ENET_PTP_TSCTL & ENET_PTP_TSCTL_TMSARU; + timeout++; + } while((RESET != temp_state) && (timeout < ENET_DELAY_TO)); + /* return ERROR due to timeout */ + if(ENET_DELAY_TO == timeout) { + enet_state = ERROR; + } else { + ENET_PTP_TSCTL |= ENET_PTP_TSCTL_TMSARU; + } + break; + case ENET_PTP_SYSTIME_UPDATE: + /* both the TMSSTU and TMSSTI bits must be read as zero before application set this bit */ + do { + temp_state = ENET_PTP_TSCTL & (ENET_PTP_TSCTL_TMSSTU | ENET_PTP_TSCTL_TMSSTI); + timeout++; + } while((RESET != temp_state) && (timeout < ENET_DELAY_TO)); + /* return ERROR due to timeout */ + if(ENET_DELAY_TO == timeout) { + enet_state = ERROR; + } else { + ENET_PTP_TSCTL |= ENET_PTP_TSCTL_TMSSTU; + } + break; + case ENET_PTP_SYSTIME_INIT: + /* this bit must be read as zero before application set it */ + do { + temp_state = ENET_PTP_TSCTL & ENET_PTP_TSCTL_TMSSTI; + timeout++; + } while((RESET != temp_state) && (timeout < ENET_DELAY_TO)); + /* return ERROR due to timeout */ + if(ENET_DELAY_TO == timeout) { + enet_state = ERROR; + } else { + ENET_PTP_TSCTL |= ENET_PTP_TSCTL_TMSSTI; + } + break; + default: + temp_config = (uint32_t)func & (~BIT(31)); + if(RESET != ((uint32_t)func & BIT(31))) { + ENET_PTP_TSCTL |= temp_config; + } else { + ENET_PTP_TSCTL &= ~temp_config; + } + break; + } + + return enet_state; +} + +/*! + \brief configure system time subsecond increment value + \param[in] subsecond: the value will be added to the subsecond value of system time, + this value must be between 0 and 0xFF + \param[out] none + \retval none +*/ +void enet_ptp_subsecond_increment_config(uint32_t subsecond) +{ + ENET_PTP_SSINC = PTP_SSINC_STMSSI(subsecond); +} + +/*! + \brief adjusting the clock frequency only in fine update mode + \param[in] add: the value will be added to the accumulator register to achieve time synchronization + \param[out] none + \retval none +*/ +void enet_ptp_timestamp_addend_config(uint32_t add) +{ + ENET_PTP_TSADDEND = add; +} + +/*! + \brief initialize or add/subtract to second of the system time + \param[in] sign: timestamp update positive or negative sign + only one parameter can be selected which is shown as below + \arg ENET_PTP_ADD_TO_TIME: timestamp update value is added to system time + \arg ENET_PTP_SUBSTRACT_FROM_TIME: timestamp update value is subtracted from system time + \param[in] second: initializing or adding/subtracting to second of the system time + \param[in] subsecond: the current subsecond of the system time + with 0.46 ns accuracy if required accuracy is 20 ns + \param[out] none + \retval none +*/ +void enet_ptp_timestamp_update_config(uint32_t sign, uint32_t second, uint32_t subsecond) +{ + ENET_PTP_TSUH = second; + ENET_PTP_TSUL = sign | PTP_TSUL_TMSUSS(subsecond); +} + +/*! + \brief configure the expected target time + \param[in] second: the expected target second time + \param[in] nanosecond: the expected target nanosecond time (signed) + \param[out] none + \retval none +*/ +void enet_ptp_expected_time_config(uint32_t second, uint32_t nanosecond) +{ + ENET_PTP_ETH = second; + ENET_PTP_ETL = nanosecond; +} + +/*! + \brief get the current system time + \param[in] none + \param[out] systime_struct: pointer to a enet_ptp_systime_struct structure which contains + parameters of PTP system time + members of the structure and the member values are shown as below: + second: 0x0 - 0xFFFF FFFF + subsecond: 0x0 - 0x7FFF FFFF + sign: ENET_PTP_TIME_POSITIVE, ENET_PTP_TIME_NEGATIVE + \retval none +*/ +void enet_ptp_system_time_get(enet_ptp_systime_struct *systime_struct) +{ + uint32_t temp_sec = 0U, temp_subs = 0U; + + /* get the value of sysytem time registers */ + temp_sec = (uint32_t)ENET_PTP_TSH; + temp_subs = (uint32_t)ENET_PTP_TSL; + + /* get sysytem time and construct the enet_ptp_systime_struct structure */ + systime_struct->second = temp_sec; + systime_struct->nanosecond = GET_PTP_TSL_STMSS(temp_subs); + systime_struct->nanosecond = enet_ptp_subsecond_2_nanosecond(systime_struct->nanosecond); + systime_struct->sign = GET_PTP_TSL_STS(temp_subs); +} + +/*! + \brief configure the PPS output frequency + \param[in] freq: PPS output frequency + only one parameter can be selected which is shown as below + \arg ENET_PPSOFC_1HZ: PPS output 1Hz frequency + \arg ENET_PPSOFC_2HZ: PPS output 2Hz frequency + \arg ENET_PPSOFC_4HZ: PPS output 4Hz frequency + \arg ENET_PPSOFC_8HZ: PPS output 8Hz frequency + \arg ENET_PPSOFC_16HZ: PPS output 16Hz frequency + \arg ENET_PPSOFC_32HZ: PPS output 32Hz frequency + \arg ENET_PPSOFC_64HZ: PPS output 64Hz frequency + \arg ENET_PPSOFC_128HZ: PPS output 128Hz frequency + \arg ENET_PPSOFC_256HZ: PPS output 256Hz frequency + \arg ENET_PPSOFC_512HZ: PPS output 512Hz frequency + \arg ENET_PPSOFC_1024HZ: PPS output 1024Hz frequency + \arg ENET_PPSOFC_2048HZ: PPS output 2048Hz frequency + \arg ENET_PPSOFC_4096HZ: PPS output 4096Hz frequency + \arg ENET_PPSOFC_8192HZ: PPS output 8192Hz frequency + \arg ENET_PPSOFC_16384HZ: PPS output 16384Hz frequency + \arg ENET_PPSOFC_32768HZ: PPS output 32768Hz frequency + \param[out] none + \retval none +*/ +void enet_ptp_pps_output_frequency_config(uint32_t freq) +{ + ENET_PTP_PPSCTL = freq; +} + +/*! + \brief configure and start PTP timestamp counter + \param[in] updatemethod: method for updating + \arg ENET_PTP_FINEMODE: fine correction method + \arg ENET_PTP_COARSEMODE: coarse correction method + \param[in] init_sec: second value for initializing system time + \param[in] init_subsec: subsecond value for initializing system time + \param[in] carry_cfg: the value to be added to the accumulator register (in fine method is used) + \param[in] accuracy_cfg: the value to be added to the subsecond value of system time + \param[out] none + \retval none +*/ +void enet_ptp_start(int32_t updatemethod, uint32_t init_sec, uint32_t init_subsec, uint32_t carry_cfg, + uint32_t accuracy_cfg) +{ + /* mask the timestamp trigger interrupt */ + enet_interrupt_disable(ENET_MAC_INT_TMSTIM); + + /* enable timestamp */ + enet_ptp_feature_enable(ENET_ALL_RX_TIMESTAMP | ENET_RXTX_TIMESTAMP); + + /* configure system time subsecond increment based on the PTP clock frequency */ + enet_ptp_subsecond_increment_config(accuracy_cfg); + + if(ENET_PTP_FINEMODE == updatemethod) { + /* fine correction method: configure the timestamp addend, then update */ + enet_ptp_timestamp_addend_config(carry_cfg); + enet_ptp_timestamp_function_config(ENET_PTP_ADDEND_UPDATE); + /* wait until update is completed */ + while(SET == enet_ptp_flag_get((uint32_t)ENET_PTP_ADDEND_UPDATE)) { + } + } + + /* choose the fine correction method */ + enet_ptp_timestamp_function_config((enet_ptp_function_enum)updatemethod); + + /* initialize the system time */ + enet_ptp_timestamp_update_config(ENET_PTP_ADD_TO_TIME, init_sec, init_subsec); + enet_ptp_timestamp_function_config(ENET_PTP_SYSTIME_INIT); + +#ifdef SELECT_DESCRIPTORS_ENHANCED_MODE + enet_desc_select_enhanced_mode(); +#endif /* SELECT_DESCRIPTORS_ENHANCED_MODE */ +} + +/*! + \brief adjust frequency in fine method by configure addend register + \param[in] carry_cfg: the value to be added to the accumulator register + \param[out] none + \retval none +*/ +void enet_ptp_finecorrection_adjfreq(int32_t carry_cfg) +{ + /* re-configure the timestamp addend, then update */ + enet_ptp_timestamp_addend_config((uint32_t)carry_cfg); + enet_ptp_timestamp_function_config(ENET_PTP_ADDEND_UPDATE); +} + +/*! + \brief update system time in coarse method + \param[in] systime_struct: : pointer to a enet_ptp_systime_struct structure which contains + parameters of PTP system time + members of the structure and the member values are shown as below: + second: 0x0 - 0xFFFF FFFF + nanosecond: 0x0 - 0x7FFF FFFF * 10^9 / 2^31 + sign: ENET_PTP_TIME_POSITIVE, ENET_PTP_TIME_NEGATIVE + \param[out] none + \retval none +*/ +void enet_ptp_coarsecorrection_systime_update(enet_ptp_systime_struct *systime_struct) +{ + uint32_t subsecond_val; + uint32_t carry_cfg; + + subsecond_val = enet_ptp_nanosecond_2_subsecond(systime_struct->nanosecond); + + /* save the carry_cfg value */ + carry_cfg = ENET_PTP_TSADDEND_TMSA; + + /* update the system time */ + enet_ptp_timestamp_update_config(systime_struct->sign, systime_struct->second, subsecond_val); + enet_ptp_timestamp_function_config(ENET_PTP_SYSTIME_UPDATE); + + /* wait until the update is completed */ + while(SET == enet_ptp_flag_get((uint32_t)ENET_PTP_SYSTIME_UPDATE)) { + } + + /* write back the carry_cfg value, then update */ + enet_ptp_timestamp_addend_config(carry_cfg); + enet_ptp_timestamp_function_config(ENET_PTP_ADDEND_UPDATE); +} + +/*! + \brief set system time in fine method + \param[in] systime_struct: : pointer to a enet_ptp_systime_struct structure which contains + parameters of PTP system time + members of the structure and the member values are shown as below: + second: 0x0 - 0xFFFF FFFF + nanosecond: 0x0 - 0x7FFF FFFF * 10^9 / 2^31 + sign: ENET_PTP_TIME_POSITIVE, ENET_PTP_TIME_NEGATIVE + \param[out] none + \retval none +*/ +void enet_ptp_finecorrection_settime(enet_ptp_systime_struct *systime_struct) +{ + uint32_t subsecond_val; + + subsecond_val = enet_ptp_nanosecond_2_subsecond(systime_struct->nanosecond); + + /* initialize the system time */ + enet_ptp_timestamp_update_config(systime_struct->sign, systime_struct->second, subsecond_val); + enet_ptp_timestamp_function_config(ENET_PTP_SYSTIME_INIT); + + /* wait until the system time initialzation finished */ + while(SET == enet_ptp_flag_get((uint32_t)ENET_PTP_SYSTIME_INIT)) { + } +} + +/*! + \brief get the ptp flag status + \param[in] flag: ptp flag status to be checked + \arg ENET_PTP_ADDEND_UPDATE: addend register update + \arg ENET_PTP_SYSTIME_UPDATE: timestamp update + \arg ENET_PTP_SYSTIME_INIT: timestamp initialize + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus enet_ptp_flag_get(uint32_t flag) +{ + FlagStatus bitstatus = RESET; + + if((uint32_t)RESET != (ENET_PTP_TSCTL & flag)) { + bitstatus = SET; + } + + return bitstatus; +} + +/*! + \brief reset the ENET initpara struct, call it before using enet_initpara_config() + \param[in] none + \param[out] none + \retval none +*/ +void enet_initpara_reset(void) +{ + enet_initpara.option_enable = 0U; + enet_initpara.forward_frame = 0U; + enet_initpara.dmabus_mode = 0U; + enet_initpara.dma_maxburst = 0U; + enet_initpara.dma_arbitration = 0U; + enet_initpara.store_forward_mode = 0U; + enet_initpara.dma_function = 0U; + enet_initpara.vlan_config = 0U; + enet_initpara.flow_control = 0U; + enet_initpara.hashtable_high = 0U; + enet_initpara.hashtable_low = 0U; + enet_initpara.framesfilter_mode = 0U; + enet_initpara.halfduplex_param = 0U; + enet_initpara.timer_config = 0U; + enet_initpara.interframegap = 0U; +} + +/*! + \brief initialize ENET peripheral with generally concerned parameters, call it by enet_init() + \param[in] none + \param[out] none + \retval none +*/ +static void enet_default_init(void) +{ + uint32_t reg_value = 0U; + + /* MAC */ + /* configure ENET_MAC_CFG register */ + reg_value = ENET_MAC_CFG; + reg_value &= MAC_CFG_MASK; + reg_value |= ENET_WATCHDOG_ENABLE | ENET_JABBER_ENABLE | ENET_INTERFRAMEGAP_96BIT \ + | ENET_SPEEDMODE_10M | ENET_MODE_HALFDUPLEX | ENET_LOOPBACKMODE_DISABLE \ + | ENET_CARRIERSENSE_ENABLE | ENET_RECEIVEOWN_ENABLE \ + | ENET_RETRYTRANSMISSION_ENABLE | ENET_BACKOFFLIMIT_10 \ + | ENET_DEFERRALCHECK_DISABLE \ + | ENET_TYPEFRAME_CRC_DROP_DISABLE \ + | ENET_AUTO_PADCRC_DROP_DISABLE \ + | ENET_CHECKSUMOFFLOAD_DISABLE; + ENET_MAC_CFG = reg_value; + + /* configure ENET_MAC_FRMF register */ + ENET_MAC_FRMF = ENET_SRC_FILTER_DISABLE | ENET_DEST_FILTER_INVERSE_DISABLE \ + | ENET_MULTICAST_FILTER_PERFECT | ENET_UNICAST_FILTER_PERFECT \ + | ENET_PCFRM_PREVENT_ALL | ENET_BROADCASTFRAMES_ENABLE \ + | ENET_PROMISCUOUS_DISABLE | ENET_RX_FILTER_ENABLE; + + /* configure ENET_MAC_HLH, ENET_MAC_HLL register */ + ENET_MAC_HLH = 0x0U; + + ENET_MAC_HLL = 0x0U; + + /* configure ENET_MAC_FCTL, ENET_MAC_FCTH register */ + reg_value = ENET_MAC_FCTL; + reg_value &= MAC_FCTL_MASK; + reg_value |= MAC_FCTL_PTM(0) | ENET_ZERO_QUANTA_PAUSE_DISABLE \ + | ENET_PAUSETIME_MINUS4 | ENET_UNIQUE_PAUSEDETECT \ + | ENET_RX_FLOWCONTROL_DISABLE | ENET_TX_FLOWCONTROL_DISABLE; + ENET_MAC_FCTL = reg_value; + + /* configure ENET_MAC_VLT register */ + ENET_MAC_VLT = ENET_VLANTAGCOMPARISON_16BIT | MAC_VLT_VLTI(0); + + /* disable MAC interrupt */ + ENET_MAC_INTMSK |= ENET_MAC_INTMSK_TMSTIM | ENET_MAC_INTMSK_WUMIM; + + /* MSC */ + /* disable MSC Rx interrupt */ + ENET_MSC_RINTMSK |= ENET_MSC_RINTMSK_RFAEIM | ENET_MSC_RINTMSK_RFCEIM \ + | ENET_MSC_RINTMSK_RGUFIM; + + /* disable MSC Tx interrupt */ + ENET_MSC_TINTMSK |= ENET_MSC_TINTMSK_TGFIM | ENET_MSC_TINTMSK_TGFMSCIM \ + | ENET_MSC_TINTMSK_TGFSCIM; + + /* DMA */ + /* configure ENET_DMA_CTL register */ + reg_value = ENET_DMA_CTL; + reg_value &= DMA_CTL_MASK; + reg_value |= ENET_TCPIP_CKSUMERROR_DROP | ENET_RX_MODE_STOREFORWARD \ + | ENET_FLUSH_RXFRAME_ENABLE | ENET_TX_MODE_STOREFORWARD \ + | ENET_TX_THRESHOLD_64BYTES | ENET_RX_THRESHOLD_64BYTES \ + | ENET_SECONDFRAME_OPT_DISABLE; + ENET_DMA_CTL = reg_value; + + /* configure ENET_DMA_BCTL register */ + reg_value = ENET_DMA_BCTL; + reg_value &= DMA_BCTL_MASK; + reg_value = ENET_ADDRESS_ALIGN_ENABLE | ENET_ARBITRATION_RXTX_2_1 \ + | ENET_RXDP_32BEAT | ENET_PGBL_32BEAT | ENET_RXTX_DIFFERENT_PGBL \ + | ENET_FIXED_BURST_ENABLE | ENET_MIXED_BURST_DISABLE \ + | ENET_NORMAL_DESCRIPTOR; + ENET_DMA_BCTL = reg_value; +} + +#ifndef USE_DELAY +/*! + \brief insert a delay time + \param[in] ncount: specifies the delay time length + \param[out] none + \param[out] none +*/ +static void enet_delay(uint32_t ncount) +{ + __IO uint32_t delay_time = 0U; + + for(delay_time = ncount; delay_time != 0U; delay_time--) { + } +} +#endif /* USE_DELAY */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_exmc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_exmc.c new file mode 100644 index 0000000..ebeac81 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_exmc.c @@ -0,0 +1,1264 @@ +/*! + \file gd32f5xx_exmc.c + \brief EXMC driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_exmc.h" + +/* EXMC bank0 register reset value */ +#define BANK0_SNCTL_RESET ((uint32_t)0x000030DAU) +#define BANK0_SNTCFG_RESET ((uint32_t)0x0FFFFFFFU) +#define BANK0_SNWTCFG_RESET ((uint32_t)0x0FFFFFFFU) + +/* EXMC bank1/2 register reset mask */ +#define BANK1_2_NPCTL_RESET ((uint32_t)0x00000008U) +#define BANK1_2_NPINTEN_RESET ((uint32_t)0x00000042U) +#define BANK1_2_NPCTCFG_RESET ((uint32_t)0xFFFFFFFFU) +#define BANK1_2_NPATCFG_RESET ((uint32_t)0xFFFFFFFFU) + +/* EXMC bank3 register reset mask */ +#define BANK3_NPCTL_RESET ((uint32_t)0x00000008U) +#define BANK3_NPINTEN_RESET ((uint32_t)0x00000040U) +#define BANK3_NPCTCFG_RESET ((uint32_t)0xFFFFFFFFU) +#define BANK3_NPATCFG_RESET ((uint32_t)0xFFFFFFFFU) +#define BANK3_PIOTCFG3_RESET ((uint32_t)0xFFFFFFFFU) + +/* EXMC SDRAM device register reset mask */ +#define SDRAM_DEVICE_SDCTL_RESET ((uint32_t)0x000002D0U) +#define SDRAM_DEVICE_SDTCFG_RESET ((uint32_t)0x0FFFFFFFU) +#define SDRAM_DEVICE_SDCMD_RESET ((uint32_t)0x00000000U) +#define SDRAM_DEVICE_SDARI_RESET ((uint32_t)0x00000000U) +#define SDRAM_DEVICE_SDSTAT_RESET ((uint32_t)0x00000000U) +#define SDRAM_DEVICE_SDRSCTL_RESET ((uint32_t)0x00000000U) + +/* EXMC bank0 SQPI-PSRAM register reset mask */ +#define BANK0_SQPI_SINIT_RESET ((uint32_t)0x18010000U) +#define BANK0_SQPI_SRCMD_RESET ((uint32_t)0x00000000U) +#define BANK0_SQPI_SWCMD_RESET ((uint32_t)0x00000000U) +#define BANK0_SQPI_SIDL_RESET ((uint32_t)0x00000000U) +#define BANK0_SQPI_SIDH_RESET ((uint32_t)0x00000000U) + +/* EXMC register bit offset */ +/* SNCTL offset */ +#define SNCTL_NRMUX_OFFSET ((uint32_t)1U) +#define SNCTL_SBRSTEN_OFFSET ((uint32_t)8U) +#define SNCTL_WRAPEN_OFFSET ((uint32_t)10U) +#define SNCTL_WREN_OFFSET ((uint32_t)12U) +#define SNCTL_NRWTEN_OFFSET ((uint32_t)13U) +#define SNCTL_EXMODEN_OFFSET ((uint32_t)14U) +#define SNCTL_ASYNCWAIT_OFFSET ((uint32_t)15U) + +/* SNTCFG offset */ +#define SNTCFG_AHLD_OFFSET ((uint32_t)4U) +#define SNTCFG_DSET_OFFSET ((uint32_t)8U) +#define SNTCFG_BUSLAT_OFFSET ((uint32_t)16U) + +/* NPCTL offset */ +#define NPCTL_NDWTEN_OFFSET ((uint32_t)1U) +#define NPCTL_ECCEN_OFFSET ((uint32_t)6U) + +/* NPCTCFG offset */ +#define NPCTCFG_COMWAIT_OFFSET ((uint32_t)8U) +#define NPCTCFG_COMHLD_OFFSET ((uint32_t)16U) +#define NPCTCFG_COMHIZ_OFFSET ((uint32_t)24U) + +/* NPATCFG offset */ +#define NPATCFG_ATTWAIT_OFFSET ((uint32_t)8U) +#define NPATCFG_ATTHLD_OFFSET ((uint32_t)16U) +#define NPATCFG_ATTHIZ_OFFSET ((uint32_t)24U) + +/* PIOTCFG offset */ +#define PIOTCFG_IOWAIT_OFFSET ((uint32_t)8U) +#define PIOTCFG_IOHLD_OFFSET ((uint32_t)16U) +#define PIOTCFG_IOHIZ_OFFSET ((uint32_t)24U) + +/* SDCTL offset */ +#define SDCTL_WPEN_OFFSET ((uint32_t)9U) +#define SDCTL_BRSTRD_OFFSET ((uint32_t)12U) + +/* SDTCFG offset */ +#define SDTCFG_XSRD_OFFSET ((uint32_t)4U) +#define SDTCFG_RASD_OFFSET ((uint32_t)8U) +#define SDTCFG_ARFD_OFFSET ((uint32_t)12U) +#define SDTCFG_WRD_OFFSET ((uint32_t)16U) +#define SDTCFG_RPD_OFFSET ((uint32_t)20U) +#define SDTCFG_RCD_OFFSET ((uint32_t)24U) + +/* SDCMD offset */ +#define SDCMD_NARF_OFFSET ((uint32_t)5U) +#define SDCMD_MRC_OFFSET ((uint32_t)9U) + +/* SDARI offset */ +#define SDARI_ARINTV_OFFSET ((uint32_t)1U) + +/* SDSTAT offset */ +#define SDSTAT_STA0_OFFSET ((uint32_t)1U) +#define SDSTAT_STA1_OFFSET ((uint32_t)3U) + +/* SRCMD offset */ +#define SRCMD_RWAITCYCLE_OFFSET ((uint32_t)16U) +#define SWCMD_WWAITCYCLE_OFFSET ((uint32_t)16U) + +/* INTEN offset */ +#define INTEN_INTS_OFFSET ((uint32_t)3U) + +/*! + \brief deinitialize EXMC NOR/SRAM region + \param[in] exmc_norsram_region: select the region of bank0 + only one parameter can be selected which is shown as below: + \arg EXMC_BANK0_NORSRAM_REGIONx(x=0..3) + \param[out] none + \retval none +*/ +void exmc_norsram_deinit(uint32_t exmc_norsram_region) +{ + /* reset the registers */ + EXMC_SNCTL(exmc_norsram_region) = BANK0_SNCTL_RESET; + EXMC_SNTCFG(exmc_norsram_region) = BANK0_SNTCFG_RESET; + EXMC_SNWTCFG(exmc_norsram_region) = BANK0_SNWTCFG_RESET; +} + +/*! + \brief initialize exmc_norsram_parameter_struct with the default values + \param[in] none + \param[out] exmc_norsram_init_struct: the initialized struct exmc_norsram_parameter_struct pointer + \retval none +*/ +void exmc_norsram_struct_para_init(exmc_norsram_parameter_struct *exmc_norsram_init_struct) +{ + /* configure the structure with default values */ + exmc_norsram_init_struct->norsram_region = EXMC_BANK0_NORSRAM_REGION0; + exmc_norsram_init_struct->address_data_mux = ENABLE; + exmc_norsram_init_struct->memory_type = EXMC_MEMORY_TYPE_SRAM; + exmc_norsram_init_struct->databus_width = EXMC_NOR_DATABUS_WIDTH_8B; + exmc_norsram_init_struct->burst_mode = DISABLE; + exmc_norsram_init_struct->nwait_polarity = EXMC_NWAIT_POLARITY_LOW; + exmc_norsram_init_struct->wrap_burst_mode = DISABLE; + exmc_norsram_init_struct->nwait_config = EXMC_NWAIT_CONFIG_BEFORE; + exmc_norsram_init_struct->memory_write = ENABLE; + exmc_norsram_init_struct->nwait_signal = ENABLE; + exmc_norsram_init_struct->extended_mode = DISABLE; + exmc_norsram_init_struct->asyn_wait = DISABLE; + exmc_norsram_init_struct->write_mode = EXMC_ASYN_WRITE; + + /* configure read/write timing */ + exmc_norsram_init_struct->read_write_timing->asyn_address_setuptime = 0xFU; + exmc_norsram_init_struct->read_write_timing->asyn_address_holdtime = 0xFU; + exmc_norsram_init_struct->read_write_timing->asyn_data_setuptime = 0xFFU; + exmc_norsram_init_struct->read_write_timing->bus_latency = 0xFU; + exmc_norsram_init_struct->read_write_timing->syn_clk_division = EXMC_SYN_CLOCK_RATIO_16_CLK; + exmc_norsram_init_struct->read_write_timing->syn_data_latency = EXMC_DATALAT_17_CLK; + exmc_norsram_init_struct->read_write_timing->syn_data_latency_dec = 0x0U; + exmc_norsram_init_struct->read_write_timing->asyn_access_mode = EXMC_ACCESS_MODE_A; + + /* configure write timing, when extended mode is used */ + exmc_norsram_init_struct->write_timing->asyn_address_setuptime = 0xFU; + exmc_norsram_init_struct->write_timing->asyn_address_holdtime = 0xFU; + exmc_norsram_init_struct->write_timing->asyn_data_setuptime = 0xFFU; + exmc_norsram_init_struct->write_timing->bus_latency = 0xFU; + exmc_norsram_init_struct->write_timing->asyn_access_mode = EXMC_ACCESS_MODE_A; +} + +/*! + \brief initialize EXMC NOR/SRAM region + \param[in] exmc_norsram_init_struct: configure the EXMC NOR/SRAM parameter + norsram_region: EXMC_BANK0_NORSRAM_REGIONx, x=0..3 + write_mode: EXMC_ASYN_WRITE, EXMC_SYN_WRITE + extended_mode: ENABLE or DISABLE + asyn_wait: ENABLE or DISABLE + nwait_signal: ENABLE or DISABLE + memory_write: ENABLE or DISABLE + nwait_config: EXMC_NWAIT_CONFIG_BEFORE, EXMC_NWAIT_CONFIG_DURING + wrap_burst_mode: ENABLE or DISABLE + nwait_polarity: EXMC_NWAIT_POLARITY_LOW, EXMC_NWAIT_POLARITY_HIGH + burst_mode: ENABLE or DISABLE + databus_width: EXMC_NOR_DATABUS_WIDTH_8B, EXMC_NOR_DATABUS_WIDTH_16B + memory_type: EXMC_MEMORY_TYPE_SRAM, EXMC_MEMORY_TYPE_PSRAM, EXMC_MEMORY_TYPE_NOR + address_data_mux: ENABLE or DISABLE + read_write_timing: struct exmc_norsram_timing_parameter_struct set the time + asyn_access_mode: EXMC_ACCESS_MODE_A, EXMC_ACCESS_MODE_B, EXMC_ACCESS_MODE_C, EXMC_ACCESS_MODE_D + syn_data_latency: EXMC_DATALAT_x_CLK, x=2..17 + syn_data_latency_dec: 0x1U~0x7U + syn_clk_division: EXMC_SYN_CLOCK_RATIO_DISABLE, EXMC_SYN_CLOCK_RATIO_x_CLK, x=2..16 + bus_latency: 0x0U~0xFU + asyn_data_setuptime: 0x01U~0xFFU + asyn_address_holdtime: 0x1U~0xFU + asyn_address_setuptime: 0x0U~0xFU + write_timing: struct exmc_norsram_timing_parameter_struct set the time + asyn_access_mode: EXMC_ACCESS_MODE_A, EXMC_ACCESS_MODE_B, EXMC_ACCESS_MODE_C, EXMC_ACCESS_MODE_D + bus_latency: 0x0U~0xFU + asyn_data_setuptime: 0x01U~0xFFU + asyn_address_holdtime: 0x1U~0xFU + asyn_address_setuptime: 0x0U~0xFU + \param[out] none + \retval none +*/ +void exmc_norsram_init(exmc_norsram_parameter_struct *exmc_norsram_init_struct) +{ + uint32_t snctl = 0x00000000U, sntcfg = 0x00000000U, snwtcfg = 0x00000000U, snlatdec = 0x00000000U; + + /* get the register value */ + snctl = EXMC_SNCTL(exmc_norsram_init_struct->norsram_region); + + /* clear relative bits */ + snctl &= ((uint32_t)~(EXMC_SNCTL_NREN | EXMC_SNCTL_NRTP | EXMC_SNCTL_NRW | EXMC_SNCTL_SBRSTEN | + EXMC_SNCTL_NRWTPOL | EXMC_SNCTL_WRAPEN | EXMC_SNCTL_NRWTCFG | EXMC_SNCTL_WEN | + EXMC_SNCTL_NRWTEN | EXMC_SNCTL_EXMODEN | EXMC_SNCTL_ASYNCWTEN | EXMC_SNCTL_SYNCWR | + EXMC_SNCTL_NRMUX)); + + /* configure control bits */ + snctl |= (uint32_t)(exmc_norsram_init_struct->address_data_mux << SNCTL_NRMUX_OFFSET) | + exmc_norsram_init_struct->memory_type | + exmc_norsram_init_struct->databus_width | + (exmc_norsram_init_struct->burst_mode << SNCTL_SBRSTEN_OFFSET) | + exmc_norsram_init_struct->nwait_polarity | + (exmc_norsram_init_struct->wrap_burst_mode << SNCTL_WRAPEN_OFFSET) | + exmc_norsram_init_struct->nwait_config | + (exmc_norsram_init_struct->memory_write << SNCTL_WREN_OFFSET) | + (exmc_norsram_init_struct->nwait_signal << SNCTL_NRWTEN_OFFSET) | + (exmc_norsram_init_struct->extended_mode << SNCTL_EXMODEN_OFFSET) | + (exmc_norsram_init_struct->asyn_wait << SNCTL_ASYNCWAIT_OFFSET) | + exmc_norsram_init_struct->write_mode; + + /* configure timing */ + sntcfg = (uint32_t)exmc_norsram_init_struct->read_write_timing->asyn_address_setuptime | + (exmc_norsram_init_struct->read_write_timing->asyn_address_holdtime << SNTCFG_AHLD_OFFSET) | + (exmc_norsram_init_struct->read_write_timing->asyn_data_setuptime << SNTCFG_DSET_OFFSET) | + (exmc_norsram_init_struct->read_write_timing->bus_latency << SNTCFG_BUSLAT_OFFSET) | + exmc_norsram_init_struct->read_write_timing->syn_clk_division | + exmc_norsram_init_struct->read_write_timing->syn_data_latency | + exmc_norsram_init_struct->read_write_timing->asyn_access_mode; + + /* configure data latency decreasing value */ + snlatdec = (uint32_t)(exmc_norsram_init_struct->read_write_timing->syn_data_latency_dec & EXMC_SNLATDEC_LATDEC); + + /* enable nor flash access */ + if(EXMC_MEMORY_TYPE_NOR == exmc_norsram_init_struct->memory_type) { + snctl |= (uint32_t)EXMC_SNCTL_NREN; + } + + /* configure extended mode */ + if(ENABLE == exmc_norsram_init_struct->extended_mode) { + snwtcfg = (uint32_t)exmc_norsram_init_struct->write_timing->asyn_address_setuptime | + (exmc_norsram_init_struct->write_timing->asyn_address_holdtime << SNTCFG_AHLD_OFFSET) | + (exmc_norsram_init_struct->write_timing->asyn_data_setuptime << SNTCFG_DSET_OFFSET) | + (exmc_norsram_init_struct->write_timing->bus_latency << SNTCFG_BUSLAT_OFFSET) | + exmc_norsram_init_struct->write_timing->asyn_access_mode; + } else { + snwtcfg = BANK0_SNWTCFG_RESET; + } + + /* configure the registers */ + EXMC_SNCTL(exmc_norsram_init_struct->norsram_region) = snctl; + EXMC_SNTCFG(exmc_norsram_init_struct->norsram_region) = sntcfg; + EXMC_SNWTCFG(exmc_norsram_init_struct->norsram_region) = snwtcfg; + EXMC_SNLATDEC(exmc_norsram_init_struct->norsram_region) = snlatdec; +} + +/*! + \brief enable EXMC NOR/PSRAM bank region + \param[in] exmc_norsram_region: specify the region of NOR/PSRAM bank + only one parameter can be selected which is shown as below: + \arg EXMC_BANK0_NORSRAM_REGIONx(x=0..3) + \param[out] none + \retval none +*/ +void exmc_norsram_enable(uint32_t exmc_norsram_region) +{ + EXMC_SNCTL(exmc_norsram_region) |= (uint32_t)EXMC_SNCTL_NRBKEN; +} + +/*! + \brief disable EXMC NOR/PSRAM bank region + \param[in] exmc_norsram_region: specify the region of NOR/PSRAM Bank + only one parameter can be selected which is shown as below: + \arg EXMC_BANK0_NORSRAM_REGIONx(x=0..3) + \param[out] none + \retval none +*/ +void exmc_norsram_disable(uint32_t exmc_norsram_region) +{ + EXMC_SNCTL(exmc_norsram_region) &= ~(uint32_t)EXMC_SNCTL_NRBKEN; +} + +/*! + \brief deinitialize EXMC NAND bank + \param[in] exmc_nand_bank: select the bank of NAND + only one parameter can be selected which is shown as below: + \arg EXMC_BANKx_NAND(x=1,2) + \param[out] none + \retval none +*/ +void exmc_nand_deinit(uint32_t exmc_nand_bank) +{ + /* EXMC_BANK1_NAND or EXMC_BANK2_NAND */ + EXMC_NPCTL(exmc_nand_bank) = BANK1_2_NPCTL_RESET; + EXMC_NPINTEN(exmc_nand_bank) = BANK1_2_NPINTEN_RESET; + EXMC_NPCTCFG(exmc_nand_bank) = BANK1_2_NPCTCFG_RESET; + EXMC_NPATCFG(exmc_nand_bank) = BANK1_2_NPATCFG_RESET; +} + +/*! + \brief initialize exmc_norsram_parameter_struct with the default values + \param[in] none + \param[out] the initialized struct exmc_nand_parameter_struct pointer + \retval none +*/ +void exmc_nand_struct_para_init(exmc_nand_parameter_struct *exmc_nand_init_struct) +{ + /* configure the structure with default values */ + exmc_nand_init_struct->nand_bank = EXMC_BANK1_NAND; + exmc_nand_init_struct->wait_feature = DISABLE; + exmc_nand_init_struct->databus_width = EXMC_NAND_DATABUS_WIDTH_8B; + exmc_nand_init_struct->ecc_logic = DISABLE; + exmc_nand_init_struct->ecc_size = EXMC_ECC_SIZE_256BYTES; + exmc_nand_init_struct->ctr_latency = 0x0U; + exmc_nand_init_struct->atr_latency = 0x0U; + exmc_nand_init_struct->common_space_timing->setuptime = 0xFCU; + exmc_nand_init_struct->common_space_timing->waittime = 0xFCU; + exmc_nand_init_struct->common_space_timing->holdtime = 0xFCU; + exmc_nand_init_struct->common_space_timing->databus_hiztime = 0xFCU; + exmc_nand_init_struct->attribute_space_timing->setuptime = 0xFCU; + exmc_nand_init_struct->attribute_space_timing->waittime = 0xFCU; + exmc_nand_init_struct->attribute_space_timing->holdtime = 0xFCU; + exmc_nand_init_struct->attribute_space_timing->databus_hiztime = 0xFCU; +} + +/*! + \brief initialize EXMC NAND bank + \param[in] exmc_nand_init_struct: configure the EXMC NAND parameter + nand_bank: EXMC_BANK1_NAND,EXMC_BANK2_NAND + ecc_size: EXMC_ECC_SIZE_xBYTES,x=256,512,1024,2048,4096 + atr_latency: EXMC_ALE_RE_DELAY_x_HCLK,x=1..16 + ctr_latency: EXMC_CLE_RE_DELAY_x_HCLK,x=1..16 + ecc_logic: ENABLE or DISABLE + databus_width: EXMC_NAND_DATABUS_WIDTH_8B,EXMC_NAND_DATABUS_WIDTH_16B + wait_feature: ENABLE or DISABLE + common_space_timing: struct exmc_nand_pccard_timing_parameter_struct set the time + databus_hiztime: 0x01U~0xFFU + holdtime: 0x01U~0xFEU + waittime: 0x02U~0xFFU + setuptime: 0x01U~0xFFU + attribute_space_timing: struct exmc_nand_pccard_timing_parameter_struct set the time + databus_hiztime: 0x00U~0xFEU + holdtime: 0x01U~0xFEU + waittime: 0x02U~0xFFU + setuptime: 0x01U~0xFFU + \param[out] none + \retval none +*/ +void exmc_nand_init(exmc_nand_parameter_struct *exmc_nand_init_struct) +{ + uint32_t npctl = 0x00000000U, npctcfg = 0x00000000U, npatcfg = 0x00000000U; + + npctl = (uint32_t)(exmc_nand_init_struct->wait_feature << NPCTL_NDWTEN_OFFSET) | + EXMC_NPCTL_NDTP | + exmc_nand_init_struct->databus_width | + (exmc_nand_init_struct->ecc_logic << NPCTL_ECCEN_OFFSET) | + exmc_nand_init_struct->ecc_size | + exmc_nand_init_struct->ctr_latency | + exmc_nand_init_struct->atr_latency; + + npctcfg = (uint32_t)((exmc_nand_init_struct->common_space_timing->setuptime - 1U) & EXMC_NPCTCFG_COMSET) | + (((exmc_nand_init_struct->common_space_timing->waittime - 1U) << NPCTCFG_COMWAIT_OFFSET) & EXMC_NPCTCFG_COMWAIT) | + ((exmc_nand_init_struct->common_space_timing->holdtime << NPCTCFG_COMHLD_OFFSET) & EXMC_NPCTCFG_COMHLD) | + (((exmc_nand_init_struct->common_space_timing->databus_hiztime - 1U) << NPCTCFG_COMHIZ_OFFSET) & EXMC_NPCTCFG_COMHIZ); + + npatcfg = (uint32_t)((exmc_nand_init_struct->attribute_space_timing->setuptime - 1U) & EXMC_NPATCFG_ATTSET) | + (((exmc_nand_init_struct->attribute_space_timing->waittime - 1U) << NPATCFG_ATTWAIT_OFFSET) & EXMC_NPATCFG_ATTWAIT) | + ((exmc_nand_init_struct->attribute_space_timing->holdtime << NPATCFG_ATTHLD_OFFSET) & EXMC_NPATCFG_ATTHLD) | + ((exmc_nand_init_struct->attribute_space_timing->databus_hiztime << NPATCFG_ATTHIZ_OFFSET) & EXMC_NPATCFG_ATTHIZ); + + /* initialize EXMC_BANK1_NAND or EXMC_BANK2_NAND */ + EXMC_NPCTL(exmc_nand_init_struct->nand_bank) = npctl; + EXMC_NPCTCFG(exmc_nand_init_struct->nand_bank) = npctcfg; + EXMC_NPATCFG(exmc_nand_init_struct->nand_bank) = npatcfg; +} + +/*! + \brief enable NAND bank + \param[in] exmc_nand_bank: specify the NAND bank + only one parameter can be selected which is shown as below: + \arg EXMC_BANKx_NAND(x=1,2) + \param[out] none + \retval none +*/ +void exmc_nand_enable(uint32_t exmc_nand_bank) +{ + EXMC_NPCTL(exmc_nand_bank) |= EXMC_NPCTL_NDBKEN; +} + +/*! + \brief disable NAND bank + \param[in] exmc_nand_bank: specify the NAND bank + only one parameter can be selected which is shown as below: + \arg EXMC_BANKx_NAND(x=1,2) + \param[out] none + \retval none +*/ +void exmc_nand_disable(uint32_t exmc_nand_bank) +{ + EXMC_NPCTL(exmc_nand_bank) &= ~EXMC_NPCTL_NDBKEN; +} + +/*! + \brief deinitialize EXMC PC card bank + \param[in] none + \param[out] none + \retval none +*/ +void exmc_pccard_deinit(void) +{ + /* EXMC_BANK3_PCCARD */ + EXMC_NPCTL3 = BANK3_NPCTL_RESET; + EXMC_NPINTEN3 = BANK3_NPINTEN_RESET; + EXMC_NPCTCFG3 = BANK3_NPCTCFG_RESET; + EXMC_NPATCFG3 = BANK3_NPATCFG_RESET; + EXMC_PIOTCFG3 = BANK3_PIOTCFG3_RESET; +} + +/*! + \brief initialize exmc_pccard_parameter_struct with the default values + \param[in] none + \param[out] the initialized struct exmc_pccard_parameter_struct pointer + \retval none +*/ +void exmc_pccard_struct_para_init(exmc_pccard_parameter_struct *exmc_pccard_init_struct) +{ + /* configure the structure with default values */ + exmc_pccard_init_struct->wait_feature = DISABLE; + exmc_pccard_init_struct->ctr_latency = 0x0U; + exmc_pccard_init_struct->atr_latency = 0x0U; + exmc_pccard_init_struct->common_space_timing->setuptime = 0xFCU; + exmc_pccard_init_struct->common_space_timing->waittime = 0xFCU; + exmc_pccard_init_struct->common_space_timing->holdtime = 0xFCU; + exmc_pccard_init_struct->common_space_timing->databus_hiztime = 0xFCU; + exmc_pccard_init_struct->attribute_space_timing->setuptime = 0xFCU; + exmc_pccard_init_struct->attribute_space_timing->waittime = 0xFCU; + exmc_pccard_init_struct->attribute_space_timing->holdtime = 0xFCU; + exmc_pccard_init_struct->attribute_space_timing->databus_hiztime = 0xFCU; + exmc_pccard_init_struct->io_space_timing->setuptime = 0xFCU; + exmc_pccard_init_struct->io_space_timing->waittime = 0xFCU; + exmc_pccard_init_struct->io_space_timing->holdtime = 0xFCU; + exmc_pccard_init_struct->io_space_timing->databus_hiztime = 0xFCU; +} + +/*! + \brief initialize EXMC PC card bank + \param[in] exmc_pccard_init_struct: configure the EXMC NAND parameter + atr_latency: EXMC_ALE_RE_DELAY_x_HCLK,x=1..16 + ctr_latency: EXMC_CLE_RE_DELAY_x_HCLK,x=1..16 + wait_feature: ENABLE or DISABLE + common_space_timing: struct exmc_nand_pccard_timing_parameter_struct set the time + databus_hiztime: 0x01U~0xFFU + holdtime: 0x01U~0xFEU + waittime: 0x02U~0xFFU + setuptime: 0x01U~0xFFU + attribute_space_timing: struct exmc_nand_pccard_timing_parameter_struct set the time + databus_hiztime: 0x00U~0xFEU + holdtime: 0x01U~0xFEU + waittime: 0x02U~0xFFU + setuptime: 0x01U~0xFFU + io_space_timing: exmc_nand_pccard_timing_parameter_struct set the time + databus_hiztime: 0x00U~0xFFU + holdtime: 0x01U~0xFFU + waittime: 0x02U~0x100U + setuptime: 0x01U~0x100U + \param[out] none + \retval none +*/ +void exmc_pccard_init(exmc_pccard_parameter_struct *exmc_pccard_init_struct) +{ + /* configure the EXMC bank3 PC card control register */ + EXMC_NPCTL3 = (uint32_t)(exmc_pccard_init_struct->wait_feature << NPCTL_NDWTEN_OFFSET) | + EXMC_NAND_DATABUS_WIDTH_16B | + exmc_pccard_init_struct->ctr_latency | + exmc_pccard_init_struct->atr_latency ; + + /* configure the EXMC bank3 PC card common space timing configuration register */ + EXMC_NPCTCFG3 = (uint32_t)((exmc_pccard_init_struct->common_space_timing->setuptime - 1U) & EXMC_NPCTCFG_COMSET) | + (((exmc_pccard_init_struct->common_space_timing->waittime - 1U) << NPCTCFG_COMWAIT_OFFSET) & EXMC_NPCTCFG_COMWAIT) | + ((exmc_pccard_init_struct->common_space_timing->holdtime << NPCTCFG_COMHLD_OFFSET) & EXMC_NPCTCFG_COMHLD) | + (((exmc_pccard_init_struct->common_space_timing->databus_hiztime - 1U) << NPCTCFG_COMHIZ_OFFSET) & EXMC_NPCTCFG_COMHIZ); + + /* configure the EXMC bank3 PC card attribute space timing configuration register */ + EXMC_NPATCFG3 = (uint32_t)((exmc_pccard_init_struct->attribute_space_timing->setuptime - 1U) & EXMC_NPATCFG_ATTSET) | + (((exmc_pccard_init_struct->attribute_space_timing->waittime - 1U) << NPATCFG_ATTWAIT_OFFSET) & EXMC_NPATCFG_ATTWAIT) | + ((exmc_pccard_init_struct->attribute_space_timing->holdtime << NPATCFG_ATTHLD_OFFSET) & EXMC_NPATCFG_ATTHLD) | + ((exmc_pccard_init_struct->attribute_space_timing->databus_hiztime << NPATCFG_ATTHIZ_OFFSET) & EXMC_NPATCFG_ATTHIZ); + + /* configure the EXMC bank3 PC card io space timing configuration register */ + EXMC_PIOTCFG3 = (uint32_t)((exmc_pccard_init_struct->io_space_timing->setuptime - 1U) & EXMC_PIOTCFG3_IOSET) | + (((exmc_pccard_init_struct->io_space_timing->waittime - 1U) << PIOTCFG_IOWAIT_OFFSET) & EXMC_PIOTCFG3_IOWAIT) | + ((exmc_pccard_init_struct->io_space_timing->holdtime << PIOTCFG_IOHLD_OFFSET) & EXMC_PIOTCFG3_IOHLD) | + ((exmc_pccard_init_struct->io_space_timing->databus_hiztime << PIOTCFG_IOHIZ_OFFSET) & EXMC_PIOTCFG3_IOHIZ); +} + +/*! + \brief enable PC Card Bank + \param[in] none + \param[out] none + \retval none +*/ +void exmc_pccard_enable(void) +{ + EXMC_NPCTL3 |= EXMC_NPCTL_NDBKEN; +} + +/*! + \brief disable PC Card Bank + \param[in] none + \param[out] none + \retval none +*/ +void exmc_pccard_disable(void) +{ + EXMC_NPCTL3 &= ~EXMC_NPCTL_NDBKEN; +} + +/*! + \brief deinitialize EXMC SDRAM device + \param[in] exmc_sdram_device: select the SRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_SDRAM_DEVICEx(x=0, 1) + \param[in] none + \param[out] none + \retval none +*/ +void exmc_sdram_deinit(uint32_t exmc_sdram_device) +{ + /* reset SDRAM registers */ + EXMC_SDCTL(exmc_sdram_device) = SDRAM_DEVICE_SDCTL_RESET; + EXMC_SDTCFG(exmc_sdram_device) = SDRAM_DEVICE_SDTCFG_RESET; + EXMC_SDCMD = SDRAM_DEVICE_SDCMD_RESET; + EXMC_SDARI = SDRAM_DEVICE_SDARI_RESET; + EXMC_SDRSCTL = SDRAM_DEVICE_SDRSCTL_RESET; +} + +/*! + \brief initialize exmc_sdram_parameter_struct with the default values + \param[in] none + \param[out] the initialized struct exmc_sdram_parameter_struct pointer + \retval none +*/ +void exmc_sdram_struct_para_init(exmc_sdram_parameter_struct *exmc_sdram_init_struct) +{ + /* configure the structure with default values */ + exmc_sdram_init_struct->sdram_device = EXMC_SDRAM_DEVICE0; + exmc_sdram_init_struct->column_address_width = EXMC_SDRAM_COW_ADDRESS_8; + exmc_sdram_init_struct->row_address_width = EXMC_SDRAM_ROW_ADDRESS_11; + exmc_sdram_init_struct->data_width = EXMC_SDRAM_DATABUS_WIDTH_16B; + exmc_sdram_init_struct->internal_bank_number = EXMC_SDRAM_4_INTER_BANK; + exmc_sdram_init_struct->cas_latency = EXMC_CAS_LATENCY_1_SDCLK; + exmc_sdram_init_struct->write_protection = ENABLE; + exmc_sdram_init_struct->sdclock_config = EXMC_SDCLK_DISABLE; + exmc_sdram_init_struct->burst_read_switch = DISABLE; + exmc_sdram_init_struct->pipeline_read_delay = EXMC_PIPELINE_DELAY_0_HCLK; + + exmc_sdram_init_struct->timing->load_mode_register_delay = 16U; + exmc_sdram_init_struct->timing->exit_selfrefresh_delay = 16U; + exmc_sdram_init_struct->timing->row_address_select_delay = 16U; + exmc_sdram_init_struct->timing->auto_refresh_delay = 16U; + exmc_sdram_init_struct->timing->write_recovery_delay = 16U; + exmc_sdram_init_struct->timing->row_precharge_delay = 16U; + exmc_sdram_init_struct->timing->row_to_column_delay = 16U; +} + +/*! + \brief initialize EXMC SDRAM device + \param[in] exmc_sdram_init_struct: configure the EXMC SDRAM parameter + sdram_device: EXMC_SDRAM_DEVICE0,EXMC_SDRAM_DEVICE1 + pipeline_read_delay: EXMC_PIPELINE_DELAY_x_HCLK,x=0..2 + burst_read_switch: ENABLE or DISABLE + sdclock_config: EXMC_SDCLK_DISABLE,EXMC_SDCLK_PERIODS_2_HCLK,EXMC_SDCLK_PERIODS_3_HCLK + write_protection: ENABLE or DISABLE + cas_latency: EXMC_CAS_LATENCY_x_SDCLK,x=1..3 + internal_bank_number: EXMC_SDRAM_2_INTER_BANK,EXMC_SDRAM_4_INTER_BANK + data_width: EXMC_SDRAM_DATABUS_WIDTH_8B,EXMC_SDRAM_DATABUS_WIDTH_16B,EXMC_SDRAM_DATABUS_WIDTH_32B + row_address_width: EXMC_SDRAM_ROW_ADDRESS_x,x=11..13 + column_address_width: EXMC_SDRAM_COW_ADDRESS_x,x=8..11 + timing: exmc_sdram_timing_parameter_struct set the time + row_to_column_delay: 1U~16U + row_precharge_delay: 1U~16U + write_recovery_delay: 1U~16U + auto_refresh_delay: 1U~16U + row_address_select_delay: 1U~16U + exit_selfrefresh_delay: 1U~16U + load_mode_register_delay: 1U~16U + \param[out] none + \retval none +*/ +void exmc_sdram_init(exmc_sdram_parameter_struct *exmc_sdram_init_struct) +{ + uint32_t sdctl0, sdctl1, sdtcfg0, sdtcfg1; + + /* configure EXMC_SDCTL0 or EXMC_SDCTL1 */ + if(EXMC_SDRAM_DEVICE0 == exmc_sdram_init_struct->sdram_device) { + /* configure EXMC_SDCTL0 */ + EXMC_SDCTL(EXMC_SDRAM_DEVICE0) = (uint32_t)(exmc_sdram_init_struct->column_address_width | + exmc_sdram_init_struct->row_address_width | + exmc_sdram_init_struct->data_width | + exmc_sdram_init_struct->internal_bank_number | + exmc_sdram_init_struct->cas_latency | + (exmc_sdram_init_struct->write_protection << SDCTL_WPEN_OFFSET) | + exmc_sdram_init_struct->sdclock_config | + (exmc_sdram_init_struct->burst_read_switch << SDCTL_BRSTRD_OFFSET) | + exmc_sdram_init_struct->pipeline_read_delay); + + /* configure EXMC_SDTCFG0 */ + EXMC_SDTCFG(EXMC_SDRAM_DEVICE0) = (uint32_t)((exmc_sdram_init_struct->timing->load_mode_register_delay) - 1U) | + (((exmc_sdram_init_struct->timing->exit_selfrefresh_delay) - 1U) << SDTCFG_XSRD_OFFSET) | + (((exmc_sdram_init_struct->timing->row_address_select_delay) - 1U) << SDTCFG_RASD_OFFSET) | + (((exmc_sdram_init_struct->timing->auto_refresh_delay) - 1U) << SDTCFG_ARFD_OFFSET) | + (((exmc_sdram_init_struct->timing->write_recovery_delay) - 1U) << SDTCFG_WRD_OFFSET) | + (((exmc_sdram_init_struct->timing->row_precharge_delay) - 1U) << SDTCFG_RPD_OFFSET) | + (((exmc_sdram_init_struct->timing->row_to_column_delay) - 1U) << SDTCFG_RCD_OFFSET); + } else { + /* configure EXMC_SDCTL0 and EXMC_SDCTL1 */ + /* some bits in the EXMC_SDCTL1 register are reserved */ + sdctl0 = EXMC_SDCTL(EXMC_SDRAM_DEVICE0) & (~(EXMC_SDCTL_PIPED | EXMC_SDCTL_BRSTRD | EXMC_SDCTL_SDCLK)); + + sdctl0 |= (uint32_t)(exmc_sdram_init_struct->sdclock_config | + (exmc_sdram_init_struct->burst_read_switch << SDCTL_BRSTRD_OFFSET) | + exmc_sdram_init_struct->pipeline_read_delay); + + sdctl1 = (uint32_t)(exmc_sdram_init_struct->column_address_width | + exmc_sdram_init_struct->row_address_width | + exmc_sdram_init_struct->data_width | + exmc_sdram_init_struct->internal_bank_number | + exmc_sdram_init_struct->cas_latency | + (exmc_sdram_init_struct->write_protection << SDCTL_WPEN_OFFSET)); + + EXMC_SDCTL(EXMC_SDRAM_DEVICE0) = sdctl0; + EXMC_SDCTL(EXMC_SDRAM_DEVICE1) = sdctl1; + + /* configure EXMC_SDTCFG0 and EXMC_SDTCFG1 */ + /* some bits in the EXMC_SDTCFG1 register are reserved */ + sdtcfg0 = EXMC_SDTCFG(EXMC_SDRAM_DEVICE0) & (~(EXMC_SDTCFG_RPD | EXMC_SDTCFG_WRD | EXMC_SDTCFG_ARFD)); + + sdtcfg0 |= (uint32_t)((((exmc_sdram_init_struct->timing->auto_refresh_delay) - 1U) << SDTCFG_ARFD_OFFSET) | + (((exmc_sdram_init_struct->timing->row_precharge_delay) - 1U) << SDTCFG_RPD_OFFSET) | + (((exmc_sdram_init_struct->timing->write_recovery_delay) - 1U) << SDTCFG_WRD_OFFSET)); + + sdtcfg1 = (uint32_t)(((exmc_sdram_init_struct->timing->load_mode_register_delay) - 1U) | + (((exmc_sdram_init_struct->timing->exit_selfrefresh_delay) - 1U) << SDTCFG_XSRD_OFFSET) | + (((exmc_sdram_init_struct->timing->row_address_select_delay) - 1U) << SDTCFG_RASD_OFFSET) | + (((exmc_sdram_init_struct->timing->row_to_column_delay) - 1U) << SDTCFG_RCD_OFFSET)); + + EXMC_SDTCFG(EXMC_SDRAM_DEVICE0) = sdtcfg0; + EXMC_SDTCFG(EXMC_SDRAM_DEVICE1) = sdtcfg1; + } +} + +/*! + \brief initialize exmc_sdram_struct_command_para_init with the default values + \param[in] none + \param[out] the initialized struct exmc_sdram_struct_command_para_init pointer + \retval none +*/ +void exmc_sdram_struct_command_para_init(exmc_sdram_command_parameter_struct *exmc_sdram_command_init_struct) +{ + /* configure the structure with default value */ + exmc_sdram_command_init_struct->mode_register_content = 0U; + exmc_sdram_command_init_struct->auto_refresh_number = EXMC_SDRAM_AUTO_REFLESH_1_SDCLK; + exmc_sdram_command_init_struct->bank_select = EXMC_SDRAM_DEVICE0_SELECT; + exmc_sdram_command_init_struct->command = EXMC_SDRAM_NORMAL_OPERATION; +} + +/*! + \brief deinitialize exmc SQPIPSRAM + \param[in] none + \param[out] none + \retval none +*/ +void exmc_sqpipsram_deinit(void) +{ + /* reset the registers */ + EXMC_SINIT = BANK0_SQPI_SINIT_RESET; + EXMC_SRCMD = BANK0_SQPI_SRCMD_RESET; + EXMC_SWCMD = BANK0_SQPI_SWCMD_RESET; + EXMC_SIDL = BANK0_SQPI_SIDL_RESET; + EXMC_SIDH = BANK0_SQPI_SIDH_RESET; +} + +/*! + \brief initialize exmc_sqpipsram_parameter_struct with the default values + \param[in] none + \param[out] the struct exmc_sqpipsram_parameter_struct pointer + \retval none +*/ +void exmc_sqpipsram_struct_para_init(exmc_sqpipsram_parameter_struct *exmc_sqpipsram_init_struct) +{ + /* configure the structure with default values */ + exmc_sqpipsram_init_struct->sample_polarity = EXMC_SQPIPSRAM_SAMPLE_RISING_EDGE; + exmc_sqpipsram_init_struct->id_length = EXMC_SQPIPSRAM_ID_LENGTH_64B; + exmc_sqpipsram_init_struct->address_bits = EXMC_SQPIPSRAM_ADDR_LENGTH_24B; + exmc_sqpipsram_init_struct->command_bits = EXMC_SQPIPSRAM_COMMAND_LENGTH_8B; +} + +/*! + \brief initialize EXMC SQPIPSRAM + \param[in] exmc_sqpipsram_init_struct: configure the EXMC SQPIPSRAM parameter + sample_polarity: EXMC_SQPIPSRAM_SAMPLE_RISING_EDGE,EXMC_SQPIPSRAM_SAMPLE_FALLING_EDGE + id_length: EXMC_SQPIPSRAM_ID_LENGTH_xB,x=8,16,32,64 + address_bits: EXMC_SQPIPSRAM_ADDR_LENGTH_xB,x=1..26 + command_bits: EXMC_SQPIPSRAM_COMMAND_LENGTH_xB,x=4,8,16 + \param[out] none + \retval none +*/ +void exmc_sqpipsram_init(exmc_sqpipsram_parameter_struct *exmc_sqpipsram_init_struct) +{ + /* initialize SQPI controller */ + EXMC_SINIT = (uint32_t)exmc_sqpipsram_init_struct->sample_polarity | + exmc_sqpipsram_init_struct->id_length | + exmc_sqpipsram_init_struct->address_bits | + exmc_sqpipsram_init_struct->command_bits; +} + +/*! + \brief configure consecutive clock + \param[in] clock_mode: specify when the clock is generated + only one parameter can be selected which is shown as below: + \arg EXMC_CLOCK_SYN_MODE: the clock is generated only during synchronous access + \arg EXMC_CLOCK_UNCONDITIONALLY: the clock is generated unconditionally + \param[out] none + \retval none +*/ +void exmc_norsram_consecutive_clock_config(uint32_t clock_mode) +{ + if(EXMC_CLOCK_UNCONDITIONALLY == clock_mode) { + EXMC_SNCTL(EXMC_BANK0_NORSRAM_REGION0) |= EXMC_CLOCK_UNCONDITIONALLY; + } else { + EXMC_SNCTL(EXMC_BANK0_NORSRAM_REGION0) &= ~EXMC_CLOCK_UNCONDITIONALLY; + } +} + +/*! + \brief configure CRAM page size + \param[in] exmc_norsram_region: select the region of bank0 + only one parameter can be selected which is shown as below: + \arg EXMC_BANK0_NORSRAM_REGIONx(x=0..3) + \param[in] page_size: CRAM page size + only one parameter can be selected which is shown as below: + \arg EXMC_CRAM_AUTO_SPLIT: the clock is generated only during synchronous access + \arg EXMC_CRAM_PAGE_SIZE_128_BYTES: page size is 128 bytes + \arg EXMC_CRAM_PAGE_SIZE_256_BYTES: page size is 256 bytes + \arg EXMC_CRAM_PAGE_SIZE_512_BYTES: page size is 512 bytes + \arg EXMC_CRAM_PAGE_SIZE_1024_BYTES: page size is 1024 bytes + \param[out] none + \retval none +*/ +void exmc_norsram_page_size_config(uint32_t exmc_norsram_region, uint32_t page_size) +{ + /* reset the bits */ + EXMC_SNCTL(exmc_norsram_region) &= ~EXMC_SNCTL_CPS; + + /* set the CPS bits */ + EXMC_SNCTL(exmc_norsram_region) |= page_size; +} + +/*! + \brief enable or disable the EXMC NAND ECC function + \param[in] exmc_nand_bank: specify the NAND bank + only one parameter can be selected which is shown as below: + \arg EXMC_BANKx_NAND(x=1,2) + \param[in] newvalue: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void exmc_nand_ecc_config(uint32_t exmc_nand_bank, ControlStatus newvalue) +{ + if(ENABLE == newvalue) { + /* enable the selected NAND bank ECC function */ + EXMC_NPCTL(exmc_nand_bank) |= EXMC_NPCTL_ECCEN; + } else { + /* disable the selected NAND bank ECC function */ + EXMC_NPCTL(exmc_nand_bank) &= ~EXMC_NPCTL_ECCEN; + } +} + +/*! + \brief get the EXMC ECC value + \param[in] exmc_nand_bank: specify the NAND bank + only one parameter can be selected which is shown as below: + \arg EXMC_BANKx_NAND(x=1,2) + \param[out] none + \retval the error correction code(ECC) value +*/ +uint32_t exmc_ecc_get(uint32_t exmc_nand_bank) +{ + return(EXMC_NECC(exmc_nand_bank)); +} + +/*! + \brief enable or disable read sample + \param[in] newvalue: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void exmc_sdram_readsample_enable(ControlStatus newvalue) +{ + if(ENABLE == newvalue) { + EXMC_SDRSCTL |= EXMC_SDRSCTL_RSEN; + } else { + EXMC_SDRSCTL &= (uint32_t)(~EXMC_SDRSCTL_RSEN); + } +} + +/*! + \brief configure the delayed sample clock of read data + \param[in] delay_cell: SDRAM the delayed sample clock of read data + only one parameter can be selected which is shown as below: + \arg EXMC_SDRAM_x_DELAY_CELL(x=0..15) + \param[in] extra_hclk: sample cycle of read data + only one parameter can be selected which is shown as below: + \arg EXMC_SDRAM_READSAMPLE_x_EXTRAHCLK(x=0,1) + \param[out] none + \retval none +*/ +void exmc_sdram_readsample_config(uint32_t delay_cell, uint32_t extra_hclk) +{ + uint32_t sdrsctl = 0U; + + /* reset the bits */ + sdrsctl = EXMC_SDRSCTL & (~(EXMC_SDRSCTL_SDSC | EXMC_SDRSCTL_SSCR)); + /* set the bits */ + sdrsctl |= (uint32_t)(delay_cell | extra_hclk); + EXMC_SDRSCTL = sdrsctl; +} + +/*! + \brief configure the SDRAM memory command + \param[in] exmc_sdram_command_init_struct: initialize EXMC SDRAM command + mode_register_content: + auto_refresh_number: EXMC_SDRAM_AUTO_REFLESH_x_SDCLK, x=1..15 + bank_select: EXMC_SDRAM_DEVICE0_SELECT, EXMC_SDRAM_DEVICE1_SELECT, EXMC_SDRAM_DEVICE0_1_SELECT + command: EXMC_SDRAM_NORMAL_OPERATION, EXMC_SDRAM_CLOCK_ENABLE, EXMC_SDRAM_PRECHARGE_ALL, + EXMC_SDRAM_AUTO_REFRESH, EXMC_SDRAM_LOAD_MODE_REGISTER, EXMC_SDRAM_SELF_REFRESH, + EXMC_SDRAM_POWERDOWN_ENTRY + \param[out] none + \retval none +*/ +void exmc_sdram_command_config(exmc_sdram_command_parameter_struct *exmc_sdram_command_init_struct) +{ + /* configure command register */ + EXMC_SDCMD = (uint32_t)((exmc_sdram_command_init_struct->command) | + (exmc_sdram_command_init_struct->bank_select) | + ((exmc_sdram_command_init_struct->auto_refresh_number)) | + ((exmc_sdram_command_init_struct->mode_register_content) << SDCMD_MRC_OFFSET)); +} + +/*! + \brief set auto-refresh interval + \param[in] exmc_count: the number SDRAM clock cycles unit between two successive auto-refresh commands, 0x0000~0x1FFF + \param[out] none + \retval none +*/ +void exmc_sdram_refresh_count_set(uint32_t exmc_count) +{ + uint32_t sdari; + sdari = EXMC_SDARI & (~EXMC_SDARI_ARINTV); + EXMC_SDARI = sdari | (uint32_t)((exmc_count << SDARI_ARINTV_OFFSET) & EXMC_SDARI_ARINTV); +} + +/*! + \brief set the number of successive auto-refresh command + \param[in] exmc_number: the number of successive Auto-refresh cycles will be send, 1~15 + \param[out] none + \retval none +*/ +void exmc_sdram_autorefresh_number_set(uint32_t exmc_number) +{ + uint32_t sdcmd; + sdcmd = EXMC_SDCMD & (~EXMC_SDCMD_NARF); + EXMC_SDCMD = sdcmd | (uint32_t)((exmc_number << SDCMD_NARF_OFFSET) & EXMC_SDCMD_NARF) ; +} + +/*! + \brief configure the write protection function + \param[in] exmc_sdram_device: specify the SDRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_SDRAM_DEVICEx(x=0,1) + \param[in] newvalue: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void exmc_sdram_write_protection_config(uint32_t exmc_sdram_device, ControlStatus newvalue) +{ + if(ENABLE == newvalue) { + EXMC_SDCTL(exmc_sdram_device) |= (uint32_t)EXMC_SDCTL_WPEN; + } else { + EXMC_SDCTL(exmc_sdram_device) &= ~((uint32_t)EXMC_SDCTL_WPEN); + } +} + +/*! + \brief get the status of SDRAM device0 or device1 + \param[in] exmc_sdram_device: specify the SDRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_SDRAM_DEVICEx(x=0,1) + \param[out] none + \retval the status of SDRAM device +*/ +uint32_t exmc_sdram_bankstatus_get(uint32_t exmc_sdram_device) +{ + uint32_t sdstat = 0U; + + if(EXMC_SDRAM_DEVICE0 == exmc_sdram_device) { + sdstat = ((uint32_t)(EXMC_SDSTAT & EXMC_SDSDAT_STA0) >> SDSTAT_STA0_OFFSET); + } else { + sdstat = ((uint32_t)(EXMC_SDSTAT & EXMC_SDSDAT_STA1) >> SDSTAT_STA1_OFFSET); + } + + return sdstat; +} + +/*! + \brief set the read command + \param[in] read_command_mode: configure SPI PSRAM read command mode + only one parameter can be selected which is shown as below: + \arg EXMC_SQPIPSRAM_READ_MODE_DISABLE: not SPI mode + \arg EXMC_SQPIPSRAM_READ_MODE_SPI: SPI mode + \arg EXMC_SQPIPSRAM_READ_MODE_SQPI: SQPI mode + \arg EXMC_SQPIPSRAM_READ_MODE_QPI: QPI mode + \param[in] read_wait_cycle: wait cycle number after address phase,0..15 + \param[in] read_command_code: read command for AHB read transfer + \param[out] none + \retval none +*/ +void exmc_sqpipsram_read_command_set(uint32_t read_command_mode, uint32_t read_wait_cycle, uint32_t read_command_code) +{ + uint32_t srcmd; + + srcmd = (uint32_t) read_command_mode | + ((read_wait_cycle << SRCMD_RWAITCYCLE_OFFSET) & EXMC_SRCMD_RWAITCYCLE) | + ((read_command_code & EXMC_SRCMD_RCMD)); + EXMC_SRCMD = srcmd; +} + +/*! + \brief set the write command + \param[in] write_command_mode: configure SPI PSRAM write command mode + only one parameter can be selected which is shown as below: + \arg EXMC_SQPIPSRAM_WRITE_MODE_DISABLE: not SPI mode + \arg EXMC_SQPIPSRAM_WRITE_MODE_SPI: SPI mode + \arg EXMC_SQPIPSRAM_WRITE_MODE_SQPI: SQPI mode + \arg EXMC_SQPIPSRAM_WRITE_MODE_QPI: QPI mode + \param[in] write_wait_cycle: wait cycle number after address phase,0..15 + \param[in] write_command_code: read command for AHB read transfer + \param[out] none + \retval none +*/ +void exmc_sqpipsram_write_command_set(uint32_t write_command_mode, uint32_t write_wait_cycle, uint32_t write_command_code) +{ + uint32_t swcmd; + + swcmd = (uint32_t) write_command_mode | + ((write_wait_cycle << SWCMD_WWAITCYCLE_OFFSET) & EXMC_SWCMD_WWAITCYCLE) | + ((write_command_code & EXMC_SWCMD_WCMD)); + EXMC_SWCMD = swcmd; +} + +/*! + \brief send SPI read ID command + \param[in] none + \param[out] none + \retval none +*/ +void exmc_sqpipsram_read_id_command_send(void) +{ + EXMC_SRCMD |= EXMC_SRCMD_RDID; +} + +/*! + \brief send SPI special command which does not have address and data phase + \param[in] none + \param[out] none + \retval none +*/ +void exmc_sqpipsram_write_cmd_send(void) +{ + EXMC_SWCMD |= EXMC_SWCMD_SC; +} + +/*! + \brief get the EXMC SPI ID low data + \param[in] none + \param[out] none + \retval the ID low data +*/ +uint32_t exmc_sqpipsram_low_id_get(void) +{ + return (EXMC_SIDL); +} + +/*! + \brief get the EXMC SPI ID high data + \param[in] none + \param[out] none + \retval the ID high data +*/ +uint32_t exmc_sqpipsram_high_id_get(void) +{ + return (EXMC_SIDH); +} + +/*! + \brief get the bit value of EXMC send write command bit or read ID command + \param[in] send_command_flag: the send command flag + only one parameter can be selected which is shown as below: + \arg EXMC_SEND_COMMAND_FLAG_RDID: EXMC_SRCMD_RDID flag bit + \arg EXMC_SEND_COMMAND_FLAG_SC: EXMC_SWCMD_SC flag bit + \param[out] none + \retval the new value of send command flag +*/ +FlagStatus exmc_sqpipsram_send_command_state_get(uint32_t send_command_flag) +{ + uint32_t flag = 0x00000000U; + + if(EXMC_SEND_COMMAND_FLAG_RDID == send_command_flag) { + flag = EXMC_SRCMD; + } else if(EXMC_SEND_COMMAND_FLAG_SC == send_command_flag) { + flag = EXMC_SWCMD; + } else { + } + + if(flag & send_command_flag) { + /* flag is set */ + return SET; + } else { + /* flag is reset */ + return RESET; + } +} + +/*! + \brief enable EXMC interrupt + \param[in] exmc_bank: specify the NAND bank,PC card bank or SDRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_BANK1_NAND: the NAND bank1 + \arg EXMC_BANK2_NAND: the NAND bank2 + \arg EXMC_BANK3_PCCARD: the PC card bank + \arg EXMC_SDRAM_DEVICE0: the SDRAM device0 + \arg EXMC_SDRAM_DEVICE1: the SDRAM device1 + \param[in] interrupt: specify EXMC interrupt flag + only one parameter can be selected which is shown as below: + \arg EXMC_NAND_PCCARD_INT_FLAG_RISE: rising edge interrupt and flag + \arg EXMC_NAND_PCCARD_INT_FLAG_LEVEL: high-level interrupt and flag + \arg EXMC_NAND_PCCARD_INT_FLAG_FALL: falling edge interrupt and flag + \arg EXMC_SDRAM_INT_FLAG_REFRESH: refresh error interrupt and flag + \param[out] none + \retval none +*/ +void exmc_interrupt_enable(uint32_t exmc_bank, uint32_t interrupt) +{ + if((EXMC_BANK1_NAND == exmc_bank) || (EXMC_BANK2_NAND == exmc_bank) || (EXMC_BANK3_PCCARD == exmc_bank)) { + /* NAND bank1,bank2 or PC card bank3 */ + EXMC_NPINTEN(exmc_bank) |= interrupt; + } else { + /* SDRAM device0 or device1 */ + EXMC_SDARI |= EXMC_SDARI_REIE; + } +} + +/*! + \brief disable EXMC interrupt + \param[in] exmc_bank: specify the NAND bank , PC card bank or SDRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_BANK1_NAND: the NAND bank1 + \arg EXMC_BANK2_NAND: the NAND bank2 + \arg EXMC_BANK3_PCCARD: the PC card bank + \arg EXMC_SDRAM_DEVICE0: the SDRAM device0 + \arg EXMC_SDRAM_DEVICE1: the SDRAM device1 + \param[in] interrupt: specify EXMC interrupt flag + only one parameter can be selected which is shown as below: + \arg EXMC_NAND_PCCARD_INT_FLAG_RISE: rising edge interrupt and flag + \arg EXMC_NAND_PCCARD_INT_FLAG_LEVEL: high-level interrupt and flag + \arg EXMC_NAND_PCCARD_INT_FLAG_FALL: falling edge interrupt and flag + \arg EXMC_SDRAM_INT_FLAG_REFRESH: refresh error interrupt and flag + \param[out] none + \retval none +*/ +void exmc_interrupt_disable(uint32_t exmc_bank, uint32_t interrupt) +{ + if((EXMC_BANK1_NAND == exmc_bank) || (EXMC_BANK2_NAND == exmc_bank) || (EXMC_BANK3_PCCARD == exmc_bank)) { + /* NAND bank1,bank2 or PC card bank3 */ + EXMC_NPINTEN(exmc_bank) &= ~interrupt; + } else { + /* SDRAM device0 or device1 */ + EXMC_SDARI &= ~EXMC_SDARI_REIE; + } +} + +/*! + \brief get EXMC flag status + \param[in] exmc_bank: specify the NAND bank , PC card bank or SDRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_BANK1_NAND: the NAND bank1 + \arg EXMC_BANK2_NAND: the NAND bank2 + \arg EXMC_BANK3_PCCARD: the PC Card bank + \arg EXMC_SDRAM_DEVICE0: the SDRAM device0 + \arg EXMC_SDRAM_DEVICE1: the SDRAM device1 + \param[in] flag: EXMC status and flag + only one parameter can be selected which is shown as below: + \arg EXMC_NAND_PCCARD_FLAG_RISE: interrupt rising edge status + \arg EXMC_NAND_PCCARD_FLAG_LEVEL: interrupt high-level status + \arg EXMC_NAND_PCCARD_FLAG_FALL: interrupt falling edge status + \arg EXMC_NAND_PCCARD_FLAG_FIFOE: FIFO empty flag + \arg EXMC_SDRAM_FLAG_REFRESH: refresh error interrupt flag + \arg EXMC_SDRAM_FLAG_NREADY: not ready status + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus exmc_flag_get(uint32_t exmc_bank, uint32_t flag) +{ + uint32_t status = 0x00000000U; + + if((EXMC_BANK1_NAND == exmc_bank) || (EXMC_BANK2_NAND == exmc_bank) || (EXMC_BANK3_PCCARD == exmc_bank)) { + /* NAND bank1,bank2 or PC card bank3 */ + status = EXMC_NPINTEN(exmc_bank); + } else { + /* SDRAM device0 or device1 */ + status = EXMC_SDSTAT; + } + + if((status & flag) != (uint32_t)flag) { + /* flag is reset */ + return RESET; + } else { + /* flag is set */ + return SET; + } +} + +/*! + \brief clear EXMC flag status + \param[in] exmc_bank: specify the NAND bank , PCCARD bank or SDRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_BANK1_NAND: the NAND bank1 + \arg EXMC_BANK2_NAND: the NAND bank2 + \arg EXMC_BANK3_PCCARD: the PC card bank + \arg EXMC_SDRAM_DEVICE0: the SDRAM device0 + \arg EXMC_SDRAM_DEVICE1: the SDRAM device1 + \param[in] flag: EXMC status and flag + only one parameter can be selected which is shown as below: + \arg EXMC_NAND_PCCARD_FLAG_RISE: interrupt rising edge status + \arg EXMC_NAND_PCCARD_FLAG_LEVEL: interrupt high-level status + \arg EXMC_NAND_PCCARD_FLAG_FALL: interrupt falling edge status + \arg EXMC_NAND_PCCARD_FLAG_FIFOE: FIFO empty flag + \arg EXMC_SDRAM_FLAG_REFRESH: refresh error interrupt flag + \arg EXMC_SDRAM_FLAG_NREADY: not ready status + \param[out] none + \retval none +*/ +void exmc_flag_clear(uint32_t exmc_bank, uint32_t flag) +{ + if((EXMC_BANK1_NAND == exmc_bank) || (EXMC_BANK2_NAND == exmc_bank) || (EXMC_BANK3_PCCARD == exmc_bank)) { + /* NAND bank1,bank2 or PC card bank3 */ + EXMC_NPINTEN(exmc_bank) &= ~flag; + } else { + /* SDRAM device0 or device1 */ + EXMC_SDSTAT &= ~flag; + } +} + +/*! + \brief get EXMC interrupt flag + \param[in] exmc_bank: specify the NAND bank , PC card bank or SDRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_BANK1_NAND: the NAND bank1 + \arg EXMC_BANK2_NAND: the NAND bank2 + \arg EXMC_BANK3_PCCARD: the PC card bank + \arg EXMC_SDRAM_DEVICE0: the SDRAM device0 + \arg EXMC_SDRAM_DEVICE1: the SDRAM device1 + \param[in] int_flag: EXMC interrupt flag + only one parameter can be selected which is shown as below: + \arg EXMC_NAND_PCCARD_INT_FLAG_RISE: rising edge interrupt and flag + \arg EXMC_NAND_PCCARD_INT_FLAG_LEVEL: high-level interrupt and flag + \arg EXMC_NAND_PCCARD_INT_FLAG_FALL: falling edge interrupt and flag + \arg EXMC_SDRAM_INT_FLAG_REFRESH: refresh error interrupt and flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus exmc_interrupt_flag_get(uint32_t exmc_bank, uint32_t int_flag) +{ + uint32_t status = 0x00000000U, interrupt_enable = 0x00000000U, interrupt_state = 0x00000000U; + + if((EXMC_BANK1_NAND == exmc_bank) || (EXMC_BANK2_NAND == exmc_bank) || (EXMC_BANK3_PCCARD == exmc_bank)) { + /* NAND bank1,bank2 or PC card bank3 */ + status = EXMC_NPINTEN(exmc_bank); + interrupt_state = (status & (int_flag >> INTEN_INTS_OFFSET)); + } else { + /* SDRAM device0 or device1 */ + status = EXMC_SDARI; + interrupt_state = (EXMC_SDSTAT & EXMC_SDSDAT_REIF); + } + + interrupt_enable = (status & int_flag); + + if((interrupt_enable) && (interrupt_state)) { + /* interrupt flag is set */ + return SET; + } else { + /* interrupt flag is reset */ + return RESET; + } +} + +/*! + \brief clear EXMC interrupt flag + \param[in] exmc_bank: specify the NAND bank , PC card bank or SDRAM device + only one parameter can be selected which is shown as below: + \arg EXMC_BANK1_NAND: the NAND bank1 + \arg EXMC_BANK2_NAND: the NAND bank2 + \arg EXMC_BANK3_PCCARD: the PC card bank + \arg EXMC_SDRAM_DEVICE0: the SDRAM device0 + \arg EXMC_SDRAM_DEVICE1: the SDRAM device1 + \param[in] int_flag: EXMC interrupt flag + only one parameter can be selected which is shown as below: + \arg EXMC_NAND_PCCARD_INT_FLAG_RISE: rising edge interrupt and flag + \arg EXMC_NAND_PCCARD_INT_FLAG_LEVEL: high-level interrupt and flag + \arg EXMC_NAND_PCCARD_INT_FLAG_FALL: falling edge interrupt and flag + \arg EXMC_SDRAM_INT_FLAG_REFRESH: refresh error interrupt and flag + \param[out] none + \retval none +*/ +void exmc_interrupt_flag_clear(uint32_t exmc_bank, uint32_t int_flag) +{ + if((EXMC_BANK1_NAND == exmc_bank) || (EXMC_BANK2_NAND == exmc_bank) || (EXMC_BANK3_PCCARD == exmc_bank)) { + /* NAND bank1, bank2 or PC card bank3 */ + EXMC_NPINTEN(exmc_bank) &= ~(int_flag >> INTEN_INTS_OFFSET); + } else { + /* SDRAM device0 or device1 */ + EXMC_SDARI |= EXMC_SDARI_REC; + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_exti.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_exti.c new file mode 100644 index 0000000..f7b8c6c --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_exti.c @@ -0,0 +1,251 @@ +/*! + \file gd32f5xx_exti.c + \brief EXTI driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_exti.h" + +#define EXTI_REG_RESET_VALUE ((uint32_t)0x00000000U) + +/*! + \brief deinitialize the EXTI + \param[in] none + \param[out] none + \retval none +*/ +void exti_deinit(void) +{ + /* reset the value of all the EXTI registers */ + EXTI_INTEN = EXTI_REG_RESET_VALUE; + EXTI_EVEN = EXTI_REG_RESET_VALUE; + EXTI_RTEN = EXTI_REG_RESET_VALUE; + EXTI_FTEN = EXTI_REG_RESET_VALUE; + EXTI_SWIEV = EXTI_REG_RESET_VALUE; +} + +/*! + \brief initialize the EXTI line x + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[in] mode: interrupt or event mode, refer to exti_mode_enum + only one parameter can be selected which is shown as below: + \arg EXTI_INTERRUPT: interrupt mode + \arg EXTI_EVENT: event mode + \param[in] trig_type: interrupt trigger type, refer to exti_trig_type_enum + only one parameter can be selected which is shown as below: + \arg EXTI_TRIG_RISING: rising edge trigger + \arg EXTI_TRIG_FALLING: falling trigger + \arg EXTI_TRIG_BOTH: rising and falling trigger + \arg EXTI_TRIG_NONE: without rising edge or falling edge trigger + \param[out] none + \retval none +*/ +void exti_init(exti_line_enum linex, \ + exti_mode_enum mode, \ + exti_trig_type_enum trig_type) +{ + /* reset the EXTI line x */ + EXTI_INTEN &= ~(uint32_t)linex; + EXTI_EVEN &= ~(uint32_t)linex; + EXTI_RTEN &= ~(uint32_t)linex; + EXTI_FTEN &= ~(uint32_t)linex; + + /* set the EXTI mode and enable the interrupts or events from EXTI line x */ + switch(mode) { + case EXTI_INTERRUPT: + EXTI_INTEN |= (uint32_t)linex; + break; + case EXTI_EVENT: + EXTI_EVEN |= (uint32_t)linex; + break; + default: + break; + } + + /* set the EXTI trigger type */ + switch(trig_type) { + case EXTI_TRIG_RISING: + EXTI_RTEN |= (uint32_t)linex; + EXTI_FTEN &= ~(uint32_t)linex; + break; + case EXTI_TRIG_FALLING: + EXTI_RTEN &= ~(uint32_t)linex; + EXTI_FTEN |= (uint32_t)linex; + break; + case EXTI_TRIG_BOTH: + EXTI_RTEN |= (uint32_t)linex; + EXTI_FTEN |= (uint32_t)linex; + break; + case EXTI_TRIG_NONE: + default: + break; + } +} + +/*! + \brief enable the interrupts from EXTI line x + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval none +*/ +void exti_interrupt_enable(exti_line_enum linex) +{ + EXTI_INTEN |= (uint32_t)linex; +} + +/*! + \brief disable the interrupt from EXTI line x + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval none +*/ +void exti_interrupt_disable(exti_line_enum linex) +{ + EXTI_INTEN &= ~(uint32_t)linex; +} + +/*! + \brief enable the events from EXTI line x + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval none +*/ +void exti_event_enable(exti_line_enum linex) +{ + EXTI_EVEN |= (uint32_t)linex; +} + +/*! + \brief disable the events from EXTI line x + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval none +*/ +void exti_event_disable(exti_line_enum linex) +{ + EXTI_EVEN &= ~(uint32_t)linex; +} + +/*! + \brief enable the software interrupt event from EXTI line x + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval none +*/ +void exti_software_interrupt_enable(exti_line_enum linex) +{ + EXTI_SWIEV |= (uint32_t)linex; +} + +/*! + \brief disable the software interrupt event from EXTI line x + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval none +*/ +void exti_software_interrupt_disable(exti_line_enum linex) +{ + EXTI_SWIEV &= ~(uint32_t)linex; +} + +/*! + \brief get EXTI line x interrupt pending flag + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval FlagStatus: status of flag (RESET or SET) +*/ +FlagStatus exti_flag_get(exti_line_enum linex) +{ + if(RESET != (EXTI_PD & (uint32_t)linex)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear EXTI line x interrupt pending flag + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval none +*/ +void exti_flag_clear(exti_line_enum linex) +{ + EXTI_PD = (uint32_t)linex; +} + +/*! + \brief get EXTI line x interrupt pending flag + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval FlagStatus: status of flag (RESET or SET) +*/ +FlagStatus exti_interrupt_flag_get(exti_line_enum linex) +{ + if(RESET != (EXTI_PD & (uint32_t)linex)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear EXTI line x interrupt pending flag + \param[in] linex: EXTI line number, refer to exti_line_enum + only one parameter can be selected which is shown as below: + \arg EXTI_x (x=0..25): EXTI line x + \param[out] none + \retval none +*/ +void exti_interrupt_flag_clear(exti_line_enum linex) +{ + EXTI_PD = (uint32_t)linex; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_fmc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_fmc.c new file mode 100644 index 0000000..83c0ee0 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_fmc.c @@ -0,0 +1,1592 @@ +/*! + \file gd32f5xx_fmc.c + \brief FMC driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_fmc.h" + +/* write protection/CBUS read protection sector mask */ +#define WP0_DRP_LOW_12BITS_MASK ((uint64_t)0x0000000000000FFFU) +#define WP0_DRP_HIGH_8BITS_MASK ((uint64_t)0x00000000000FF000U) +#define WP1_DRP_LOW_12BITS_MASK ((uint64_t)0x00000000FFF00000U) +#define WP1_DRP_HIGH_8BITS_MASK ((uint64_t)0x000000FF00000000U) + +/* write protection/CBUS read protection sector offset */ +#define WP0_DRP_LOW_12BITS_OFFSET ((uint32_t)0x00000000U) +#define WP0_DRP_HIGH_8BITS_OFFSET ((uint32_t)0x0000000CU) +#define WP1_DRP_LOW_12BITS_OFFSET ((uint32_t)0x00000014U) +#define WP1_DRP_HIGH_8BITS_OFFSET ((uint32_t)0x00000020U) + +/* FMC register bit offset */ +#define OBCTL0_WP0_L_OFFSET ((uint32_t)0x00000010U) /*!< bit offset of WP0[11:0] in OBCTL1 */ +#define OBCTL1_WP0_H_OFFSET ((uint32_t)0x00000000U) /*!< bit offset of WP0[19:12] in OBCTL1 */ +#define OBCTL1_WP1_L_OFFSET ((uint32_t)0x00000010U) /*!< bit offset of WP1[11:0] in OBCTL1 */ +#define OBCTL1_WP1_H_OFFSET ((uint32_t)0x00000008U) /*!< bit offset of WP1[19:12] in OBCTL1 */ + +/* EFUSE register bit offset */ +#define EFUSE_ADDR_EFSIZE_OFFSET ((uint32_t)(0x00000008U)) /*!< EFSIZE OFFSET in register EFUSE_ADDR */ + + +/*! + \brief unlock the main FMC operation + \param[in] none + \param[out] none + \retval none +*/ +void fmc_unlock(void) +{ + if((RESET != (FMC_CTL & FMC_CTL_LK))) { + /* write the FMC key */ + FMC_KEY = UNLOCK_KEY0; + FMC_KEY = UNLOCK_KEY1; + } +} + +/*! + \brief lock the main FMC operation + \param[in] none + \param[out] none + \retval none +*/ +void fmc_lock(void) +{ + /* set the LK bit*/ + FMC_CTL |= FMC_CTL_LK; +} + +/*! + \brief FMC erase page + \param[in] page_addr: the page address to be erased. + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_page_erase(uint32_t page_addr) +{ + fmc_state_enum fmc_state = FMC_READY; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + /* unlock page erase operation */ + FMC_PEKEY = UNLOCK_PE_KEY; + + /* start page erase */ + FMC_PECFG = FMC_PECFG_PE_EN | page_addr; + FMC_CTL |= FMC_CTL_SER; + FMC_CTL |= FMC_CTL_START; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + FMC_PECFG &= ~FMC_PECFG_PE_EN; + FMC_CTL &= ~FMC_CTL_SER; + } + + /* return the FMC state */ + return fmc_state; +} + +/*! + \brief FMC erase sector + \param[in] fmc_sector: select the sector to erase + only one parameter can be selected which is shown as below: + \arg CTL_SECTOR_NUMBER_x: sector x(x = 0,1,2...53) + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_sector_erase(uint32_t fmc_sector) +{ + fmc_state_enum fmc_state = FMC_READY; + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + /* start sector erase */ + FMC_CTL &= ~FMC_CTL_SER; + FMC_CTL &= ~(FMC_CTL_SN | FMC_CTL_SN_5); + FMC_CTL |= FMC_CTL_SER | fmc_sector; + FMC_CTL |= FMC_CTL_START; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + /* reset the SER bit */ + FMC_CTL &= ~FMC_CTL_SER; + FMC_CTL &= ~(FMC_CTL_SN | FMC_CTL_SN_5); + } + + /* return the FMC state */ + return fmc_state; +} + +/*! + \brief FMC erase whole chip + \param[in] none + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_mass_erase(void) +{ + fmc_state_enum fmc_state = FMC_READY; + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + /* start whole chip erase */ + FMC_CTL |= (FMC_CTL_MER0 | FMC_CTL_MER1); + FMC_CTL |= FMC_CTL_START; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + /* reset the MER bits */ + FMC_CTL &= ~(FMC_CTL_MER0 | FMC_CTL_MER1); + } + + /* return the fmc state */ + return fmc_state; +} + +/*! + \brief FMC erase whole bank0 + \param[in] none + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_bank0_erase(void) +{ + fmc_state_enum fmc_state = FMC_READY; + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + /* start FMC bank0 erase */ + FMC_CTL |= FMC_CTL_MER0; + FMC_CTL |= FMC_CTL_START; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + /* reset the MER0 bit */ + FMC_CTL &= (~FMC_CTL_MER0); + } + + /* return the fmc state */ + return fmc_state; +} + +/*! + \brief FMC erase whole bank1(include bank1_ex) + \param[in] none + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_bank1_erase(void) +{ + fmc_state_enum fmc_state = FMC_READY; + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + /* start FMC bank1 erase */ + FMC_CTL |= FMC_CTL_MER1; + FMC_CTL |= FMC_CTL_START; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + /* reset the MER1 bit */ + FMC_CTL &= (~FMC_CTL_MER1); + } + + /* return the fmc state */ + return fmc_state; +} + +/*! + \brief program a doubleword at the corresponding address + \param[in] address: address to program + \param[in] data: doubleword to program(0x0000000000000000 - 0xFFFFFFFFFFFFFFFF) + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_doubleword_program(uint32_t address, uint64_t data) +{ + fmc_state_enum fmc_state = FMC_READY; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + FMC_CTL |= FMC_CTL_DWPGE; + + /* set the PG bit to start program */ + FMC_CTL |= FMC_CTL_PG; + + REG32(address) = (uint32_t)(data & 0xFFFFFFFFU); + REG32(address + 4U) = (uint32_t)((data >> 32U) & 0xFFFFFFFFU); + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + /* reset the PG bit */ + FMC_CTL &= ~FMC_CTL_PG; + /* reset the DWPGE bit */ + FMC_CTL &= ~FMC_CTL_DWPGE; + } + + /* return the FMC state */ + return fmc_state; +} + +/*! + \brief program a word at the corresponding address + \param[in] address: address to program + \param[in] data: word to program(0x00000000 - 0xFFFFFFFF) + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_word_program(uint32_t address, uint32_t data) +{ + fmc_state_enum fmc_state = FMC_READY; + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + FMC_CTL &= ~FMC_CTL_DWPGE; + FMC_CTL &= ~FMC_CTL_PSZ; + FMC_CTL |= CTL_PSZ_WORD; + + /* set the PG bit to start program */ + FMC_CTL |= FMC_CTL_PG; + + REG32(address) = data; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + /* reset the PG bit */ + FMC_CTL &= ~FMC_CTL_PG; + } + + /* return the FMC state */ + return fmc_state; +} + +/*! + \brief program a half word at the corresponding address + \param[in] address: address to program + \param[in] data: halfword to program(0x0000 - 0xFFFF) + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_halfword_program(uint32_t address, uint16_t data) +{ + fmc_state_enum fmc_state = FMC_READY; + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + FMC_CTL &= ~FMC_CTL_DWPGE; + FMC_CTL &= ~FMC_CTL_PSZ; + FMC_CTL |= CTL_PSZ_HALF_WORD; + + /* set the PG bit to start program */ + FMC_CTL |= FMC_CTL_PG; + + REG16(address) = data; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + /* reset the PG bit */ + FMC_CTL &= ~FMC_CTL_PG; + } + + /* return the FMC state */ + return fmc_state; +} + +/*! + \brief program a byte at the corresponding address + \param[in] address: address to program + \param[in] data: byte to program(0x00 - 0xFF) + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_byte_program(uint32_t address, uint8_t data) +{ + fmc_state_enum fmc_state = FMC_READY; + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + FMC_CTL &= ~FMC_CTL_DWPGE; + FMC_CTL &= ~FMC_CTL_PSZ; + FMC_CTL |= CTL_PSZ_BYTE; + + /* set the PG bit to start program */ + FMC_CTL |= FMC_CTL_PG; + + REG8(address) = data; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + /* reset the PG bit */ + FMC_CTL &= ~FMC_CTL_PG; + } + + /* return the FMC state */ + return fmc_state; +} + +/*! + \brief enable no waiting time area load after system reset + \param[in] none + \param[out] none + \retval none +*/ +void fmc_nwa_enable(void) +{ + FMC_CTL |= FMC_CTL_NWLDE; +} + +/*! + \brief disable no waiting time area load after system reset + \param[in] none + \param[out] none + \retval none +*/ +void fmc_nwa_disable(void) +{ + FMC_CTL &= ~FMC_CTL_NWLDE; +} + +/*! + \brief set OTP1 data block not be read + \param[in] block: specify OTP1 data block x not be read + one or more parameters can be selected which are shown as below: + \arg OTP1_DATA_BLOCK_x: data blcok x(x = 0,1,2...15) + \arg OTP1_DATA_BLOCK_ALL: all data blcok + \param[out] none + \retval none +*/ +void otp1_read_disable(uint32_t block) +{ + FMC_OTP1CFG &= ~block; +} + +/*! + \brief enable read lock block protection for OTP2 + \param[in] none + \param[out] none + \retval none +*/ +void otp2_rlock_enable(void) +{ + FMC_CTL |= FMC_CTL_RLBP; +} + +/*! + \brief unlock the option byte operation + \param[in] none + \param[out] none + \retval none +*/ +void ob_unlock(void) +{ + if(RESET != (FMC_OBCTL0 & FMC_OBCTL0_OB_LK)) { + /* write the FMC key */ + FMC_OBKEY = OB_UNLOCK_KEY0; + FMC_OBKEY = OB_UNLOCK_KEY1; + } +} + +/*! + \brief lock the option byte operation + \param[in] none + \param[out] none + \retval none +*/ +void ob_lock(void) +{ + /* reset the OB_LK bit */ + FMC_OBCTL0 |= FMC_OBCTL0_OB_LK; +} + +/*! + \brief send option byte change command + \param[in] none + \param[out] none + \retval none +*/ +void ob_start(void) +{ + /* set the OB_START bit in OBCTL0 register */ + FMC_OBCTL0 |= FMC_OBCTL0_OB_START; +} + +/*! + \brief erase option byte + \param[in] none + \param[out] none + \retval none +*/ +void ob_erase(void) +{ + uint32_t reg, reg1; + fmc_state_enum fmc_state = FMC_READY; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + reg = FMC_OBCTL0; + reg1 = FMC_OBCTL1; + + if(FMC_READY == fmc_state) { + /* reset the OB_FWDGT, OB_DEEPSLEEP and OB_STDBY, set according to ob_fwdgt, ob_deepsleep and ob_stdby */ + reg |= (FMC_OBCTL0_NWDG_HW | FMC_OBCTL0_NRST_DPSLP | FMC_OBCTL0_NRST_STDBY); + /* reset the BOR level */ + reg |= FMC_OBCTL0_BOR_TH; + /* reset option byte boot bank value */ + reg &= ~FMC_OBCTL0_BB; + /* set option byte eccen value */ + reg |= FMC_OBCTL0_ECCEN; + /* reset drp and wp value */ + reg |= FMC_OBCTL0_WP0; + reg &= (~FMC_OBCTL0_DRP); + /* set option byte nwa value */ + reg |= FMC_OBCTL0_NWA; + FMC_OBCTL0 = reg; + + reg1 |= FMC_OBCTL1_WP0_H | FMC_OBCTL1_WP1_L | FMC_OBCTL1_WP1_H; + FMC_OBCTL1 = reg1; + } +} + +/*! + \brief enable write protection + \param[in] ob_wp: specify sector to be write protected + one or more parameters can be selected which are shown as below: + \arg OB_WP_x(x=0..38):sector x(x = 0,1,2...38) + \arg OB_WP_39_53: sector39~53 + \arg OB_WP_ALL: all sector + \param[out] none + \retval SUCCESS or ERROR +*/ +ErrStatus ob_write_protection_enable(uint64_t ob_wp) +{ + uint32_t reg0 = FMC_OBCTL0; + uint32_t reg1 = FMC_OBCTL1; + uint32_t wp0_low; + uint32_t wp0_high; + uint32_t wp1_low; + uint32_t wp1_high; + fmc_state_enum fmc_state = FMC_READY; + + if(RESET != (FMC_OBCTL0 & FMC_OBCTL0_DRP)) { + return ERROR; + } + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + wp0_low = (uint32_t)(((ob_wp & WP0_DRP_LOW_12BITS_MASK) >> WP0_DRP_LOW_12BITS_OFFSET) << OBCTL0_WP0_L_OFFSET); + wp0_high = (uint32_t)(((ob_wp & WP0_DRP_HIGH_8BITS_MASK) >> WP0_DRP_HIGH_8BITS_OFFSET) << OBCTL1_WP0_H_OFFSET); + wp1_low = (uint32_t)(((ob_wp & WP1_DRP_LOW_12BITS_MASK) >> WP1_DRP_LOW_12BITS_OFFSET) << OBCTL1_WP1_L_OFFSET); + wp1_high = (uint32_t)(((ob_wp & WP1_DRP_HIGH_8BITS_MASK) >> WP1_DRP_HIGH_8BITS_OFFSET) << OBCTL1_WP1_H_OFFSET); + + reg0 &= ~wp0_low; + reg1 &= ~(wp0_high | wp1_low | wp1_high); + FMC_OBCTL0 = reg0; + FMC_OBCTL1 = reg1; + + return SUCCESS; + } else { + return ERROR; + } +} + +/*! + \brief disable write protection + \param[in] ob_wp: specify sector to be write protected + one or more parameters can be selected which are shown as below: + \arg OB_WP_x(x=0..38): sector x(x = 0,1,2...38) + \arg OB_WP_39_53: sector39~53 + \arg OB_WP_ALL: all sector + \param[out] none + \retval SUCCESS or ERROR +*/ +ErrStatus ob_write_protection_disable(uint64_t ob_wp) +{ + uint32_t reg0 = FMC_OBCTL0; + uint32_t reg1 = FMC_OBCTL1; + uint32_t wp0_low; + uint32_t wp0_high; + uint32_t wp1_low; + uint32_t wp1_high; + fmc_state_enum fmc_state = FMC_READY; + + if(RESET != (FMC_OBCTL0 & FMC_OBCTL0_DRP)) { + return ERROR; + } + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + wp0_low = (uint32_t)(((ob_wp & WP0_DRP_LOW_12BITS_MASK) >> WP0_DRP_LOW_12BITS_OFFSET) << OBCTL0_WP0_L_OFFSET); + wp0_high = (uint32_t)(((ob_wp & WP0_DRP_HIGH_8BITS_MASK) >> WP0_DRP_HIGH_8BITS_OFFSET) << OBCTL1_WP0_H_OFFSET); + wp1_low = (uint32_t)(((ob_wp & WP1_DRP_LOW_12BITS_MASK) >> WP1_DRP_LOW_12BITS_OFFSET) << OBCTL1_WP1_L_OFFSET); + wp1_high = (uint32_t)(((ob_wp & WP1_DRP_HIGH_8BITS_MASK) >> WP1_DRP_HIGH_8BITS_OFFSET) << OBCTL1_WP1_H_OFFSET); + + reg0 |= wp0_low; + reg1 |= wp0_high | wp1_low | wp1_high; + + FMC_OBCTL0 = reg0; + FMC_OBCTL1 = reg1; + + return SUCCESS; + } else { + return ERROR; + } +} + +/*! + \brief enable erase/program protection and CBUS read protection + \param[in] ob_drp: enable the WPx bits used as erase/program protection and CBUS read protection of each sector + one or more parameters can be selected which are shown as below: + \arg OB_DRP_x(x=0..38): sector x(x = 0,1,2...38) + \arg OB_DRP_39_53: sector39~53 + \arg OB_DRP_ALL: all sector + \param[out] none + \retval none +*/ +void ob_drp_enable(uint64_t ob_drp) +{ + uint32_t reg0 = FMC_OBCTL0; + uint32_t reg1 = FMC_OBCTL1; + fmc_state_enum fmc_state = FMC_READY; + uint32_t drp_state = FMC_OBCTL0 & FMC_OBCTL0_DRP; + uint32_t drp0_low; + uint32_t drp0_high; + uint32_t drp1_low; + uint32_t drp1_high; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + if(RESET == drp_state) { + reg0 &= ~FMC_OBCTL0_WP0; + reg1 &= ~(FMC_OBCTL1_WP1_L | FMC_OBCTL1_WP1_H | FMC_OBCTL1_WP0_H); + } + + drp0_low = (uint32_t)(((ob_drp & WP0_DRP_LOW_12BITS_MASK) >> WP0_DRP_LOW_12BITS_OFFSET) << OBCTL0_WP0_L_OFFSET); + drp0_high = (uint32_t)(((ob_drp & WP0_DRP_HIGH_8BITS_MASK) >> WP0_DRP_HIGH_8BITS_OFFSET) << OBCTL1_WP0_H_OFFSET); + drp1_low = (uint32_t)(((ob_drp & WP1_DRP_LOW_12BITS_MASK) >> WP1_DRP_LOW_12BITS_OFFSET) << OBCTL1_WP1_L_OFFSET); + drp1_high = (uint32_t)(((ob_drp & WP1_DRP_HIGH_8BITS_MASK) >> WP1_DRP_HIGH_8BITS_OFFSET) << OBCTL1_WP1_H_OFFSET); + + reg0 |= drp0_low; + reg0 |= FMC_OBCTL0_DRP; + reg1 |= drp0_high | drp1_low | drp1_high; + + FMC_OBCTL0 = reg0; + FMC_OBCTL1 = reg1; + } +} + +/*! + \brief disable all erase/program protection and CBUS read protection + \param[in] none + \param[out] none + \retval none +*/ +void ob_drp_disable(void) +{ + uint32_t reg0 = FMC_OBCTL0; + uint32_t reg1 = FMC_OBCTL1; + fmc_state_enum fmc_state = FMC_READY; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + if(((uint8_t)(reg0 >> 8U)) == (uint8_t)FMC_NSPC) { + /* security protection should be set as low level protection before disable CBUS read protection */ + reg0 &= ~FMC_OBCTL0_SPC; + reg0 |= ((uint32_t)FMC_LSPC << 8U); + FMC_OBCTL0 = reg0; + + /* set the OB_START bit in OBCTL0 register */ + FMC_OBCTL0 |= FMC_OBCTL0_OB_START; + } + + /* it is necessary to disable the security protection at the same time when CBUS read protection is disabled */ + reg0 &= ~FMC_OBCTL0_SPC; + reg0 |= ((uint32_t)FMC_NSPC << 8U); + reg0 |= FMC_OBCTL0_WP0; + reg0 &= (~FMC_OBCTL0_DRP); + FMC_OBCTL0 = reg0; + + reg1 |= FMC_OBCTL1_WP0_H | FMC_OBCTL1_WP1_L | FMC_OBCTL1_WP1_H; + FMC_OBCTL1 = reg1; + } +} + +/*! + \brief configure security protection level + \param[in] ob_spc: specify security protection level + only one parameter can be selected which is shown as below: + \arg FMC_NSPC: no security protection + \arg FMC_LSPC: low security protection + \arg FMC_HSPC: high security protection + \param[out] none + \retval none +*/ +void ob_security_protection_config(uint8_t ob_spc) +{ + fmc_state_enum fmc_state = FMC_READY; + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + uint32_t reg; + + reg = FMC_OBCTL0; + /* reset the OBCTL0_SPC, set according to ob_spc */ + reg &= ~FMC_OBCTL0_SPC; + reg |= ((uint32_t)ob_spc << 8U); + FMC_OBCTL0 = reg; + } +} + +/*! + \brief program the FMC user option byte + \param[in] ob_fwdgt: option byte watchdog value + only one parameter can be selected which is shown as below: + \arg OB_FWDGT_SW: software free watchdog + \arg OB_FWDGT_HW: hardware free watchdog + \param[in] ob_deepsleep: option byte deepsleep reset value + only one parameter can be selected which is shown as below: + \arg OB_DEEPSLEEP_NRST: no reset when entering deepsleep mode + \arg OB_DEEPSLEEP_RST: generate a reset instead of entering deepsleep mode + \param[in] ob_stdby:option byte standby reset value + only one parameter can be selected which is shown as below: + \arg OB_STDBY_NRST: no reset when entering standby mode + \arg OB_STDBY_RST: generate a reset instead of entering standby mode + \param[out] none + \retval none +*/ +void ob_user_write(uint32_t ob_fwdgt, uint32_t ob_deepsleep, uint32_t ob_stdby) +{ + fmc_state_enum fmc_state = FMC_READY; + + /* wait for the FMC ready */ + fmc_state = fmc_ready_wait(FMC_TIMEOUT_COUNT); + + if(FMC_READY == fmc_state) { + uint32_t reg; + + reg = FMC_OBCTL0; + /* reset the OB_FWDGT, OB_DEEPSLEEP and OB_STDBY, set according to ob_fwdgt ,ob_deepsleep and ob_stdby */ + reg &= ~(FMC_OBCTL0_NWDG_HW | FMC_OBCTL0_NRST_DPSLP | FMC_OBCTL0_NRST_STDBY); + FMC_OBCTL0 = (reg | ob_fwdgt | ob_deepsleep | ob_stdby); + } +} + +/*! + \brief program the option byte BOR threshold value + \param[in] ob_bor_th: user option byte + only one parameter can be selected which is shown as below: + \arg OB_BOR_TH_VALUE3: BOR threshold value 3 + \arg OB_BOR_TH_VALUE2: BOR threshold value 2 + \arg OB_BOR_TH_VALUE1: BOR threshold value 1 + \arg OB_BOR_TH_OFF: no BOR function + \param[out] none + \retval none +*/ +void ob_user_bor_threshold(uint32_t ob_bor_th) +{ + uint32_t reg; + + reg = FMC_OBCTL0; + /* set the BOR level */ + reg &= ~FMC_OBCTL0_BOR_TH; + FMC_OBCTL0 = (reg | ob_bor_th); +} + +/*! + \brief configure the option byte boot bank value + \param[in] boot_mode: specifies the option byte boot bank value + only one parameter can be selected which is shown as below: + \arg OB_BB_DISABLE: boot from bank0 + \arg OB_BB_ENABLE: boot from bank1 or bank0 if bank1 is void + \param[out] none + \retval none +*/ +void ob_boot_mode_config(uint32_t boot_mode) +{ + uint32_t reg; + + reg = FMC_OBCTL0; + + /* set option byte boot bank value */ + reg &= ~FMC_OBCTL0_BB; + FMC_OBCTL0 = (reg | boot_mode); +} + +/*! + \brief configure FMC/SRAM ECC checking, only valid after power reset. + \param[in] ecc_config: specifies the option byte FMC/SRAM ECC checking + only one parameter can be selected which is shown as below: + \arg OB_ECC_DISABLE: disable FMC/SRAM ECC checking + \arg OB_ECC_ENABLE: enable FMC/SRAM ECC checking + \param[out] none + \retval none +*/ +void ob_ecc_config(uint32_t ecc_config) +{ + uint32_t reg; + + reg = FMC_OBCTL0; + + /* set option byte boot bank value */ + reg &= ~FMC_OBCTL0_ECCEN; + FMC_OBCTL0 = (reg | ecc_config); +} + +/*! + \brief select no waiting time area, only valid after power reset, only for 4MB dual bank series. + \param[in] nwa_select: specifies the option byte no waiting time area + only one parameter can be selected which is shown as below: + \arg OB_NWA_BANK1: bank1 is no waiting time area + \arg OB_NWA_BANK0: bank0 is no waiting time area + \param[out] none + \retval none +*/ +void ob_nwa_select(uint32_t nwa_select) +{ + uint32_t reg; + + reg = FMC_OBCTL0; + + /* set option byte boot bank value */ + reg &= ~FMC_OBCTL0_NWA; + FMC_OBCTL0 = (reg | nwa_select); +} + +/*! + \brief get the FMC user option byte + \param[in] none + \param[out] none + \retval the FMC user option byte values: ob_fwdgt(Bit0), ob_deepsleep(Bit1), ob_stdby(Bit2) +*/ +uint8_t ob_user_get(void) +{ + return (uint8_t)((uint8_t)(FMC_OBCTL0 >> 5U) & 0x07U); +} + +/*! + \brief get the FMC option byte write protection of bank0 + \param[in] none + \param[out] none + \retval the FMC write protection option byte value +*/ +uint32_t ob_write_protection0_get(void) +{ + uint32_t wp0_value; + + wp0_value = (uint32_t)(((uint32_t)(FMC_OBCTL0 & FMC_OBCTL0_WP0)) >> OBCTL0_WP0_L_OFFSET); + wp0_value |= (uint32_t)((((uint32_t)(FMC_OBCTL1 & FMC_OBCTL1_WP0_H)) >> OBCTL1_WP0_H_OFFSET) << 12U); + + return wp0_value; +} + +/*! + \brief get the FMC option byte write protection of bank1 + \param[in] none + \param[out] none + \retval the FMC write protection option byte value +*/ +uint32_t ob_write_protection1_get(void) +{ + uint32_t wp1_value; + + wp1_value = (uint32_t)(((uint32_t)(FMC_OBCTL1 & FMC_OBCTL1_WP1_L)) >> OBCTL1_WP1_L_OFFSET); + wp1_value |= (uint32_t)((((uint32_t)(FMC_OBCTL1 & FMC_OBCTL1_WP1_H)) >> OBCTL1_WP1_H_OFFSET) << 12U); + + return wp1_value; +} + +/*! + \brief get the FMC erase/program protection and CBUS read protection option bytes value of bank0 + \param[in] none + \param[out] none + \retval the FMC erase/program protection and CBUS read protection option bytes value +*/ +uint32_t ob_drp0_get(void) +{ + uint32_t drp0_value; + + /* return the FMC erase/program protection and CBUS read protection option bytes value */ + if(FMC_OBCTL0 & FMC_OBCTL0_DRP) { + drp0_value = (uint32_t)(((uint32_t)(FMC_OBCTL0 & FMC_OBCTL0_WP0)) >> OBCTL0_WP0_L_OFFSET); + drp0_value |= (uint32_t)((((uint32_t)(FMC_OBCTL1 & FMC_OBCTL1_WP0_H)) >> OBCTL1_WP0_H_OFFSET) << 12U); + } else { + drp0_value = 0U; + } + return drp0_value; +} + +/*! + \brief get the FMC erase/program protection and CBUS read protection option bytes value of bank1 + \param[in] none + \param[out] none + \retval the FMC erase/program protection and CBUS read protection option bytes value +*/ +uint32_t ob_drp1_get(void) +{ + uint32_t drp1_value; + + /* return the FMC erase/program protection and CBUS read protection option bytes value */ + if(FMC_OBCTL0 & FMC_OBCTL0_DRP) { + drp1_value = (uint32_t)(((uint32_t)(FMC_OBCTL1 & FMC_OBCTL1_WP1_L)) >> OBCTL1_WP1_L_OFFSET); + drp1_value |= (uint32_t)((((uint32_t)(FMC_OBCTL1 & FMC_OBCTL1_WP1_H)) >> OBCTL1_WP1_H_OFFSET) << 12U); + } else { + drp1_value = 0U; + } + return drp1_value; +} + +/*! + \brief get option byte security protection code value + \param[in] none + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus ob_spc_get(void) +{ + FlagStatus spc_state = RESET; + + if(((uint8_t)(FMC_OBCTL0 >> 8U)) != FMC_NSPC) { + spc_state = SET; + } else { + spc_state = RESET; + } + return spc_state; +} + +/*! + \brief get the FMC option byte BOR threshold value + \param[in] none + \param[out] none + \retval the FMC BOR threshold value:OB_BOR_TH_OFF,OB_BOR_TH_VALUE1,OB_BOR_TH_VALUE2,OB_BOR_TH_VALUE3 +*/ +uint32_t ob_user_bor_threshold_get(void) +{ + /* return the FMC BOR threshold value */ + return (FMC_OBCTL0 & FMC_OBCTL0_BOR_TH); +} + +/*! + \brief get the boot mode + \param[in] none + \param[out] none + \retval the FMC boot bank value:OB_BB_DISABLE,OB_BB_ENABLE +*/ +uint32_t ob_boot_mode_get(void) +{ + /* return the boot mode */ + return (FMC_OBCTL0 & FMC_OBCTL0_BB); +} + +/*! + \brief get FMC/SRAM ECC checking + \param[in] none + \param[out] none + \retval the FMC BOR threshold value:OB_ECC_DISABLE,OB_ECC_ENABLE +*/ +uint32_t ob_ecc_get(void) +{ + /* return the FMC/SRAM ECC checking */ + return (FMC_OBCTL0 & FMC_OBCTL0_ECCEN); +} + +/*! + \brief get no waiting time area + \param[in] none + \param[out] none + \retval the no waiting time area:OB_NWA_BANK1,OB_NWA_BANK0 +*/ +uint32_t ob_nwa_get(void) +{ + /* return the FMC/SRAM ECC checking */ + return (FMC_OBCTL0 & FMC_OBCTL0_ECCEN); +} + +/*! + \brief get flag set or reset + \param[in] fmc_flag: check FMC flag + only one parameter can be selected which is shown as below: + \arg FMC_FLAG_END: FMC end of operation flag bit + \arg FMC_FLAG_OPERR: FMC operation error flag bit + \arg FMC_FLAG_LDECCDET: FMC multi bit ECC error when load code from flash flag bit + \arg FMC_FLAG_WPERR: FMC Erase/Program protection error flag bit + \arg FMC_FLAG_PGAERR: FMC program alignment error flag bit + \arg FMC_FLAG_PGMERR: FMC program size not match error flag bit + \arg FMC_FLAG_PGSERR: FMC program sequence error flag bit + \arg FMC_FLAG_RDCERR: FMC CBUS data read protection error flag bit + \arg FMC_FLAG_BUSY: FMC busy flag bit + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus fmc_flag_get(uint32_t fmc_flag) +{ + if(FMC_STAT & fmc_flag) { + return SET; + } + /* return the state of corresponding FMC flag */ + return RESET; +} + +/*! + \brief clear the FMC pending flag + \param[in] FMC_flag: clear FMC flag + only one parameter can be selected which is shown as below: + \arg FMC_FLAG_END: FMC end of operation flag bit + \arg FMC_FLAG_OPERR: FMC operation error flag bit + \arg FMC_FLAG_LDECCDET: FMC multi bit ECC error when load code from flash flag bit + \arg FMC_FLAG_WPERR: FMC Erase/Program protection error flag bit + \arg FMC_FLAG_PGAERR: FMC program alignment error flag bit + \arg FMC_FLAG_PGMERR: FMC program size not match error flag bit + \arg FMC_FLAG_PGSERR: FMC program sequence error flag bit + \arg FMC_FLAG_RDCERR: FMC CBUS data read protection error flag bit + \arg FMC_FLAG_BUSY: FMC busy flag bit + \param[out] none + \retval none +*/ +void fmc_flag_clear(uint32_t fmc_flag) +{ + /* clear the flags */ + FMC_STAT = fmc_flag; +} + +/*! + \brief enable FMC interrupt + \param[in] fmc_int: the FMC interrupt source + only one parameter can be selected which is shown as below: + \arg FMC_INT_END: enable FMC end of program interrupt + \arg FMC_INT_ERR: enable FMC error interrupt + \arg FMC_INT_LDECC: enable FMC load code ECC error interrupt + \param[out] none + \retval none +*/ +void fmc_interrupt_enable(uint32_t fmc_int) +{ + FMC_CTL |= fmc_int; +} + +/*! + \brief disable FMC interrupt + \param[in] fmc_int: the FMC interrupt source + only one parameter can be selected which is shown as below: + \arg FMC_INT_END: disable FMC end of program interrupt + \arg FMC_INT_ERR: disable FMC error interrupt + \arg FMC_INT_LDECC: enable FMC load code ECC error interrupt + \param[out] none + \retval none +*/ +void fmc_interrupt_disable(uint32_t fmc_int) +{ + FMC_CTL &= ~fmc_int; +} + +/*! + \brief get FMC interrupt flag set or reset + \param[in] fmc_int_flag: FMC interrupt flag + only one parameter can be selected which is shown as below: + \arg FMC_INT_FLAG_END: FMC end of operation interrupt flag + \arg FMC_INT_FLAG_OPERR: FMC operation error interrupt flag + \arg FMC_INT_FLAG_LDECCDET: FMC two bits ECC error when load code from flash/OTP1/bootloader interrupt flag + \arg FMC_INT_FLAG_WPERR: FMC Erase/Program protection error interrupt flag + \arg FMC_INT_FLAG_PGAERR: FMC program alignment error interrupt flag + \arg FMC_INT_FLAG_PGMERR: FMC program size not match error interrupt flag + \arg FMC_INT_FLAG_PGSERR: FMC program sequence error interrupt flag + \arg FMC_INT_FLAG_RDCERR: FMC CBUS data read protection error interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus fmc_interrupt_flag_get(uint32_t fmc_int_flag) +{ + if(FMC_FLAG_END == fmc_int_flag) { + /* end of operation interrupt flag */ + if(FMC_CTL & FMC_CTL_ENDIE) { + if(FMC_STAT & fmc_int_flag) { + return SET; + } + } + } else { + /* error interrupt flags */ + if(FMC_CTL & FMC_CTL_ERRIE) { + if(FMC_STAT & fmc_int_flag) { + return SET; + } + } + } + return RESET; +} + +/*! + \brief clear the FMC interrupt flag + \param[in] fmc_int_flag: FMC interrupt flag + only one parameter can be selected which is shown as below: + \arg FMC_INT_FLAG_END: FMC end of operation interrupt flag + \arg FMC_INT_FLAG_OPERR: FMC operation error interrupt flag + \arg FMC_INT_FLAG_LDECCDET: FMC two bits ECC error when load code from flash/OTP1/bootloader interrupt flag + \arg FMC_INT_FLAG_WPERR: FMC Erase/Program protection error interrupt flag + \arg FMC_INT_FLAG_PGAERR: FMC program alignment error interrupt flag + \arg FMC_INT_FLAG_PGMERR: FMC program size not match error interrupt flag + \arg FMC_INT_FLAG_PGSERR: FMC program sequence error interrupt flag + \arg FMC_INT_FLAG_RDCERR: FMC CBUS data read protection error interrupt flag + \param[out] none + \retval none +*/ +void fmc_interrupt_flag_clear(uint32_t fmc_int_flag) +{ + /* clear the interrupt flag */ + FMC_STAT = fmc_int_flag; +} + +/*! + \brief get the FMC state + \param[in] none + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader +*/ +fmc_state_enum fmc_state_get(void) +{ + fmc_state_enum fmc_state = FMC_READY; + uint32_t temp_val = FMC_STAT; + + if(RESET != (temp_val & FMC_FLAG_BUSY)) { + fmc_state = FMC_BUSY; + } else if(RESET != (temp_val & FMC_FLAG_RDCERR)) { + fmc_state = FMC_RDCERR; + } else if(RESET != (temp_val & FMC_FLAG_PGSERR)) { + fmc_state = FMC_PGSERR; + } else if(RESET != (temp_val & FMC_FLAG_PGMERR)) { + fmc_state = FMC_PGMERR; + } else if(RESET != (temp_val & FMC_FLAG_PGAERR)) { + fmc_state = FMC_PGAERR; + } else if(RESET != (temp_val & FMC_FLAG_WPERR)) { + fmc_state = FMC_WPERR; + } else if(RESET != (temp_val & FMC_FLAG_OPERR)) { + fmc_state = FMC_OPERR; + } else if(RESET != (temp_val & FMC_FLAG_LDECCDET)) { + fmc_state = FMC_LDECCDET; + } else { + fmc_state = FMC_READY; + } + + /* return the FMC state */ + return fmc_state; +} + +/*! + \brief check whether FMC is ready or not + \param[in] timeout: timeout value + \param[out] none + \retval state of FMC + \arg FMC_READY: the operation has been completed + \arg FMC_BUSY: the operation is in progress + \arg FMC_RDCERR: CBUS data read protection error + \arg FMC_PGSERR: program sequence error + \arg FMC_PGMERR: program size not match error + \arg FMC_PGAERR: program alignment error + \arg FMC_WPERR: erase/program protection error + \arg FMC_OPERR: operation error + \arg FMC_LDECCDET: two bits ECC error when load code from flash/OTP1/bootloader + \arg FMC_TOERR: timeout error +*/ +fmc_state_enum fmc_ready_wait(uint32_t timeout) +{ + fmc_state_enum fmc_state = FMC_BUSY; + + /* wait for FMC ready */ + do { + /* get FMC state */ + fmc_state = fmc_state_get(); + timeout--; + } while((FMC_BUSY == fmc_state) && (0U != timeout)); + + if(0U == timeout) { + fmc_state = FMC_TOERR; + } + + /* return the FMC state */ + return fmc_state; +} + +/*! + \brief unlock the EFUSE_CTL register + \param[in] none + \param[out] none + \retval none +*/ +void efuse_ctrl_unlock(void) +{ + /* clear the LK bit */ + EFUSE_CTL &= ~EFUSE_CTL_LK; +} + +/*! + \brief lock the EFUSE_CTL register + \param[in] none + \param[out] none + \retval none +*/ +void efuse_ctrl_lock(void) +{ + /* set the LK bit */ + EFUSE_CTL |= EFUSE_CTL_LK; +} + +/*! + \brief unlock the EFUSE_USER_DATA register + \param[in] none + \param[out] none + \retval none +*/ +void efuse_user_data_unlock(void) +{ + /* clear the UDLK bit */ + EFUSE_CTL &= ~EFUSE_CTL_UDLK; +} + +/*! + \brief lock the EFUSE_USER_DATA register + \param[in] none + \param[out] none + \retval none +*/ +void efuse_user_data_lock(void) +{ + /* set the UDLK bit */ + EFUSE_CTL |= EFUSE_CTL_UDLK; +} + +/*! + \brief read EFUSE value + \param[in] ef_addr: EFUSE address + \arg EFUSE_CTL_EFADDR: efuse controladdress + \arg USER_DATA_EFADDR: user data address + \param[in] size: byte count to read + \param[out] buf: the buffer for storing read-out EFUSE data + \retval state of EFUSE: + \arg EFUSE_READY: EFUSE operation has been completed + \arg EFUSE_BUSY: EFUSE operation is in progress + \arg EFUSE_OBER: overstep boundary error + \arg EFUSE_TOERR: EFUSE timeout error +*/ +efuse_state_enum efuse_read(uint32_t ef_addr, uint32_t size, uint32_t buf[]) +{ + uint32_t reg_addr = 0U; + efuse_state_enum efuse_state = EFUSE_READY; + + if(1U != size) { + return EFUSE_OBER; + } + + if(EFUSE_CTL_EFADDR == ef_addr) { + /* read efuse control*/ + reg_addr = (uint32_t)(FMC + EFUSE_CTL_OFFSET); + } else if(USER_DATA_EFADDR == ef_addr) { + /* read user data */ + reg_addr = (uint32_t)(FMC + EFUSE_USER_DATA_OFFSET); + } else { + return EFUSE_OBER; + } + + /* clear the RDIF bit if it is SET */ + efuse_flag_clear(EFUSE_RDIC); + + /* make sure no overstep boundary errors */ + if(RESET != efuse_flag_get(EFUSE_OBERIF)) { + return EFUSE_OBER; + } + + /* EFUSE read operation */ + EFUSE_CS &= (~EFUSE_CS_EFRW); + + /* write the desired efuse address and size to the EFUSE_ADDR register */ + EFUSE_ADDR = (uint32_t)((1U << EFUSE_ADDR_EFSIZE_OFFSET) | ef_addr); + + /* start read EFUSE operation */ + EFUSE_CS |= EFUSE_CS_EFSTR; + + /* wait for the operation to complete */ + efuse_state = efuse_ready_wait(EFUSE_RDIF, EFUSE_TIMEOUT_COUNT); + if(EFUSE_READY == efuse_state) { + /* read EFUSE data to buffer */ + buf[0] = REG32(reg_addr); + } + + return efuse_state; +} + +/*! + \brief write EFUSE + \param[in] ef_addr: EFUSE address + \arg EFUSE_CTL_EFADDR: efuse controladdress + \arg USER_DATA_EFADDR: user data address + \param[in] size: byte count to write, (1~1) + \param[in] ef_data: data to write EFUSE + \param[out] none + \retval state of EFUSE: + \arg EFUSE_READY: EFUSE operation has been completed + \arg EFUSE_BUSY: EFUSE operation is in progress + \arg EFUSE_OBER: overstep boundary error + \arg EFUSE_TOERR: EFUSE timeout error +*/ +efuse_state_enum efuse_write(uint32_t ef_addr, uint32_t size, uint8_t ef_data) +{ + uint32_t reg_addr = 0U; + efuse_state_enum efuse_state; + + if(1U != size) { + return EFUSE_OBER; + } + + if(EFUSE_CTL_EFADDR == ef_addr) { + /* program efuse control*/ + reg_addr = (uint32_t)(FMC + EFUSE_CTL_OFFSET); + } else if(USER_DATA_EFADDR == ef_addr) { + /* program user data */ + reg_addr = (uint32_t)(FMC + EFUSE_USER_DATA_OFFSET); + } else { + return EFUSE_OBER; + } + + /* clear the PGIF bit if it is SET */ + efuse_flag_clear(EFUSE_PGIC); + + /* make sure no overstep boundary errors */ + if(RESET != efuse_flag_get(EFUSE_OBERIF)) { + return EFUSE_OBER; + } + + /* EFUSE write operation */ + EFUSE_CS |= EFUSE_CS_EFRW; + + /* write the desired efuse address and size to the EFUSE_ADDR register */ + EFUSE_ADDR = (uint32_t)((size << EFUSE_ADDR_EFSIZE_OFFSET) | ef_addr); + + REG32(reg_addr) = (uint32_t)ef_data; + + /* start array write EFUSE operation */ + EFUSE_CS |= EFUSE_CS_EFSTR; + + /* wait for the operation to complete */ + efuse_state = efuse_ready_wait(EFUSE_PGIF, EFUSE_TIMEOUT_COUNT); + + return efuse_state; +} + +/*! + \brief write control data parameter + \param[in] ef_data: EFUSE data to write + \param[out] none + \retval state of EFUSE: + \arg EFUSE_READY: EFUSE operation has been completed + \arg EFUSE_BUSY: EFUSE operation is in progress + \arg EFUSE_OBER: overstep boundary error + \arg EFUSE_TOERR: EFUSE timeout error +*/ +efuse_state_enum efuse_control_write(uint8_t ef_data) +{ + return efuse_write(EFUSE_CTL_EFADDR, 1UL, ef_data); +} + +/*! + \brief write user data parameter + \param[in] ef_data: EFUSE data to write + \param[out] none + \retval state of EFUSE: + \arg EFUSE_READY: EFUSE operation has been completed + \arg EFUSE_BUSY: EFUSE operation is in progress + \arg EFUSE_OBER: overstep boundary error + \arg EFUSE_TOERR: EFUSE timeout error +*/ +efuse_state_enum efuse_user_data_write(uint8_t ef_data) +{ + return efuse_write(USER_DATA_EFADDR, 1UL, ef_data); +} + +/*! + \brief get EFUSE flag is set or not + \param[in] efuse_flag: specifies to get a flag + only one parameter can be selected which is shown as below: + \arg EFUSE_PGIF: programming operation completion flag + \arg EFUSE_RDIF: read operation completion flag + \arg EFUSE_OBERIF: overstep boundary error flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus efuse_flag_get(uint32_t efuse_flag) +{ + if(EFUSE_CS & efuse_flag) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear EFUSE pending flag + \param[in] flag: specifies to clear a flag + only one parameter can be selected which is shown as below: + \arg EFUSE_PGIC: clear programming operation completion flag + \arg EFUSE_RDIC: clear read operation completion flag + \arg EFUSE_OBERIC: clear overstep boundary error flag + \param[out] none + \retval none +*/ +void efuse_flag_clear(uint32_t efuse_cflag) +{ + EFUSE_CS |= efuse_cflag; +} + +/*! + \brief enable EFUSE interrupt + \param[in] source: specifies an interrupt to enable + one or more parameters can be selected which are shown as below: + \arg EFUSE_INT_PG: programming operation completion interrupt + \arg EFUSE_INT_RD: read operation completion interrupt + \arg EFUSE_INT_OBER: overstep boundary error interrupt + \param[out] none + \retval none +*/ +void efuse_interrupt_enable(uint32_t source) +{ + EFUSE_CS = source; +} + +/*! + \brief disable EFUSE interrupt + \param[in] source: specifies an interrupt to disable + one or more parameters can be selected which are shown as below: + \arg EFUSE_INT_PG: programming operation completion interrupt + \arg EFUSE_INT_RD: read operation completion interrupt + \arg EFUSE_INT_OBER: overstep boundary error interrupt + \param[out] none + \retval none +*/ +void efuse_interrupt_disable(uint32_t source) +{ + EFUSE_CS &= ~source; +} + +/*! + \brief get EFUSE interrupt flag is set or not + \param[in] efuse_flag: specifies to get a flag + only one parameter can be selected which is shown as below: + \arg EFUSE_INT_PGIF: programming operation completion interrupt flag + \arg EFUSE_INT_RDIF: read operation completion interrupt flag + \arg EFUSE_INT_OBERIF: overstep boundary error interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus efuse_interrupt_flag_get(uint32_t int_flag) +{ + if(EFUSE_CS & int_flag) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear EFUSE pending interrupt flag + \param[in] efuse_flag: specifies to clear a flag + only one parameter can be selected which is shown as below: + \arg EFUSE_INT_PGIC: clear programming operation completion interrupt flag + \arg EFUSE_INT_RDIC: clear operation completion interrupt flag + \arg EFUSE_INT_OBERIC: clear overstep boundary error interrupt flag + \param[out] none + \retval none +*/ +void efuse_interrupt_flag_clear(uint32_t int_cflag) +{ + EFUSE_CS |= int_cflag; +} + +/*! + \brief check whether EFUSE is ready or not + \param[in] efuse_flag: specifies to get a flag + only one parameter can be selected which is shown as below: + \arg EFUSE_PGIF: programming operation completion flag + \arg EFUSE_RDIF: read operation completion flag + \arg EFUSE_OBERIF: overstep boundary error flag + \param[in] timeout: timeout value + \param[out] none + \retval state of EFUSE + \arg EFUSE_READY: EFUSE operation has been completed + \arg EFUSE_BUSY: EFUSE operation is in progress + \arg EFUSE_OBER: overstep boundary error + \arg EFUSE_TOERR: EFUSE timeout error +*/ +efuse_state_enum efuse_ready_wait(uint32_t efuse_flag, uint32_t timeout) +{ + efuse_state_enum efuse_state = EFUSE_BUSY; + + /* wait for EFUSE ready */ + do { + /* get EFUSE flag set or not */ + if(EFUSE_CS & (uint32_t)efuse_flag) { + efuse_state = EFUSE_READY; + } else if(EFUSE_CS & EFUSE_CS_OVBERIF) { + efuse_state = EFUSE_OBER; + } else { + + } + timeout--; + } while((EFUSE_BUSY == efuse_state) && (0U != timeout)); + + if(EFUSE_BUSY == efuse_state) { + efuse_state = EFUSE_TOERR; + } + + /* return the EFUSE state */ + return efuse_state; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_fwdgt.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_fwdgt.c new file mode 100644 index 0000000..d3902dd --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_fwdgt.c @@ -0,0 +1,229 @@ +/*! + \file gd32f5xx_fwdgt.c + \brief FWDGT driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_fwdgt.h" + +/*! + \brief enable write access to FWDGT_PSC and FWDGT_RLD + \param[in] none + \param[out] none + \retval none +*/ +void fwdgt_write_enable(void) +{ + FWDGT_CTL = FWDGT_WRITEACCESS_ENABLE; +} + +/*! + \brief disable write access to FWDGT_PSC and FWDGT_RLD + \param[in] none + \param[out] none + \retval none +*/ +void fwdgt_write_disable(void) +{ + FWDGT_CTL = FWDGT_WRITEACCESS_DISABLE; +} + +/*! + \brief start the free watchdog timer counter + \param[in] none + \param[out] none + \retval none +*/ +void fwdgt_enable(void) +{ + FWDGT_CTL = FWDGT_KEY_ENABLE; +} + +/*! + \brief configure the free watchdog timer counter prescaler value + \param[in] prescaler_value: specify prescaler value + only one parameter can be selected which is shown as below: + \arg FWDGT_PSC_DIV4: FWDGT prescaler set to 4 + \arg FWDGT_PSC_DIV8: FWDGT prescaler set to 8 + \arg FWDGT_PSC_DIV16: FWDGT prescaler set to 16 + \arg FWDGT_PSC_DIV32: FWDGT prescaler set to 32 + \arg FWDGT_PSC_DIV64: FWDGT prescaler set to 64 + \arg FWDGT_PSC_DIV128: FWDGT prescaler set to 128 + \arg FWDGT_PSC_DIV256: FWDGT prescaler set to 256 + \arg FWDGT_PSC_DIV512: FWDGT prescaler set to 512 + \arg FWDGT_PSC_DIV1024: FWDGT prescaler set to 1024 + \arg FWDGT_PSC_DIV2048: FWDGT prescaler set to 2048 + \arg FWDGT_PSC_DIV4096: FWDGT prescaler set to 4096 + \arg FWDGT_PSC_DIV8192: FWDGT prescaler set to 8192 + \arg FWDGT_PSC_DIV16384: FWDGT prescaler set to 16384 + \arg FWDGT_PSC_DIV32768: FWDGT prescaler set to 32768 + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus fwdgt_prescaler_value_config(uint16_t prescaler_value) +{ + uint32_t timeout = FWDGT_PSC_TIMEOUT; + uint32_t flag_status = RESET; + + /* enable write access to FWDGT_PSC */ + FWDGT_CTL = FWDGT_WRITEACCESS_ENABLE; + + /* wait until the PUD flag to be reset */ + do { + flag_status = FWDGT_STAT & FWDGT_STAT_PUD; + } while((--timeout > 0U) && ((uint32_t)RESET != flag_status)); + + if((uint32_t)RESET != flag_status) { + return ERROR; + } + + /* configure FWDGT */ + FWDGT_PSC = (uint32_t)prescaler_value; + + return SUCCESS; +} + +/*! + \brief configure the free watchdog timer counter reload value + \param[in] reload_value: specify reload value(0x0000 - 0x0FFF) + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus fwdgt_reload_value_config(uint16_t reload_value) +{ + uint32_t timeout = FWDGT_RLD_TIMEOUT; + uint32_t flag_status = RESET; + + /* enable write access to FWDGT_RLD */ + FWDGT_CTL = FWDGT_WRITEACCESS_ENABLE; + + /* wait until the RUD flag to be reset */ + do { + flag_status = FWDGT_STAT & FWDGT_STAT_RUD; + } while((--timeout > 0U) && ((uint32_t)RESET != flag_status)); + + if((uint32_t)RESET != flag_status) { + return ERROR; + } + + FWDGT_RLD = RLD_RLD(reload_value); + + return SUCCESS; +} + +/*! + \brief reload the counter of FWDGT + \param[in] none + \param[out] none + \retval none +*/ +void fwdgt_counter_reload(void) +{ + FWDGT_CTL = FWDGT_KEY_RELOAD; +} + +/*! + \brief configure counter reload value, and prescaler divider value + \param[in] reload_value: specify reload value(0x0000 - 0x0FFF) + \param[in] prescaler_div: FWDGT prescaler value + only one parameter can be selected which is shown as below: + \arg FWDGT_PSC_DIV4: FWDGT prescaler set to 4 + \arg FWDGT_PSC_DIV8: FWDGT prescaler set to 8 + \arg FWDGT_PSC_DIV16: FWDGT prescaler set to 16 + \arg FWDGT_PSC_DIV32: FWDGT prescaler set to 32 + \arg FWDGT_PSC_DIV64: FWDGT prescaler set to 64 + \arg FWDGT_PSC_DIV128: FWDGT prescaler set to 128 + \arg FWDGT_PSC_DIV256: FWDGT prescaler set to 256 + \arg FWDGT_PSC_DIV512 : FWDGT prescaler set to 512 + \arg FWDGT_PSC_DIV1024 : FWDGT prescaler set to 1024 + \arg FWDGT_PSC_DIV2048 : FWDGT prescaler set to 2048 + \arg FWDGT_PSC_DIV4096 : FWDGT prescaler set to 4096 + \arg FWDGT_PSC_DIV8192 : FWDGT prescaler set to 8192 + \arg FWDGT_PSC_DIV16384 : FWDGT prescaler set to 16384 + \arg FWDGT_PSC_DIV32768 : FWDGT prescaler set to 32768 + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus fwdgt_config(uint16_t reload_value, uint8_t prescaler_div) +{ + uint32_t timeout = FWDGT_PSC_TIMEOUT; + uint32_t flag_status = RESET; + + /* enable write access to FWDGT_PSC,and FWDGT_RLD */ + FWDGT_CTL = FWDGT_WRITEACCESS_ENABLE; + + /* wait until the PUD flag to be reset */ + do { + flag_status = FWDGT_STAT & FWDGT_STAT_PUD; + } while((--timeout > 0U) && ((uint32_t)RESET != flag_status)); + + if((uint32_t)RESET != flag_status) { + return ERROR; + } + + /* configure FWDGT */ + FWDGT_PSC = (uint32_t)prescaler_div; + + timeout = FWDGT_RLD_TIMEOUT; + /* wait until the RUD flag to be reset */ + do { + flag_status = FWDGT_STAT & FWDGT_STAT_RUD; + } while((--timeout > 0U) && ((uint32_t)RESET != flag_status)); + + if((uint32_t)RESET != flag_status) { + return ERROR; + } + + FWDGT_RLD = RLD_RLD(reload_value); + + /* reload the counter */ + FWDGT_CTL = FWDGT_KEY_RELOAD; + + return SUCCESS; +} + +/*! + \brief get flag state of FWDGT + \param[in] flag: flag to get + only one parameter can be selected which is shown as below: + \arg FWDGT_STAT_PUD: a write operation to FWDGT_PSC register is on going + \arg FWDGT_STAT_RUD: a write operation to FWDGT_RLD register is on going + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus fwdgt_flag_get(uint16_t flag) +{ + if(RESET != (FWDGT_STAT & flag)) { + return SET; + } + + return RESET; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_gpio.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_gpio.c new file mode 100644 index 0000000..fd8b70d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_gpio.c @@ -0,0 +1,431 @@ +/*! + \file gd32f5xx_gpio.c + \brief GPIO driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_gpio.h" + +/*! + \brief reset GPIO port + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[out] none + \retval none +*/ +void gpio_deinit(uint32_t gpio_periph) +{ + switch(gpio_periph) { + case GPIOA: + /* reset GPIOA */ + rcu_periph_reset_enable(RCU_GPIOARST); + rcu_periph_reset_disable(RCU_GPIOARST); + break; + case GPIOB: + /* reset GPIOB */ + rcu_periph_reset_enable(RCU_GPIOBRST); + rcu_periph_reset_disable(RCU_GPIOBRST); + break; + case GPIOC: + /* reset GPIOC */ + rcu_periph_reset_enable(RCU_GPIOCRST); + rcu_periph_reset_disable(RCU_GPIOCRST); + break; + case GPIOD: + /* reset GPIOD */ + rcu_periph_reset_enable(RCU_GPIODRST); + rcu_periph_reset_disable(RCU_GPIODRST); + break; + case GPIOE: + /* reset GPIOE */ + rcu_periph_reset_enable(RCU_GPIOERST); + rcu_periph_reset_disable(RCU_GPIOERST); + break; + case GPIOF: + /* reset GPIOF */ + rcu_periph_reset_enable(RCU_GPIOFRST); + rcu_periph_reset_disable(RCU_GPIOFRST); + break; + case GPIOG: + /* reset GPIOG */ + rcu_periph_reset_enable(RCU_GPIOGRST); + rcu_periph_reset_disable(RCU_GPIOGRST); + break; + case GPIOH: + /* reset GPIOH */ + rcu_periph_reset_enable(RCU_GPIOHRST); + rcu_periph_reset_disable(RCU_GPIOHRST); + break; + case GPIOI: + /* reset GPIOI */ + rcu_periph_reset_enable(RCU_GPIOIRST); + rcu_periph_reset_disable(RCU_GPIOIRST); + break; + default: + break; + } +} + +/*! + \brief set GPIO mode + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] mode: GPIO pin mode + \arg GPIO_MODE_INPUT: input mode + \arg GPIO_MODE_OUTPUT: output mode + \arg GPIO_MODE_AF: alternate function mode + \arg GPIO_MODE_ANALOG: analog mode + \param[in] pull_up_down: GPIO pin with pull-up or pull-down resistor + \arg GPIO_PUPD_NONE: floating mode, no pull-up and pull-down resistors + \arg GPIO_PUPD_PULLUP: with pull-up resistor + \arg GPIO_PUPD_PULLDOWN:with pull-down resistor + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval none +*/ +void gpio_mode_set(uint32_t gpio_periph, uint32_t mode, uint32_t pull_up_down, uint32_t pin) +{ + uint16_t i; + uint32_t ctl, pupd; + + ctl = GPIO_CTL(gpio_periph); + pupd = GPIO_PUD(gpio_periph); + + for(i = 0U; i < 16U; i++) { + if((1U << i) & pin) { + /* clear the specified pin mode bits */ + ctl &= ~GPIO_MODE_MASK(i); + /* set the specified pin mode bits */ + ctl |= GPIO_MODE_SET(i, mode); + + /* clear the specified pin pupd bits */ + pupd &= ~GPIO_PUPD_MASK(i); + /* set the specified pin pupd bits */ + pupd |= GPIO_PUPD_SET(i, pull_up_down); + } + } + + GPIO_CTL(gpio_periph) = ctl; + GPIO_PUD(gpio_periph) = pupd; +} + +/*! + \brief set GPIO output type and speed + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] otype: GPIO pin output mode + \arg GPIO_OTYPE_PP: push pull mode + \arg GPIO_OTYPE_OD: open drain mode + \param[in] speed: GPIO pin output max speed + \arg GPIO_OSPEED_2MHZ: output max speed 2MHz + \arg GPIO_OSPEED_10MHZ: output max speed 10MHz + \arg GPIO_OSPEED_50MHZ: output max speed 50MHz + \arg GPIO_OSPEED_MAX: output max speed more than 50MHz + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval none +*/ +void gpio_output_options_set(uint32_t gpio_periph, uint8_t otype, uint32_t speed, uint32_t pin) +{ + uint16_t i; + uint32_t ospeedr; + + if(GPIO_OTYPE_OD == otype) { + GPIO_OMODE(gpio_periph) |= (uint32_t)pin; + } else { + GPIO_OMODE(gpio_periph) &= (uint32_t)(~pin); + } + + /* get the specified pin output speed bits value */ + ospeedr = GPIO_OSPD(gpio_periph); + + for(i = 0U; i < 16U; i++) { + if((1U << i) & pin) { + /* clear the specified pin output speed bits */ + ospeedr &= ~GPIO_OSPEED_MASK(i); + /* set the specified pin output speed bits */ + ospeedr |= GPIO_OSPEED_SET(i, speed); + } + } + GPIO_OSPD(gpio_periph) = ospeedr; +} + +/*! + \brief set GPIO pin bit + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval none +*/ +void gpio_bit_set(uint32_t gpio_periph, uint32_t pin) +{ + GPIO_BOP(gpio_periph) = (uint32_t)pin; +} + +/*! + \brief reset GPIO pin bit + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval none +*/ +void gpio_bit_reset(uint32_t gpio_periph, uint32_t pin) +{ + GPIO_BC(gpio_periph) = (uint32_t)pin; +} + +/*! + \brief write data to the specified GPIO pin + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[in] bit_value: SET or RESET + \arg RESET: clear the port pin + \arg SET: set the port pin + \param[out] none + \retval none +*/ +void gpio_bit_write(uint32_t gpio_periph, uint32_t pin, bit_status bit_value) +{ + if(RESET != bit_value) { + GPIO_BOP(gpio_periph) = (uint32_t)pin; + } else { + GPIO_BC(gpio_periph) = (uint32_t)pin; + } +} + +/*! + \brief write data to the specified GPIO port + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] data: specify the value to be written to the port output control register + \param[out] none + \retval none +*/ +void gpio_port_write(uint32_t gpio_periph, uint16_t data) +{ + GPIO_OCTL(gpio_periph) = (uint32_t)data; +} + +/*! + \brief get GPIO pin input status + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval input status of GPIO pin: SET or RESET +*/ +FlagStatus gpio_input_bit_get(uint32_t gpio_periph, uint32_t pin) +{ + if((uint32_t)RESET != (GPIO_ISTAT(gpio_periph) & (pin))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief get GPIO all pins input status + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[out] none + \retval input status of GPIO all pins +*/ +uint16_t gpio_input_port_get(uint32_t gpio_periph) +{ + return ((uint16_t)GPIO_ISTAT(gpio_periph)); +} + +/*! + \brief get GPIO pin output status + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval output status of GPIO pin: SET or RESET +*/ +FlagStatus gpio_output_bit_get(uint32_t gpio_periph, uint32_t pin) +{ + if((uint32_t)RESET != (GPIO_OCTL(gpio_periph) & (pin))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief get GPIO port output status + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[out] none + \retval output status of GPIO all pins +*/ +uint16_t gpio_output_port_get(uint32_t gpio_periph) +{ + return ((uint16_t)GPIO_OCTL(gpio_periph)); +} + +/*! + \brief set GPIO alternate function + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] alt_func_num: GPIO pin af function + \arg GPIO_AF_0: SYSTEM + \arg GPIO_AF_1: TIMER0, TIMER1, TIMER7 + \arg GPIO_AF_2: TIMER0, TIMER2, TIMER3, TIMER4 + \arg GPIO_AF_3: TIMER7, TIMER8, TIMER9, TIMER10 + \arg GPIO_AF_4: I2C0, I2C1, I2C2, I2C3, SPI4, TIMER0 + \arg GPIO_AF_5: SPI0, SPI1, SPI2, SPI3, SPI4, SPI5, I2C3 + \arg GPIO_AF_6: SPI1, SPI2, SPI3, SPI4, SAI0, I2C4 + \arg GPIO_AF_7: USART0, USART1, USART2, SPI0, SPI1, SPI2 + \arg GPIO_AF_8: UART3, UART4, USART5, UART6, UART7 + \arg GPIO_AF_9: CAN0, CAN1, TLI, TIMER11, TIMER12, TIMER13, I2C1, I2C2, CTC + \arg GPIO_AF_10: USB_FS, USB_HS + \arg GPIO_AF_11: ENET + \arg GPIO_AF_12: EXMC, SDIO, USB_HS + \arg GPIO_AF_13: DCI + \arg GPIO_AF_14: TLI + \arg GPIO_AF_15: EVENTOUT + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval none +*/ +void gpio_af_set(uint32_t gpio_periph, uint32_t alt_func_num, uint32_t pin) +{ + uint16_t i; + uint32_t afrl, afrh; + + afrl = GPIO_AFSEL0(gpio_periph); + afrh = GPIO_AFSEL1(gpio_periph); + + for(i = 0U; i < 8U; i++) { + if((1U << i) & pin) { + /* clear the specified pin alternate function bits */ + afrl &= ~GPIO_AFR_MASK(i); + afrl |= GPIO_AFR_SET(i, alt_func_num); + } + } + + for(i = 8U; i < 16U; i++) { + if((1U << i) & pin) { + /* clear the specified pin alternate function bits */ + afrh &= ~GPIO_AFR_MASK(i - 8U); + afrh |= GPIO_AFR_SET(i - 8U, alt_func_num); + } + } + + GPIO_AFSEL0(gpio_periph) = afrl; + GPIO_AFSEL1(gpio_periph) = afrh; +} + +/*! + \brief lock GPIO pin bit + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval none +*/ +void gpio_pin_lock(uint32_t gpio_periph, uint32_t pin) +{ + uint32_t lock = 0x00010000U; + lock |= pin; + + /* lock key writing sequence: write 1->write 0->write 1->read 0->read 1 */ + GPIO_LOCK(gpio_periph) = (uint32_t)lock; + GPIO_LOCK(gpio_periph) = (uint32_t)pin; + GPIO_LOCK(gpio_periph) = (uint32_t)lock; + lock = GPIO_LOCK(gpio_periph); + lock = GPIO_LOCK(gpio_periph); +} + +/*! + \brief toggle GPIO pin status + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + \param[in] pin: GPIO pin + one or more parameters can be selected which are shown as below: + \arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL + \param[out] none + \retval none +*/ +void gpio_bit_toggle(uint32_t gpio_periph, uint32_t pin) +{ + GPIO_TG(gpio_periph) = (uint32_t)pin; +} + +/*! + \brief toggle GPIO port status + \param[in] gpio_periph: GPIO port + only one parameter can be selected which is shown as below: + \arg GPIOx(x = A,B,C,D,E,F,G,H,I) + + \param[out] none + \retval none +*/ +void gpio_port_toggle(uint32_t gpio_periph) +{ + GPIO_TG(gpio_periph) = 0x0000FFFFU; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_hau.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_hau.c new file mode 100644 index 0000000..2a020d9 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_hau.c @@ -0,0 +1,402 @@ +/*! + \file gd32f5xx_hau.c + \brief HAU driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_hau.h" + +#define HASH_CONTEXT_INTERNAL_REG 37U +#define HMAC_CONTEXT_INTERNAL_REG 53U + +/*! + \brief reset the HAU peripheral + \param[in] none + \param[out] none + \retval none +*/ +void hau_deinit(void) +{ + /* enable HAU reset state */ + rcu_periph_reset_enable(RCU_HAURST); + /* release HAU from reset state */ + rcu_periph_reset_disable(RCU_HAURST); +} + +/*! + \brief initialize the HAU peripheral parameters + \param[in] none + \param[out] initpara: HAU init parameter struct + members of the structure and the member values are shown as below: + algo: HAU_ALGO_SHA1, HAU_ALGO_SHA224, HAU_ALGO_SHA256, HAU_ALGO_MD5 + mode: HAU_MODE_HASH, HAU_MODE_HMAC + datatype: HAU_SWAPPING_32BIT, HAU_SWAPPING_16BIT, HAU_SWAPPING_8BIT, HAU_SWAPPING_1BIT + keytype: HAU_KEY_SHORTER_64, HAU_KEY_LONGGER_64 + \retval none +*/ +void hau_init(hau_init_parameter_struct* initpara) +{ + /* configure the algorithm, mode and the data type */ + HAU_CTL &= (~(uint32_t)(HAU_CTL_ALGM_0 | HAU_CTL_ALGM_1 | HAU_CTL_DATAM | HAU_CTL_HMS)); + HAU_CTL |= (initpara->algo | initpara->datatype | initpara->mode); + + /* when mode is HMAC, set the key */ + if(HAU_MODE_HMAC == initpara->mode){ + HAU_CTL &= (~(uint32_t)(HAU_CTL_KLM)); + HAU_CTL |= initpara->keytype; + } + + /* start the digest of a new message */ + HAU_CTL |= HAU_CTL_START; +} + +/*! + \brief initialize the sturct hau_initpara + \param[in] initpara: HAU init parameter struct + members of the structure and the member values are shown as below: + algo: HAU_ALGO_SHA1, HAU_ALGO_SHA224, HAU_ALGO_SHA256, HAU_ALGO_MD5 + mode: HAU_MODE_HASH, HAU_MODE_HMAC + datatype: HAU_SWAPPING_32BIT, HAU_SWAPPING_16BIT, HAU_SWAPPING_8BIT, HAU_SWAPPING_1BIT + keytype: HAU_KEY_SHORTER_64, HAU_KEY_LONGGER_64 + \param[out] none + \retval none +*/ +void hau_init_struct_para_init(hau_init_parameter_struct* initpara) +{ + initpara->algo = HAU_ALGO_SHA1; + initpara->mode = HAU_MODE_HASH; + initpara->datatype = HAU_SWAPPING_32BIT; + initpara->keytype = HAU_KEY_SHORTER_64; +} + +/*! + \brief reset the HAU processor core + \param[in] none + \param[out] none + \retval none +*/ +void hau_reset(void) +{ + /* set to 1 to reset the HAU processor core, then it is ready to start the digest calculation */ + HAU_CTL |= HAU_CTL_START; +} + +/*! + \brief configure the number of valid bits in last word of the message + \param[in] valid_num: number of valid bits in last word of the message + only one parameter can be selected which is shown as below: + \arg 0x00: all 32 bits of the last data written are valid + \arg 0x01: only bit [31] of the last data written to HAU_DI after data swapping are valid + \arg 0x02: only bits [31:30] of the last data written to HAU_DI after data swapping are valid + \arg 0x03: only bits [31:29] of the last data written to HAU_DI after data swapping are valid + ... + \arg 0x1F: only bit [0] of the last data written to HAU_DI after data swapping are valid + \param[out] none + \retval none +*/ +void hau_last_word_validbits_num_config(uint32_t valid_num) +{ + HAU_CFG &= (~(uint32_t)(HAU_CFG_VBL)); + HAU_CFG |= CFG_VBL(valid_num); +} + +/*! + \brief write data to the IN FIFO + \param[in] data: data to write + \param[out] none + \retval none +*/ +void hau_data_write(uint32_t data) +{ + HAU_DI = data; +} + +/*! + \brief return the number of words already written into the IN FIFO + \param[in] none + \param[out] none + \retval number of words in the input FIFO +*/ +uint32_t hau_infifo_words_num_get(void) +{ + uint32_t ret = 0U; + ret = GET_CTL_NWIF(HAU_CTL); + return ret; +} + +/*! + \brief read the message digest result + \param[in] none + \param[out] digestpara: HAU digest parameter struct + out[7:0]: message digest result 0-7 + \retval none +*/ +void hau_digest_read(hau_digest_parameter_struct* digestpara) +{ + digestpara->out[0] = HAU_DO0; + digestpara->out[1] = HAU_DO1; + digestpara->out[2] = HAU_DO2; + digestpara->out[3] = HAU_DO3; + digestpara->out[4] = HAU_DO4; + digestpara->out[5] = HAU_DO5; + digestpara->out[6] = HAU_DO6; + digestpara->out[7] = HAU_DO7; +} + +/*! + \brief enable digest calculation + \param[in] none + \param[out] none + \retval none +*/ +void hau_digest_calculation_enable(void) +{ + HAU_CFG |= HAU_CFG_CALEN; +} + +/*! + \brief configure single or multiple DMA is used, and digest calculation at the end of a DMA transfer or not + \param[in] multi_single + only one parameter can be selected which is shown as below + \arg SINGLE_DMA_AUTO_DIGEST: message padding and message digest calculation at the end of a DMA transfer + \arg MULTIPLE_DMA_NO_DIGEST: multiple DMA transfers needed and CALEN bit is not automatically set at the end of a DMA transfer + \param[out] none + \retval none +*/ +void hau_multiple_single_dma_config(uint32_t multi_single) +{ + HAU_CTL &= (~(uint32_t)(HAU_CTL_MDS)); + HAU_CTL |= multi_single; +} + +/*! + \brief enable the HAU DMA interface + \param[in] none + \param[out] none + \retval none +*/ +void hau_dma_enable(void) +{ + HAU_CTL |= HAU_CTL_DMAE; +} + +/*! + \brief disable the HAU DMA interface + \param[in] none + \param[out] none + \retval none +*/ +void hau_dma_disable(void) +{ + HAU_CTL &= (~(uint32_t)(HAU_CTL_DMAE)); +} + +/*! + \brief initialize the struct context + \param[in] context: HAU context parameter struct + \param[out] none + \retval none +*/ +void hau_context_struct_para_init(hau_context_parameter_struct* context) +{ + uint8_t i = 0U; + + /* initialize context parameter struct */ + context->hau_inten_bak = 0U; + context->hau_cfg_bak = 0U; + context->hau_ctl_bak = 0U; + for(i = 0U; i <= HMAC_CONTEXT_INTERNAL_REG; i++){ + context->hau_ctxs_bak[i] = 0U; + } +} + +/*! + \brief save the HAU peripheral context + \param[in] none + \param[out] context_save: pointer to a hau_context structure that contains the repository for current context + \retval none +*/ +void hau_context_save(hau_context_parameter_struct* context_save) +{ + uint8_t i = 0U; + uint8_t i_max = HASH_CONTEXT_INTERNAL_REG; + + hau_context_struct_para_init(context_save); + /* save context registers */ + context_save->hau_inten_bak = HAU_INTEN; + context_save->hau_cfg_bak = HAU_CFG; + context_save->hau_ctl_bak = HAU_CTL; + + if(0U != (HAU_CTL & HAU_CTL_HMS)){ + i_max = HMAC_CONTEXT_INTERNAL_REG; + } + for(i = 0U; i <= i_max; i++){ + context_save->hau_ctxs_bak[i] = HAU_CTXS(i); + } +} + +/*! + \brief restore the HAU peripheral context + \param[in] context_restore: pointer to a hau_context_parameter_struct structure that contains the repository for saved context + \param[out] none + \retval none +*/ +void hau_context_restore(hau_context_parameter_struct* context_restore) +{ + uint8_t i = 0U; + uint8_t i_max = HASH_CONTEXT_INTERNAL_REG; + + /* restore context registers */ + HAU_INTEN = context_restore->hau_inten_bak; + HAU_CFG = context_restore->hau_cfg_bak; + HAU_CTL = context_restore->hau_ctl_bak; + /* Initialize the hash processor */ + HAU_CTL |= HAU_CTL_START; + + /* continue restoring context registers */ + if(0U != (HAU_CTL & HAU_CTL_HMS)){ + i_max = HMAC_CONTEXT_INTERNAL_REG; + } + for(i = 0U; i <= i_max; i++){ + HAU_CTXS(i) = context_restore->hau_ctxs_bak[i]; + } +} + +/*! + \brief get the HAU flag status + \param[in] flag: HAU flag status + only one parameter can be selected which is shown as below: + \arg HAU_FLAG_DATA_INPUT: there is enough space (16 bytes) in the input FIFO + \arg HAU_FLAG_CALCULATION_COMPLETE: digest calculation is completed + \arg HAU_FLAG_DMA: DMA is enabled (DMAE =1) or a transfer is processing + \arg HAU_FLAG_BUSY: data block is in process + \arg HAU_FLAG_INFIFO_NO_EMPTY: the input FIFO is not empty + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus hau_flag_get(uint32_t flag) +{ + uint32_t ret = 0U; + FlagStatus ret_flag = RESET; + + /* check if the flag is in HAU_CTL register */ + if(RESET != (flag & HAU_FLAG_INFIFO_NO_EMPTY)){ + ret = HAU_CTL; + }else{ + ret = HAU_STAT; + } + + if (RESET != (ret & flag)){ + ret_flag = SET; + } + + return ret_flag; +} + +/*! + \brief clear the HAU flag status + \param[in] flag: HAU flag status + one or more parameters can be selected which are shown as below + \arg HAU_FLAG_DATA_INPUT: there is enough space (16 bytes) in the input FIFO + \arg HAU_FLAG_CALCULATION_COMPLETE: digest calculation is completed + \param[out] none + \retval none +*/ +void hau_flag_clear(uint32_t flag) +{ + HAU_STAT = ~(uint32_t)(flag); +} + +/*! + \brief enable the HAU interrupts + \param[in] interrupt: specify the HAU interrupt source to be enabled + one or more parameters can be selected which are shown as below + \arg HAU_INT_DATA_INPUT: a new block can be entered into the IN buffer + \arg HAU_INT_CALCULATION_COMPLETE: calculation complete + \param[out] none + \retval none +*/ +void hau_interrupt_enable(uint32_t interrupt) +{ + HAU_INTEN |= interrupt; +} + +/*! + \brief disable the HAU interrupts + \param[in] interrupt: specify the HAU interrupt source to be disabled + one or more parameters can be selected which are shown as below + \arg HAU_INT_DATA_INPUT: a new block can be entered into the IN buffer + \arg HAU_INT_CALCULATION_COMPLETE: calculation complete + \param[out] none + \retval none +*/ +void hau_interrupt_disable(uint32_t interrupt) +{ + HAU_INTEN &= ~(uint32_t)(interrupt); +} + +/*! + \brief get the HAU interrupt flag status + \param[in] int_flag: HAU interrupt flag status + only one parameter can be selected which is shown as below + \arg HAU_INT_FLAG_DATA_INPUT: there is enough space (16 bytes) in the input FIFO + \arg HAU_INT_FLAG_CALCULATION_COMPLETE: digest calculation is completed + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus hau_interrupt_flag_get(uint32_t int_flag) +{ + uint32_t ret = 0U; + FlagStatus flag = RESET; + + /* return the status of the interrupt */ + ret = HAU_STAT; + + if(RESET != ((HAU_INTEN & ret) & int_flag)){ + flag = SET; + } + + return flag; +} + +/*! + \brief clear the HAU interrupt flag status + \param[in] int_flag: HAU interrupt flag status + one or more parameters can be selected which are shown as below + \arg HAU_INT_FLAG_DATA_INPUT: there is enough space (16 bytes) in the input FIFO + \arg HAU_INT_FLAG_CALCULATION_COMPLETE: digest calculation is completed + \param[out] none + \retval none +*/ +void hau_interrupt_flag_clear(uint32_t int_flag) +{ + HAU_STAT = ~(uint32_t)(int_flag); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_hau_sha_md5.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_hau_sha_md5.c new file mode 100644 index 0000000..f8de361 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_hau_sha_md5.c @@ -0,0 +1,419 @@ +/*! + \file gd32f5xx_hau_sha_md5.c + \brief HAU_SHA_MD5 driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_hau.h" + +#define SHAMD5_BSY_TIMEOUT ((uint32_t)0x00010000U) + +/* HAU SHA/MD5 digest read in HASH mode */ +static void hau_sha_md5_digest_read(uint32_t algo, uint8_t *output); +/* HAU digest calculate process in HASH mode */ +static ErrStatus hau_hash_calculate(uint32_t algo, uint8_t *input, uint32_t in_length, uint8_t *output); +/* HAU digest calculate process in HMAC mode */ +static ErrStatus hau_hmac_calculate(uint32_t algo, uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t *output); + +/*! + \brief calculate digest using SHA1 in HASH mode + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus hau_hash_sha_1(uint8_t *input, uint32_t in_length, uint8_t output[]) +{ + ErrStatus ret = ERROR; + ret = hau_hash_calculate(HAU_ALGO_SHA1, input, in_length, output); + return ret; +} + +/*! + \brief calculate digest using SHA1 in HMAC mode + \param[in] key: pointer to the key used for HMAC + \param[in] keysize: length of the key used for HMAC + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus hau_hmac_sha_1(uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t output[]) +{ + ErrStatus ret = ERROR; + ret = hau_hmac_calculate(HAU_ALGO_SHA1, key, keysize, input, in_length, output); + return ret; +} + +/*! + \brief calculate digest using SHA224 in HASH mode + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus hau_hash_sha_224(uint8_t *input, uint32_t in_length, uint8_t output[]) +{ + ErrStatus ret = ERROR; + ret = hau_hash_calculate(HAU_ALGO_SHA224, input, in_length, output); + return ret; +} + +/*! + \brief calculate digest using SHA224 in HMAC mode + \param[in] key: pointer to the key used for HMAC + \param[in] keysize: length of the key used for HMAC + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus hau_hmac_sha_224(uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t output[]) +{ + ErrStatus ret = ERROR; + ret = hau_hmac_calculate(HAU_ALGO_SHA224, key, keysize, input, in_length, output); + return ret; +} + +/*! + \brief calculate digest using SHA256 in HASH mode + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus hau_hash_sha_256(uint8_t *input, uint32_t in_length, uint8_t output[]) +{ + ErrStatus ret = ERROR; + ret = hau_hash_calculate(HAU_ALGO_SHA256, input, in_length, output); + return ret; +} + +/*! + \brief calculate digest using SHA256 in HMAC mode + \param[in] key: pointer to the key used for HMAC + \param[in] keysize: length of the key used for HMAC + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus hau_hmac_sha_256(uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t output[]) +{ + ErrStatus ret = ERROR; + ret = hau_hmac_calculate(HAU_ALGO_SHA256, key, keysize, input, in_length, output); + return ret; +} + +/*! + \brief calculate digest using MD5 in HASH mode + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus hau_hash_md5(uint8_t *input, uint32_t in_length, uint8_t output[]) +{ + ErrStatus ret = ERROR; + ret = hau_hash_calculate(HAU_ALGO_MD5, input, in_length, output); + return ret; +} + +/*! + \brief calculate digest using MD5 in HMAC mode + \param[in] key: pointer to the key used for HMAC + \param[in] keysize: length of the key used for HMAC + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus hau_hmac_md5(uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t output[]) +{ + ErrStatus ret = ERROR; + ret = hau_hmac_calculate(HAU_ALGO_MD5, key, keysize, input, in_length, output); + return ret; +} + +/*! + \brief HAU SHA/MD5 digest read + \param[in] algo: algorithm selection + \param[out] output: the result digest + \retval none +*/ +static void hau_sha_md5_digest_read(uint32_t algo, uint8_t *output) +{ + hau_digest_parameter_struct digest_para; + uint32_t outputaddr = (uint32_t)output; + + switch(algo){ + case HAU_ALGO_SHA1: + hau_digest_read(&digest_para); + *(uint32_t*)(outputaddr) = __REV(digest_para.out[0]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[1]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[2]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[3]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[4]); + break; + case HAU_ALGO_SHA224: + hau_digest_read(&digest_para); + *(uint32_t*)(outputaddr) = __REV(digest_para.out[0]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[1]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[2]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[3]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[4]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[5]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[6]); + break; + case HAU_ALGO_SHA256: + hau_digest_read(&digest_para); + *(uint32_t*)(outputaddr) = __REV(digest_para.out[0]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[1]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[2]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[3]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[4]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[5]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[6]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[7]); + break; + case HAU_ALGO_MD5: + hau_digest_read(&digest_para); + *(uint32_t*)(outputaddr) = __REV(digest_para.out[0]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[1]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[2]); + outputaddr += 4U; + *(uint32_t*)(outputaddr) = __REV(digest_para.out[3]); + break; + default: + break; + } +} + +/*! + \brief HAU digest calculate process in HASH mode + \param[in] algo: algorithm selection + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +static ErrStatus hau_hash_calculate(uint32_t algo, uint8_t *input, uint32_t in_length, uint8_t *output) +{ + hau_init_parameter_struct init_para; + + __IO uint32_t num_last_valid = 0U; + uint32_t i = 0U; + __IO uint32_t counter = 0U; + uint32_t busystatus = 0U; + uint32_t inputaddr = (uint32_t)input; + + /* number of valid bits in last word */ + num_last_valid = 8U * (in_length % 4U); + + /* HAU peripheral initialization */ + hau_deinit(); + + /* HAU configuration */ + init_para.algo = algo; + init_para.mode = HAU_MODE_HASH; + init_para.datatype = HAU_SWAPPING_8BIT; + hau_init(&init_para); + + /* configure the number of valid bits in last word of the message */ + hau_last_word_validbits_num_config(num_last_valid); + + /* write data to the IN FIFO */ + for(i = 0U; i < in_length; i += 4U){ + hau_data_write(*(uint32_t*)inputaddr); + inputaddr += 4U; + } + + /* enable digest calculation */ + hau_digest_calculation_enable(); + + /* wait until the busy flag is reset */ + do{ + busystatus = hau_flag_get(HAU_FLAG_BUSY); + counter++; + }while((SHAMD5_BSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus){ + return ERROR; + }else{ + /* read the message digest */ + hau_sha_md5_digest_read(algo, output); + } + return SUCCESS; +} + +/*! + \brief HAU digest calculate process in HMAC mode + \param[in] algo: algorithm selection + \param[in] key: pointer to the key used for HMAC + \param[in] keysize: length of the key used for HMAC + \param[in] input: pointer to the input buffer + \param[in] in_length: length of the input buffer + \param[in] output: the result digest + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +static ErrStatus hau_hmac_calculate(uint32_t algo, uint8_t *key, uint32_t keysize, uint8_t *input, uint32_t in_length, uint8_t *output) +{ + hau_init_parameter_struct init_para; + + __IO uint16_t num_last_valid = 0U; + __IO uint16_t num_key_valid = 0U; + uint32_t i = 0U; + __IO uint32_t counter = 0U; + uint32_t busystatus = 0U; + uint32_t keyaddr = (uint32_t)key; + uint32_t inputaddr = (uint32_t)input; + + /* number of valid bits in last word of the message */ + num_last_valid = 8U * (uint16_t)(in_length % 4U); + /* number of valid bits in last word of the key */ + num_key_valid = 8U * (uint16_t)(keysize % 4U); + + /* HAU peripheral initialization */ + hau_deinit(); + + /* HAU configuration */ + init_para.algo = algo; + init_para.mode = HAU_MODE_HMAC; + init_para.datatype = HAU_SWAPPING_8BIT; + if(keysize > 64U){ + init_para.keytype = HAU_KEY_LONGGER_64; + }else{ + init_para.keytype = HAU_KEY_SHORTER_64; + } + hau_init(&init_para); + + /* configure the number of valid bits in last word of the key */ + hau_last_word_validbits_num_config((uint32_t)num_key_valid); + + /* write the key */ + for(i = 0U; i < keysize; i += 4U){ + hau_data_write(*(uint32_t*)keyaddr); + keyaddr += 4U; + } + + /* enable digest calculation */ + hau_digest_calculation_enable(); + + /* wait until the busy flag is reset */ + do{ + busystatus = hau_flag_get(HAU_FLAG_BUSY); + counter++; + }while((SHAMD5_BSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus){ + return ERROR; + }else{ + /* configure the number of valid bits in last word of the message */ + hau_last_word_validbits_num_config((uint32_t)num_last_valid); + + /* write data to the IN FIFO */ + for(i = 0U; i < in_length; i += 4U){ + hau_data_write(*(uint32_t*)inputaddr); + inputaddr += 4U; + } + + /* enable digest calculation */ + hau_digest_calculation_enable(); + + /* wait until the busy flag is reset */ + counter = 0U; + do{ + busystatus = hau_flag_get(HAU_FLAG_BUSY); + counter++; + }while((SHAMD5_BSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus){ + return ERROR; + }else{ + /* configure the number of valid bits in last word of the key */ + hau_last_word_validbits_num_config((uint32_t)num_key_valid); + + /* write the key */ + keyaddr = (uint32_t)key; + for(i = 0U; i < keysize; i += 4U){ + hau_data_write(*(uint32_t*)keyaddr); + keyaddr += 4U; + } + + /* enable digest calculation */ + hau_digest_calculation_enable(); + + /* wait until the busy flag is reset */ + counter =0U; + do{ + busystatus = hau_flag_get(HAU_FLAG_BUSY); + counter++; + }while((SHAMD5_BSY_TIMEOUT != counter) && (RESET != busystatus)); + + if(RESET != busystatus){ + return ERROR; + }else{ + /* read the message digest */ + hau_sha_md5_digest_read(algo, output); + } + } + } + return SUCCESS; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_i2c.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_i2c.c new file mode 100644 index 0000000..2dc6bb2 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_i2c.c @@ -0,0 +1,857 @@ +/*! + \file gd32f5xx_i2c.c + \brief I2C driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_i2c.h" + +/* I2C register bit mask */ +#define I2CCLK_MAX ((uint32_t)0x00000032U) /*!< i2cclk maximum value */ +#define I2CCLK_MIN ((uint32_t)0x00000002U) /*!< i2cclk minimum value */ +#define I2C_FLAG_MASK ((uint32_t)0x0000FFFFU) /*!< i2c flag mask */ +#define I2C_ADDRESS_MASK ((uint32_t)0x000003FFU) /*!< i2c address mask */ +#define I2C_ADDRESS2_MASK ((uint32_t)0x000000FEU) /*!< the second i2c address mask */ + +/* I2C register bit offset */ +#define STAT1_PECV_OFFSET ((uint32_t)0x00000008U) /* bit offset of PECV in I2C_STAT1 */ + +/*! + \brief reset I2C + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_deinit(uint32_t i2c_periph) +{ + switch(i2c_periph) { + case I2C0: + /* reset I2C0 */ + rcu_periph_reset_enable(RCU_I2C0RST); + rcu_periph_reset_disable(RCU_I2C0RST); + break; + case I2C1: + /* reset I2C1 */ + rcu_periph_reset_enable(RCU_I2C1RST); + rcu_periph_reset_disable(RCU_I2C1RST); + break; + case I2C2: + /* reset I2C2 */ + rcu_periph_reset_enable(RCU_I2C2RST); + rcu_periph_reset_disable(RCU_I2C2RST); + break; + default: + break; + } +} + +/*! + \brief configure I2C clock + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] clkspeed: I2C clock speed, supports standard mode (up to 100 kHz), fast mode (up to 400 kHz) + \param[in] dutycyc: duty cycle in fast mode + only one parameter can be selected which is shown as below: + \arg I2C_DTCY_2: T_low/T_high = 2 in fast mode + \arg I2C_DTCY_16_9: T_low/T_high = 16/9 in fast mode + \param[out] none + \retval none +*/ +void i2c_clock_config(uint32_t i2c_periph, uint32_t clkspeed, uint32_t dutycyc) +{ + uint32_t pclk1, clkc, freq, risetime; + uint32_t temp; + + pclk1 = rcu_clock_freq_get(CK_APB1); + /* I2C peripheral clock frequency */ + freq = (uint32_t)(pclk1 / 1000000U); + if(freq >= I2CCLK_MAX) { + freq = I2CCLK_MAX; + } + temp = I2C_CTL1(i2c_periph); + temp &= ~I2C_CTL1_I2CCLK; + temp |= freq; + + I2C_CTL1(i2c_periph) = temp; + + if(100000U >= clkspeed) { + /* the maximum SCL rise time is 1000ns in standard mode */ + risetime = (uint32_t)((pclk1 / 1000000U) + 1U); + if(risetime >= I2CCLK_MAX) { + I2C_RT(i2c_periph) = I2CCLK_MAX; + } else if(risetime <= I2CCLK_MIN) { + I2C_RT(i2c_periph) = I2CCLK_MIN; + } else { + I2C_RT(i2c_periph) = risetime; + } + clkc = (uint32_t)(pclk1 / (clkspeed * 2U)); + if(clkc < 0x04U) { + /* the CLKC in standard mode minmum value is 4 */ + clkc = 0x04U; + } + + I2C_CKCFG(i2c_periph) |= (I2C_CKCFG_CLKC & clkc); + + } else if(400000U >= clkspeed) { + /* the maximum SCL rise time is 300ns in fast mode */ + I2C_RT(i2c_periph) = (uint32_t)(((freq * (uint32_t)300U) / (uint32_t)1000U) + (uint32_t)1U); + if(I2C_DTCY_2 == dutycyc) { + /* I2C duty cycle is 2 */ + clkc = (uint32_t)(pclk1 / (clkspeed * 3U)); + I2C_CKCFG(i2c_periph) &= ~I2C_CKCFG_DTCY; + } else { + /* I2C duty cycle is 16/9 */ + clkc = (uint32_t)(pclk1 / (clkspeed * 25U)); + I2C_CKCFG(i2c_periph) |= I2C_CKCFG_DTCY; + } + if(0U == (clkc & I2C_CKCFG_CLKC)) { + /* the CLKC in fast mode minmum value is 1 */ + clkc |= 0x0001U; + } + I2C_CKCFG(i2c_periph) |= I2C_CKCFG_FAST; + I2C_CKCFG(i2c_periph) |= clkc; + } else { + } +} + +/*! + \brief configure I2C address + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] mode: + only one parameter can be selected which is shown as below: + \arg I2C_I2CMODE_ENABLE: I2C mode + \arg I2C_SMBUSMODE_ENABLE: SMBus mode + \param[in] addformat: 7bits or 10bits + only one parameter can be selected which is shown as below: + \arg I2C_ADDFORMAT_7BITS: address format is 7 bits + \arg I2C_ADDFORMAT_10BITS: address format is 10 bits + \param[in] addr: I2C address + \param[out] none + \retval none +*/ +void i2c_mode_addr_config(uint32_t i2c_periph, uint32_t mode, uint32_t addformat, uint32_t addr) +{ + /* SMBus/I2C mode selected */ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_SMBEN); + ctl |= mode; + I2C_CTL0(i2c_periph) = ctl; + /* configure address */ + addr = addr & I2C_ADDRESS_MASK; + I2C_SADDR0(i2c_periph) = (addformat | addr); +} + +/*! + \brief select SMBus type + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] type: + only one parameter can be selected which is shown as below: + \arg I2C_SMBUS_DEVICE: SMBus mode device type + \arg I2C_SMBUS_HOST: SMBus mode host type + \param[out] none + \retval none +*/ +void i2c_smbus_type_config(uint32_t i2c_periph, uint32_t type) +{ + if(I2C_SMBUS_HOST == type) { + I2C_CTL0(i2c_periph) |= I2C_CTL0_SMBSEL; + } else { + I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_SMBSEL); + } +} + +/*! + \brief whether or not to send an ACK + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] ack: + only one parameter can be selected which is shown as below: + \arg I2C_ACK_ENABLE: ACK will be sent + \arg I2C_ACK_DISABLE: ACK will not be sent + \param[out] none + \retval none +*/ +void i2c_ack_config(uint32_t i2c_periph, uint32_t ack) +{ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_ACKEN); + ctl |= ack; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief configure I2C POAP position + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] pos: + only one parameter can be selected which is shown as below: + \arg I2C_ACKPOS_CURRENT: ACKEN bit decides whether or not to send ACK or not for the current byte + \arg I2C_ACKPOS_NEXT: ACKEN bit decides whether or not to send ACK for the next byte + \param[out] none + \retval none +*/ +void i2c_ackpos_config(uint32_t i2c_periph, uint32_t pos) +{ + uint32_t ctl = 0U; + /* configure I2C POAP position */ + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_POAP); + ctl |= pos; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief master sends slave address + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] addr: slave address + \param[in] trandirection: transmitter or receiver + only one parameter can be selected which is shown as below: + \arg I2C_TRANSMITTER: transmitter + \arg I2C_RECEIVER: receiver + \param[out] none + \retval none +*/ +void i2c_master_addressing(uint32_t i2c_periph, uint32_t addr, uint32_t trandirection) +{ + /* master is a transmitter or a receiver */ + if(I2C_TRANSMITTER == trandirection) { + addr = addr & I2C_TRANSMITTER; + } else { + addr = addr | I2C_RECEIVER; + } + /* send slave address */ + I2C_DATA(i2c_periph) = addr; +} + +/*! + \brief enable dual-address mode + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] addr: the second address in dual-address mode + \param[out] none + \retval none +*/ +void i2c_dualaddr_enable(uint32_t i2c_periph, uint32_t addr) +{ + /* configure address */ + addr = addr & I2C_ADDRESS2_MASK; + I2C_SADDR1(i2c_periph) = (I2C_SADDR1_DUADEN | addr); +} + +/*! + \brief disable dual-address mode + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_dualaddr_disable(uint32_t i2c_periph) +{ + I2C_SADDR1(i2c_periph) &= ~(I2C_SADDR1_DUADEN); +} + +/*! + \brief enable I2C + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_enable(uint32_t i2c_periph) +{ + I2C_CTL0(i2c_periph) |= I2C_CTL0_I2CEN; +} + +/*! + \brief disable I2C + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_disable(uint32_t i2c_periph) +{ + I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_I2CEN); +} + +/*! + \brief generate a START condition on I2C bus + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_start_on_bus(uint32_t i2c_periph) +{ + I2C_CTL0(i2c_periph) |= I2C_CTL0_START; +} + +/*! + \brief generate a STOP condition on I2C bus + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_stop_on_bus(uint32_t i2c_periph) +{ + I2C_CTL0(i2c_periph) |= I2C_CTL0_STOP; +} + +/*! + \brief I2C transmit data function + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] data: data of transmission + \param[out] none + \retval none +*/ +void i2c_data_transmit(uint32_t i2c_periph, uint8_t data) +{ + I2C_DATA(i2c_periph) = DATA_TRANS(data); +} + +/*! + \brief I2C receive data function + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval data of received +*/ +uint8_t i2c_data_receive(uint32_t i2c_periph) +{ + return (uint8_t)DATA_RECV(I2C_DATA(i2c_periph)); +} + +/*! + \brief configure I2C DMA mode + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] dmastate: + only one parameter can be selected which is shown as below: + \arg I2C_DMA_ON: enable DMA mode + \arg I2C_DMA_OFF: disable DMA mode + \param[out] none + \retval none +*/ +void i2c_dma_config(uint32_t i2c_periph, uint32_t dmastate) +{ + /* configure I2C DMA function */ + uint32_t ctl = 0U; + + ctl = I2C_CTL1(i2c_periph); + ctl &= ~(I2C_CTL1_DMAON); + ctl |= dmastate; + I2C_CTL1(i2c_periph) = ctl; +} + +/*! + \brief configure whether next DMA EOT is DMA last transfer or not + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] dmalast: + only one parameter can be selected which is shown as below: + \arg I2C_DMALST_ON: next DMA EOT is the last transfer + \arg I2C_DMALST_OFF: next DMA EOT is not the last transfer + \param[out] none + \retval none +*/ +void i2c_dma_last_transfer_config(uint32_t i2c_periph, uint32_t dmalast) +{ + /* configure DMA last transfer */ + uint32_t ctl = 0U; + + ctl = I2C_CTL1(i2c_periph); + ctl &= ~(I2C_CTL1_DMALST); + ctl |= dmalast; + I2C_CTL1(i2c_periph) = ctl; +} + +/*! + \brief configure RBNE clear condition + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] rbnecondition: + only one parameter can be selected which is shown as below: + \arg I2C_CFGRBNE_ON: RBNE can be cleared when RDATA is read + \arg I2C_CFGRBNE_OFF: RBNE can be cleared when RDATA is read and BTC is cleared + \param[out] none + \retval none +*/ +void i2c_rbne_clear_config(uint32_t i2c_periph, uint32_t rbnecondition) +{ + /* configure rbne clear condition */ + uint32_t ctl = 0U; + + ctl = I2C_CTL1(i2c_periph); + ctl &= ~(I2C_CTL1_CFGRBNE); + ctl |= rbnecondition; + I2C_CTL1(i2c_periph) = ctl; +} + +/*! + \brief whether to stretch SCL low when data is not ready in slave mode + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] stretchpara: + only one parameter can be selected which is shown as below: + \arg I2C_SCLSTRETCH_ENABLE: enable SCL stretching + \arg I2C_SCLSTRETCH_DISABLE: disable SCL stretching + \param[out] none + \retval none +*/ +void i2c_stretch_scl_low_config(uint32_t i2c_periph, uint32_t stretchpara) +{ + /* configure I2C SCL strerching */ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_SS); + ctl |= stretchpara; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief whether or not to response to a general call + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] gcallpara: + only one parameter can be selected which is shown as below: + \arg I2C_GCEN_ENABLE: slave will response to a general call + \arg I2C_GCEN_DISABLE: slave will not response to a general call + \param[out] none + \retval none +*/ +void i2c_slave_response_to_gcall_config(uint32_t i2c_periph, uint32_t gcallpara) +{ + /* configure slave response to a general call enable or disable */ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_GCEN); + ctl |= gcallpara; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief configure software reset of I2C + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] sreset: + only one parameter can be selected which is shown as below: + \arg I2C_SRESET_SET: I2C is under reset + \arg I2C_SRESET_RESET: I2C is not under reset + \param[out] none + \retval none +*/ +void i2c_software_reset_config(uint32_t i2c_periph, uint32_t sreset) +{ + /* modify CTL0 and configure software reset I2C state */ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_SRESET); + ctl |= sreset; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief configure I2C PEC calculation + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] pecstate: + only one parameter can be selected which is shown as below: + \arg I2C_PEC_ENABLE: PEC calculation on + \arg I2C_PEC_DISABLE: PEC calculation off + \param[out] none + \retval none +*/ +void i2c_pec_config(uint32_t i2c_periph, uint32_t pecstate) +{ + /* on/off PEC calculation */ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_PECEN); + ctl |= pecstate; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief configure whether to transfer PEC value + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] pecpara: + only one parameter can be selected which is shown as below: + \arg I2C_PECTRANS_ENABLE: transfer PEC value + \arg I2C_PECTRANS_DISABLE: not transfer PEC value + \param[out] none + \retval none +*/ +void i2c_pec_transfer_config(uint32_t i2c_periph, uint32_t pecpara) +{ + /* whether to transfer PEC */ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_PECTRANS); + ctl |= pecpara; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief get packet error checking value + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval PEC value +*/ +uint8_t i2c_pec_value_get(uint32_t i2c_periph) +{ + return (uint8_t)((I2C_STAT1(i2c_periph) & I2C_STAT1_PECV) >> STAT1_PECV_OFFSET); +} + +/*! + \brief configure I2C alert through SMBA pin + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] smbuspara: + only one parameter can be selected which is shown as below: + \arg I2C_SALTSEND_ENABLE: issue alert through SMBA pin + \arg I2C_SALTSEND_DISABLE: not issue alert through SMBA pin + \param[out] none + \retval none +*/ +void i2c_smbus_alert_config(uint32_t i2c_periph, uint32_t smbuspara) +{ + /* configure smubus alert through SMBA pin */ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_SALT); + ctl |= smbuspara; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief configure I2C ARP protocol in SMBus + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] arpstate: + only one parameter can be selected which is shown as below: + \arg I2C_ARP_ENABLE: enable ARP + \arg I2C_ARP_DISABLE: disable ARP + \param[out] none + \retval none +*/ +void i2c_smbus_arp_config(uint32_t i2c_periph, uint32_t arpstate) +{ + /* enable or disable I2C ARP protocol*/ + uint32_t ctl = 0U; + + ctl = I2C_CTL0(i2c_periph); + ctl &= ~(I2C_CTL0_ARPEN); + ctl |= arpstate; + I2C_CTL0(i2c_periph) = ctl; +} + +/*! + \brief disable analog noise filter + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_analog_noise_filter_disable(uint32_t i2c_periph) +{ + I2C_FCTL(i2c_periph) |= I2C_FCTL_AFD; +} + +/*! + \brief enable analog noise filter + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_analog_noise_filter_enable(uint32_t i2c_periph) +{ + I2C_FCTL(i2c_periph) &= ~(I2C_FCTL_AFD); +} + +/*! + \brief configure digital noise filter + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] dfilterpara: refer to i2c_digital_filter_enum + only one parameter can be selected which is shown as below: + \arg I2C_DF_DISABLE: disable digital noise filter + \arg I2C_DF_1PCLK: enable digital noise filter and the maximum filtered spiker's length 1 PCLK1 + \arg I2C_DF_2PCLK: enable digital noise filter and the maximum filtered spiker's length 2 PCLK1 + \arg I2C_DF_3PCLK: enable digital noise filter and the maximum filtered spiker's length 3 PCLK1 + \arg I2C_DF_4PCLK: enable digital noise filter and the maximum filtered spiker's length 4 PCLK1 + \arg I2C_DF_5PCLK: enable digital noise filter and the maximum filtered spiker's length 5 PCLK1 + \arg I2C_DF_6PCLK: enable digital noise filter and the maximum filtered spiker's length 6 PCLK1 + \arg I2C_DF_7PCLK: enable digital noise filter and the maximum filtered spiker's length 7 PCLK1 + \arg I2C_DF_8PCLK: enable digital noise filter and the maximum filtered spiker's length 8 PCLK1 + \arg I2C_DF_9PCLK: enable digital noise filter and the maximum filtered spiker's length 9 PCLK1 + \arg I2C_DF_10PCLK: enable digital noise filter and the maximum filtered spiker's length 10 PCLK1 + \arg I2C_DF_11CLK: enable digital noise filter and the maximum filtered spiker's length 11 PCLK1 + \arg I2C_DF_12CLK: enable digital noise filter and the maximum filtered spiker's length 12 PCLK1 + \arg I2C_DF_13PCLK: enable digital noise filter and the maximum filtered spiker's length 13 PCLK1 + \arg I2C_DF_14PCLK: enable digital noise filter and the maximum filtered spiker's length 14 PCLK1 + \arg I2C_DF_15PCLK: enable digital noise filter and the maximum filtered spiker's length 15 PCLK1 + \param[out] none + \retval none +*/ +void i2c_digital_noise_filter_config(uint32_t i2c_periph, i2c_digital_filter_enum dfilterpara) +{ + I2C_FCTL(i2c_periph) |= dfilterpara; +} + +/*! + \brief enable SAM_V interface + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_sam_enable(uint32_t i2c_periph) +{ + I2C_SAMCS(i2c_periph) |= I2C_SAMCS_SAMEN; +} + +/*! + \brief disable SAM_V interface + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_sam_disable(uint32_t i2c_periph) +{ + I2C_SAMCS(i2c_periph) &= ~(I2C_SAMCS_SAMEN); +} + +/*! + \brief enable SAM_V interface timeout detect + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_sam_timeout_enable(uint32_t i2c_periph) +{ + I2C_SAMCS(i2c_periph) |= I2C_SAMCS_STOEN; +} + +/*! + \brief disable SAM_V interface timeout detect + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[out] none + \retval none +*/ +void i2c_sam_timeout_disable(uint32_t i2c_periph) +{ + I2C_SAMCS(i2c_periph) &= ~(I2C_SAMCS_STOEN); +} + +/*! + \brief get I2C flag status + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] flag: I2C flags, refer to i2c_flag_enum + only one parameter can be selected which is shown as below: + \arg I2C_FLAG_SBSEND: start condition sent out in master mode + \arg I2C_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode + \arg I2C_FLAG_BTC: byte transmission finishes + \arg I2C_FLAG_ADD10SEND: header of 10-bit address is sent in master mode + \arg I2C_FLAG_STPDET: stop condition detected in slave mode + \arg I2C_FLAG_RBNE: I2C_DATA is not empty during receiving + \arg I2C_FLAG_TBE: I2C_DATA is empty during transmitting + \arg I2C_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus + \arg I2C_FLAG_LOSTARB: arbitration lost in master mode + \arg I2C_FLAG_AERR: acknowledge error + \arg I2C_FLAG_OUERR: over-run or under-run situation occurs in slave mode + \arg I2C_FLAG_PECERR: PEC error when receiving data + \arg I2C_FLAG_SMBTO: timeout signal in SMBus mode + \arg I2C_FLAG_SMBALT: SMBus alert status + \arg I2C_FLAG_MASTER: a flag indicating whether I2C block is in master or slave mode + \arg I2C_FLAG_I2CBSY: busy flag + \arg I2C_FLAG_TR: whether the I2C is a transmitter or a receiver + \arg I2C_FLAG_RXGC: general call address (00h) received + \arg I2C_FLAG_DEFSMB: default address of SMBus device + \arg I2C_FLAG_HSTSMB: SMBus host header detected in slave mode + \arg I2C_FLAG_DUMOD: dual flag in slave mode indicating which address is matched in dual-address mode + \arg I2C_FLAG_TFF: txframe fall flag + \arg I2C_FLAG_TFR: txframe rise flag + \arg I2C_FLAG_RFF: rxframe fall flag + \arg I2C_FLAG_RFR: rxframe rise flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus i2c_flag_get(uint32_t i2c_periph, i2c_flag_enum flag) +{ + if(RESET != (I2C_REG_VAL(i2c_periph, flag) & BIT(I2C_BIT_POS(flag)))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear I2C flag status + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] flag: I2C flags, refer to i2c_flag_enum + only one parameter can be selected which is shown as below: + \arg I2C_FLAG_SMBALT: SMBus alert status + \arg I2C_FLAG_SMBTO: timeout signal in SMBus mode + \arg I2C_FLAG_PECERR: PEC error when receiving data + \arg I2C_FLAG_OUERR: over-run or under-run situation occurs in slave mode + \arg I2C_FLAG_AERR: acknowledge error + \arg I2C_FLAG_LOSTARB: arbitration lost in master mode + \arg I2C_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus + \arg I2C_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode + \arg I2C_FLAG_TFF: txframe fall flag + \arg I2C_FLAG_TFR: txframe rise flag + \arg I2C_FLAG_RFF: rxframe fall flag + \arg I2C_FLAG_RFR: rxframe rise flag + \param[out] none + \retval none +*/ +void i2c_flag_clear(uint32_t i2c_periph, i2c_flag_enum flag) +{ + if(I2C_FLAG_ADDSEND == flag) { + /* read I2C_STAT0 and then read I2C_STAT1 to clear ADDSEND */ + I2C_STAT0(i2c_periph); + I2C_STAT1(i2c_periph); + } else { + I2C_REG_VAL(i2c_periph, flag) &= ~BIT(I2C_BIT_POS(flag)); + } +} + +/*! + \brief enable I2C interrupt + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] interrupt: I2C interrupts, refer to i2c_interrupt_enum + only one parameter can be selected which is shown as below: + \arg I2C_INT_ERR: error interrupt + \arg I2C_INT_EV: event interrupt + \arg I2C_INT_BUF: buffer interrupt + \arg I2C_INT_TFF: txframe fall interrupt + \arg I2C_INT_TFR: txframe rise interrupt + \arg I2C_INT_RFF: rxframe fall interrupt + \arg I2C_INT_RFR: rxframe rise interrupt + \param[out] none + \retval none +*/ +void i2c_interrupt_enable(uint32_t i2c_periph, i2c_interrupt_enum interrupt) +{ + I2C_REG_VAL(i2c_periph, interrupt) |= BIT(I2C_BIT_POS(interrupt)); +} + +/*! + \brief disable I2C interrupt + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] interrupt: I2C interrupts, refer to i2c_interrupt_enum + only one parameter can be selected which is shown as below: + \arg I2C_INT_ERR: error interrupt + \arg I2C_INT_EV: event interrupt + \arg I2C_INT_BUF: buffer interrupt + \arg I2C_INT_TFF: txframe fall interrupt + \arg I2C_INT_TFR: txframe rise interrupt + \arg I2C_INT_RFF: rxframe fall interrupt + \arg I2C_INT_RFR: rxframe rise interrupt + \param[out] none + \retval none +*/ +void i2c_interrupt_disable(uint32_t i2c_periph, i2c_interrupt_enum interrupt) +{ + I2C_REG_VAL(i2c_periph, interrupt) &= ~BIT(I2C_BIT_POS(interrupt)); +} + +/*! + \brief get I2C interrupt flag status + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] int_flag: I2C interrupt flags, refer to i2c_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg I2C_INT_FLAG_SBSEND: start condition sent out in master mode interrupt flag + \arg I2C_INT_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode interrupt flag + \arg I2C_INT_FLAG_BTC: byte transmission finishes interrupt flag + \arg I2C_INT_FLAG_ADD10SEND: header of 10-bit address is sent in master mode interrupt flag + \arg I2C_INT_FLAG_STPDET: stop condition detected in slave mode interrupt flag + \arg I2C_INT_FLAG_RBNE: I2C_DATA is not Empty during receiving interrupt flag + \arg I2C_INT_FLAG_TBE: I2C_DATA is empty during transmitting interrupt flag + \arg I2C_INT_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag + \arg I2C_INT_FLAG_LOSTARB: arbitration lost in master mode interrupt flag + \arg I2C_INT_FLAG_AERR: acknowledge error interrupt flag + \arg I2C_INT_FLAG_OUERR: over-run or under-run situation occurs in slave mode interrupt flag + \arg I2C_INT_FLAG_PECERR: PEC error when receiving data interrupt flag + \arg I2C_INT_FLAG_SMBTO: timeout signal in SMBus mode interrupt flag + \arg I2C_INT_FLAG_SMBALT: SMBus alert status interrupt flag + \arg I2C_INT_FLAG_TFF: txframe fall interrupt flag + \arg I2C_INT_FLAG_TFR: txframe rise interrupt flag + \arg I2C_INT_FLAG_RFF: rxframe fall interrupt flag + \arg I2C_INT_FLAG_RFR: rxframe rise interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus i2c_interrupt_flag_get(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag) +{ + uint32_t intenable = 0U, flagstatus = 0U, bufie; + + /* check BUFIE */ + bufie = I2C_CTL1(i2c_periph)&I2C_CTL1_BUFIE; + + /* get the interrupt enable bit status */ + intenable = (I2C_REG_VAL(i2c_periph, int_flag) & BIT(I2C_BIT_POS(int_flag))); + /* get the corresponding flag bit status */ + flagstatus = (I2C_REG_VAL2(i2c_periph, int_flag) & BIT(I2C_BIT_POS2(int_flag))); + + if((I2C_INT_FLAG_RBNE == int_flag) || (I2C_INT_FLAG_TBE == int_flag)) { + if(intenable && bufie) { + intenable = 1U; + } else { + intenable = 0U; + } + } + if((0U != flagstatus) && (0U != intenable)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear I2C interrupt flag status + \param[in] i2c_periph: I2Cx(x=0,1,2) + \param[in] int_flag: I2C interrupt flags, refer to i2c_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg I2C_INT_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode interrupt flag + \arg I2C_INT_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag + \arg I2C_INT_FLAG_LOSTARB: arbitration lost in master mode interrupt flag + \arg I2C_INT_FLAG_AERR: acknowledge error interrupt flag + \arg I2C_INT_FLAG_OUERR: over-run or under-run situation occurs in slave mode interrupt flag + \arg I2C_INT_FLAG_PECERR: PEC error when receiving data interrupt flag + \arg I2C_INT_FLAG_SMBTO: timeout signal in SMBus mode interrupt flag + \arg I2C_INT_FLAG_SMBALT: SMBus alert status interrupt flag + \arg I2C_INT_FLAG_TFF: txframe fall interrupt flag + \arg I2C_INT_FLAG_TFR: txframe rise interrupt flag + \arg I2C_INT_FLAG_RFF: rxframe fall interrupt flag + \arg I2C_INT_FLAG_RFR: rxframe rise interrupt flag + \param[out] none + \retval none +*/ +void i2c_interrupt_flag_clear(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag) +{ + if(I2C_INT_FLAG_ADDSEND == int_flag) { + /* read I2C_STAT0 and then read I2C_STAT1 to clear ADDSEND */ + I2C_STAT0(i2c_periph); + I2C_STAT1(i2c_periph); + } else { + I2C_REG_VAL2(i2c_periph, int_flag) &= ~BIT(I2C_BIT_POS2(int_flag)); + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_i2c_add.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_i2c_add.c new file mode 100644 index 0000000..656e7e7 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_i2c_add.c @@ -0,0 +1,978 @@ +/*! + \file gd32f5xx_i2c.c + \brief I2C driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_i2c_add.h" + +/* I2C register bit mask */ +#define I2C_ADD_ADDRESS_MASK ((uint32_t)0x000003FFU) /*!< i2c address mask */ +#define I2C_ADD_ADDRESS2_MASK ((uint32_t)0x000000FEU) /*!< the second i2c address mask */ + +/* I2C register bit offset */ +#define CTL0_DNF_OFFSET ((uint32_t)0x00000008U) /*!< bit offset of DNF in I2C_ADD_CTL0 */ +#define CTL1_BYTENUM_OFFSET ((uint32_t)0x00000010U) /*!< bit offset of BYTENUM in I2C_ADD_CTL1 */ +#define STAT_READDR_OFFSET ((uint32_t)0x00000011U) /*!< bit offset of READDR in I2C_ADD_STAT */ +#define TIMING_SCLL_OFFSET ((uint32_t)0x00000000U) /*!< bit offset of SCLL in I2C_ADD_TIMING */ +#define TIMING_SCLH_OFFSET ((uint32_t)0x00000008U) /*!< bit offset of SCLH in I2C_ADD_TIMING */ +#define TIMING_SDADELY_OFFSET ((uint32_t)0x00000010U) /*!< bit offset of SDADELY in I2C_ADD_TIMING */ +#define TIMING_SCLDELY_OFFSET ((uint32_t)0x00000014U) /*!< bit offset of SCLDELY in I2C_ADD_TIMING */ +#define TIMING_PSC_OFFSET ((uint32_t)0x0000001CU) /*!< bit offset of PSC in I2C_ADD_TIMING */ +#define SADDR1_ADDMSK_OFFSET ((uint32_t)0x00000008U) /*!< bit offset of ADDMSK in I2C_ADD_SADDR1 */ +#define TIMEOUT_BUSTOB_OFFSET ((uint32_t)0x00000010U) /*!< bit offset of BUSTOB in I2C_ADD_TIMEOUT */ + +/*! + \brief reset I2C + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_deinit(uint32_t i2c_add_periph) +{ + switch(i2c_add_periph) { + /* reset I2C3 */ + case I2C3: + rcu_periph_reset_enable(RCU_I2C3RST); + rcu_periph_reset_disable(RCU_I2C3RST); + break; + /* reset I2C4 */ + case I2C4: + rcu_periph_reset_enable(RCU_I2C4RST); + rcu_periph_reset_disable(RCU_I2C4RST); + break; + /* reset I2C5 */ + case I2C5: + rcu_periph_reset_enable(RCU_I2C5RST); + rcu_periph_reset_disable(RCU_I2C5RST); + break; + default: + break; + } +} + +/*! + \brief configure the timing parameters + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] psc: 0-0x0000000F, timing prescaler + \param[in] scl_dely: 0-0x0000000F, data setup time + \param[in] sda_dely: 0-0x0000000F, data hold time + \param[out] none + \retval none +*/ +void i2c_add_timing_config(uint32_t i2c_add_periph, uint32_t psc, uint32_t scl_dely, uint32_t sda_dely) +{ + /* clear PSC, SCLDELY, SDADELY bits in I2C_ADD_TIMING register */ + I2C_ADD_TIMING(i2c_add_periph) &= ~I2C_ADD_TIMING_PSC; + I2C_ADD_TIMING(i2c_add_periph) &= ~I2C_ADD_TIMING_SCLDELY; + I2C_ADD_TIMING(i2c_add_periph) &= ~I2C_ADD_TIMING_SDADELY; + /* mask PSC, SCLDELY, SDADELY bits in I2C_ADD_TIMING register */ + psc = (uint32_t)(psc << TIMING_PSC_OFFSET) & I2C_ADD_TIMING_PSC; + scl_dely = (uint32_t)(scl_dely << TIMING_SCLDELY_OFFSET) & I2C_ADD_TIMING_SCLDELY; + sda_dely = (uint32_t)(sda_dely << TIMING_SDADELY_OFFSET) & I2C_ADD_TIMING_SDADELY; + /* write PSC, SCLDELY, SDADELY bits in I2C_ADD_TIMING register */ + I2C_ADD_TIMING(i2c_add_periph) |= (psc | scl_dely | sda_dely); +} + +/*! + \brief configure digital noise filter + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] filter_length: the length of filter spikes + only one parameter can be selected which is shown as below: + \arg FILTER_DISABLE: digital filter is disabled + \arg FILTER_LENGTH_1: digital filter is enabled and filter spikes with a length of up to 1 tI2CCLK + \arg FILTER_LENGTH_2: digital filter is enabled and filter spikes with a length of up to 2 tI2CCLK + \arg FILTER_LENGTH_3: digital filter is enabled and filter spikes with a length of up to 3 tI2CCLK + \arg FILTER_LENGTH_4: digital filter is enabled and filter spikes with a length of up to 4 tI2CCLK + \arg FILTER_LENGTH_5: digital filter is enabled and filter spikes with a length of up to 5 tI2CCLK + \arg FILTER_LENGTH_6: digital filter is enabled and filter spikes with a length of up to 6 tI2CCLK + \arg FILTER_LENGTH_7: digital filter is enabled and filter spikes with a length of up to 7 tI2CCLK + \arg FILTER_LENGTH_8: digital filter is enabled and filter spikes with a length of up to 8 tI2CCLK + \arg FILTER_LENGTH_9: digital filter is enabled and filter spikes with a length of up to 9 tI2CCLK + \arg FILTER_LENGTH_10: digital filter is enabled and filter spikes with a length of up to 10 tI2CCLK + \arg FILTER_LENGTH_11: digital filter is enabled and filter spikes with a length of up to 11 tI2CCLK + \arg FILTER_LENGTH_12: digital filter is enabled and filter spikes with a length of up to 12 tI2CCLK + \arg FILTER_LENGTH_13: digital filter is enabled and filter spikes with a length of up to 13 tI2CCLK + \arg FILTER_LENGTH_14: digital filter is enabled and filter spikes with a length of up to 14 tI2CCLK + \arg FILTER_LENGTH_15: digital filter is enabled and filter spikes with a length of up to 15 tI2CCLK + \param[out] none + \retval none +*/ +void i2c_add_digital_noise_filter_config(uint32_t i2c_add_periph, uint32_t filter_length) +{ + I2C_ADD_CTL0(i2c_add_periph) &= (uint32_t)(~I2C_ADD_CTL0_DNF); + I2C_ADD_CTL0(i2c_add_periph) |= (uint32_t)(filter_length << CTL0_DNF_OFFSET); +} + +/*! + \brief enable analog noise filter + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_analog_noise_filter_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_ANOFF; +} + +/*! + \brief disable analog noise filter + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_analog_noise_filter_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_ANOFF; +} + +/*! + \brief configure the SCL high and low period of clock in master mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] sclh: 0-0x000000FF, SCL high period + \param[in] scll: 0-0x000000FF, SCL low period + \param[out] none + \retval none +*/ +void i2c_add_master_clock_config(uint32_t i2c_add_periph, uint32_t sclh, uint32_t scll) +{ + /* clear SCLH, SCLL bits in I2C_ADD_TIMING register */ + I2C_ADD_TIMING(i2c_add_periph) &= ~I2C_ADD_TIMING_SCLH; + I2C_ADD_TIMING(i2c_add_periph) &= ~I2C_ADD_TIMING_SCLL; + /* mask SCLH, SCLL bits in I2C_ADD_TIMING register */ + sclh = (uint32_t)(sclh << TIMING_SCLH_OFFSET) & I2C_ADD_TIMING_SCLH; + scll = (uint32_t)(scll << TIMING_SCLL_OFFSET) & I2C_ADD_TIMING_SCLL; + /* write SCLH, SCLL bits in I2C_ADD_TIMING register */ + I2C_ADD_TIMING(i2c_add_periph) |= (sclh | scll); +} + +/*! + \brief configure i2c slave address and transfer direction in master mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] address: 0-0x3FF except reserved address, I2C slave address to be sent + \param[in] trans_direction: I2C transfer direction in master mode + only one parameter can be selected which is shown as below: + \arg I2C_ADD_MASTER_TRANSMIT: master transmit + \arg I2C_ADD_MASTER_RECEIVE: master receive + \param[out] none + \retval none +*/ +void i2c_add_master_addressing(uint32_t i2c_add_periph, uint32_t address, uint32_t trans_direction) +{ + /* configure slave address */ + I2C_ADD_CTL1(i2c_add_periph) &= ~I2C_ADD_CTL1_SADDRESS; + I2C_ADD_CTL1(i2c_add_periph) |= address; + /* configure transfer direction */ + I2C_ADD_CTL1(i2c_add_periph) &= ~I2C_ADD_CTL1_TRDIR; + I2C_ADD_CTL1(i2c_add_periph) |= trans_direction; +} + +/*! + \brief 10-bit address header executes read direction only in master receive mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_address10_header_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) |= I2C_ADD_CTL1_HEAD10R; +} + +/*! + \brief 10-bit address header executes complete sequence in master receive mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_address10_header_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) &= ~I2C_ADD_CTL1_HEAD10R; +} + +/*! + \brief enable 10-bit addressing mode in master mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_address10_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) |= I2C_ADD_CTL1_ADD10EN; +} + +/*! + \brief disable 10-bit addressing mode in master mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_address10_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) &= ~I2C_ADD_CTL1_ADD10EN; +} + +/*! + \brief enable I2C automatic end mode in master mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_automatic_end_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) |= I2C_ADD_CTL1_AUTOEND; +} + +/*! + \brief disable I2C automatic end mode in master mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_automatic_end_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) &= ~I2C_ADD_CTL1_AUTOEND; +} + +/*! + \brief enable the response to a general call + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_slave_response_to_gcall_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_GCEN; +} + +/*! + \brief disable the response to a general call + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_slave_response_to_gcall_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_GCEN; +} + +/*! + \brief enable to stretch SCL low when data is not ready in slave mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_stretch_scl_low_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_SS; +} + +/*! + \brief disable to stretch SCL low when data is not ready in slave mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_stretch_scl_low_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_SS; +} + +/*! + \brief configure i2c slave address + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] address: I2C address + \param[in] addr_format: 7bits or 10bits + only one parameter can be selected which is shown as below: + \arg I2C_ADD_ADDFORMAT_7BITS: 7bits + \arg I2C_ADD_ADDFORMAT_10BITS: 10bits + \param[out] none + \retval none +*/ +void i2c_add_address_config(uint32_t i2c_add_periph, uint32_t address, uint32_t addr_format) +{ + /* configure ADDRESS[7:1] and address format */ + address = address & I2C_ADD_ADDRESS_MASK; + I2C_ADD_SADDR0(i2c_add_periph) = (addr_format | address); + /* enable i2c address in slave mode */ + I2C_ADD_SADDR0(i2c_add_periph) |= I2C_ADD_SADDR0_ADDRESSEN; +} + +/*! + \brief define which bits of ADDRESS[7:1] need to compare with the incoming address byte + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] compare_bits: the bits need to compare + one or more parameters can be selected which are shown as below: + \arg ADDRESS_BIT1_COMPARE: address bit1 needs compare + \arg ADDRESS_BIT2_COMPARE: address bit2 needs compare + \arg ADDRESS_BIT3_COMPARE: address bit3 needs compare + \arg ADDRESS_BIT4_COMPARE: address bit4 needs compare + \arg ADDRESS_BIT5_COMPARE: address bit5 needs compare + \arg ADDRESS_BIT6_COMPARE: address bit6 needs compare + \arg ADDRESS_BIT7_COMPARE: address bit7 needs compare + \param[out] none + \retval none +*/ +void i2c_add_address_bit_compare_config(uint32_t i2c_add_periph, uint32_t compare_bits) +{ + I2C_ADD_CTL2(i2c_add_periph) &= ~I2C_ADD_CTL2_ADDM; + I2C_ADD_CTL2(i2c_add_periph) |= compare_bits; +} + +/*! + \brief disable i2c address in slave mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_address_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_SADDR0(i2c_add_periph) &= ~I2C_ADD_SADDR0_ADDRESSEN; +} + +/*! + \brief configure i2c second slave address + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] address: I2C address + \param[in] addr_mask: the bits not need to compare + one or more parameters can be selected which are shown as below: + \arg ADDRESS2_NO_MASK: no mask, all the bits must be compared + \arg ADDRESS2_MASK_BIT1: ADDRESS2[1] is masked, only ADDRESS2[7:2] are compared + \arg ADDRESS2_MASK_BIT1_2: ADDRESS2[2:1] is masked, only ADDRESS2[7:3] are compared + \arg ADDRESS2_MASK_BIT1_3: ADDRESS2[3:1] is masked, only ADDRESS2[7:4] are compared + \arg ADDRESS2_MASK_BIT1_4: ADDRESS2[4:1] is masked, only ADDRESS2[7:5] are compared + \arg ADDRESS2_MASK_BIT1_5: ADDRESS2[5:1] is masked, only ADDRESS2[7:6] are compared + \arg ADDRESS2_MASK_BIT1_6: ADDRESS2[6:1] is masked, only ADDRESS2[7] are compared + \arg ADDRESS2_MASK_ALL: all the ADDRESS2[7:1] bits are masked + \param[out] none + \retval none +*/ +void i2c_add_second_address_config(uint32_t i2c_add_periph, uint32_t address, uint32_t addr_mask) +{ + /* configure ADDRESS2[7:1] */ + address = address & I2C_ADD_ADDRESS2_MASK; + I2C_ADD_SADDR1(i2c_add_periph) |= address; + /* configure ADDRESS2[7:1] mask */ + I2C_ADD_SADDR1(i2c_add_periph) &= ~I2C_ADD_SADDR1_ADDMSK2; + I2C_ADD_SADDR1(i2c_add_periph) |= (uint32_t)(addr_mask << SADDR1_ADDMSK_OFFSET); + /* enable i2c second address in slave mode */ + I2C_ADD_SADDR1(i2c_add_periph) |= I2C_ADD_SADDR1_ADDRESS2EN; +} + +/*! + \brief disable i2c second address in slave mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_second_address_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_SADDR1(i2c_add_periph) &= ~I2C_ADD_SADDR1_ADDRESS2EN; +} + +/*! + \brief get received match address in slave mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval received match address +*/ +uint32_t i2c_add_recevied_address_get(uint32_t i2c_add_periph) +{ + return (uint32_t)((I2C_ADD_STAT(i2c_add_periph) & I2C_ADD_STAT_READDR) >> STAT_READDR_OFFSET); +} + +/*! + \brief enable slave byte control + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_slave_byte_control_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_SBCTL; +} + +/*! + \brief disable slave byte control + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_slave_byte_control_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_SBCTL; +} + +/*! + \brief generate a NACK in slave mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_nack_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) |= I2C_ADD_CTL1_NACKEN; +} + +/*! + \brief generate an ACK in slave mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_nack_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) &= ~I2C_ADD_CTL1_NACKEN; +} + +/*! + \brief enable wakeup from deep-sleep mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_wakeup_from_deepsleep_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_WUEN; +} + +/*! + \brief disable wakeup from deep-sleep mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_wakeup_from_deepsleep_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_WUEN; +} + +/*! + \brief enable I2C + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_I2CEN; +} + +/*! + \brief disable I2C + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_I2CEN; +} + +/*! + \brief generate a START condition on I2C bus + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_start_on_bus(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) |= I2C_ADD_CTL1_START; +} + +/*! + \brief generate a STOP condition on I2C bus + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_stop_on_bus(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) |= I2C_ADD_CTL1_STOP; +} + +/*! + \brief I2C transmit data + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] data: data to be transmitted + \param[out] none + \retval none +*/ +void i2c_add_data_transmit(uint32_t i2c_add_periph, uint32_t data) +{ + I2C_ADD_TDATA(i2c_add_periph) = (I2C_ADD_TDATA_TDATA & data); +} + +/*! + \brief I2C receive data + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval received data +*/ +uint32_t i2c_add_data_receive(uint32_t i2c_add_periph) +{ + return (I2C_ADD_RDATA(i2c_add_periph) & I2C_ADD_RDATA_RDATA); +} + +/*! + \brief enable I2C reload mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_reload_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) |= I2C_ADD_CTL1_RELOAD; +} + +/*! + \brief disable I2C reload mode + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_reload_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) &= ~I2C_ADD_CTL1_RELOAD; +} + +/*! + \brief configure number of bytes to be transferred + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] byte_number: 0x0-0xFF, number of bytes to be transferred + \param[out] none + \retval none +*/ +void i2c_add_transfer_byte_number_config(uint32_t i2c_add_periph, uint32_t byte_number) +{ + I2C_ADD_CTL1(i2c_add_periph) &= (uint32_t)(~I2C_ADD_CTL1_BYTENUM); + I2C_ADD_CTL1(i2c_add_periph) |= (uint32_t)(byte_number << CTL1_BYTENUM_OFFSET); +} + +/*! + \brief enable I2C DMA for transmission or reception + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] dma: I2C DMA + only one parameter can be selected which is shown as below: + \arg I2C_ADD_DMA_TRANSMIT: transmit data using DMA + \arg I2C_ADD_DMA_RECEIVE: receive data using DMA + \param[out] none + \retval none +*/ +void i2c_add_dma_enable(uint32_t i2c_add_periph, uint8_t dma) +{ + if(I2C_ADD_DMA_TRANSMIT == dma) { + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_DENT; + } else { + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_DENR; + } +} + +/*! + \brief disable I2C DMA for transmission or reception + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] dma: I2C DMA + only one parameter can be selected which is shown as below: + \arg I2C_ADD_DMA_TRANSMIT: transmit data using DMA + \arg I2C_ADD_DMA_RECEIVE: receive data using DMA + \param[out] none + \retval none +*/ +void i2c_add_dma_disable(uint32_t i2c_add_periph, uint8_t dma) +{ + if(I2C_ADD_DMA_TRANSMIT == dma) { + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_DENT; + } else { + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_DENR; + } +} + +/*! + \brief I2C transfers PEC value + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_pec_transfer(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL1(i2c_add_periph) |= I2C_ADD_CTL1_PECTRANS; +} + +/*! + \brief enable I2C PEC calculation + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_pec_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_PECEN; +} + +/*! + \brief disable I2C PEC calculation + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_pec_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_PECEN; +} + +/*! + \brief get packet error checking value + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval PEC value +*/ +uint32_t i2c_add_pec_value_get(uint32_t i2c_add_periph) +{ + return (I2C_ADD_PEC(i2c_add_periph) & I2C_ADD_PEC_PECV); +} + +/*! + \brief enable SMBus alert + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_smbus_alert_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_SMBALTEN; +} + +/*! + \brief disable SMBus alert + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_smbus_alert_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_SMBALTEN; +} + +/*! + \brief enable SMBus device default address + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_smbus_default_addr_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_SMBDAEN; +} + +/*! + \brief disable SMBus device default address + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_smbus_default_addr_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_SMBDAEN; +} + +/*! + \brief enable SMBus Host address + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_smbus_host_addr_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) |= I2C_ADD_CTL0_SMBHAEN; +} + +/*! + \brief disable SMBus Host address + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] none + \param[out] none + \retval none +*/ +void i2c_add_smbus_host_addr_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~I2C_ADD_CTL0_SMBHAEN; +} + +/*! + \brief enable extended clock timeout detection + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_extented_clock_timeout_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_TIMEOUT(i2c_add_periph) |= I2C_ADD_TIMEOUT_EXTOEN; +} + +/*! + \brief disable extended clock timeout detection + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_extented_clock_timeout_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_TIMEOUT(i2c_add_periph) &= ~I2C_ADD_TIMEOUT_EXTOEN; +} + +/*! + \brief enable clock timeout detection + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_clock_timeout_enable(uint32_t i2c_add_periph) +{ + I2C_ADD_TIMEOUT(i2c_add_periph) |= I2C_ADD_TIMEOUT_TOEN; +} + +/*! + \brief disable clock timeout detection + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[out] none + \retval none +*/ +void i2c_add_clock_timeout_disable(uint32_t i2c_add_periph) +{ + I2C_ADD_TIMEOUT(i2c_add_periph) &= ~I2C_ADD_TIMEOUT_TOEN; +} + +/*! + \brief configure bus timeout B + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] timeout: bus timeout B + \param[out] none + \retval none +*/ +void i2c_add_bus_timeout_b_config(uint32_t i2c_add_periph, uint32_t timeout) +{ + I2C_ADD_TIMEOUT(i2c_add_periph) &= ~I2C_ADD_TIMEOUT_BUSTOB; + I2C_ADD_TIMEOUT(i2c_add_periph) |= (uint32_t)(timeout << TIMEOUT_BUSTOB_OFFSET); +} + +/*! + \brief configure bus timeout A + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] timeout: bus timeout A + \param[out] none + \retval none +*/ +void i2c_add_bus_timeout_a_config(uint32_t i2c_add_periph, uint32_t timeout) +{ + I2C_ADD_TIMEOUT(i2c_add_periph) &= ~I2C_ADD_TIMEOUT_BUSTOA; + I2C_ADD_TIMEOUT(i2c_add_periph) |= timeout; +} + +/*! + \brief configure idle clock timeout detection + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] timeout: bus timeout A + \arg BUSTOA_DETECT_SCL_LOW: BUSTOA is used to detect SCL low timeout + \arg BUSTOA_DETECT_IDLE: BUSTOA is used to detect both SCL and SDA high timeout when the bus is idle + \param[out] none + \retval none +*/ +void i2c_add_idle_clock_timeout_config(uint32_t i2c_add_periph, uint32_t timeout) +{ + I2C_ADD_TIMEOUT(i2c_add_periph) &= ~I2C_ADD_TIMEOUT_TOIDLE; + I2C_ADD_TIMEOUT(i2c_add_periph) |= timeout; +} + +/*! + \brief get I2C flag status + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] flag: I2C flags + only one parameter can be selected which is shown as below: + \arg I2C_ADD_FLAG_TBE: I2C_ADD_TDATA is empty during transmitting + \arg I2C_ADD_FLAG_TI: transmit interrupt + \arg I2C_ADD_FLAG_RBNE: I2C_ADD_RDATA is not empty during receiving + \arg I2C_ADD_FLAG_ADDSEND: address received matches in slave mode + \arg I2C_ADD_FLAG_NACK: not acknowledge flag + \arg I2C_ADD_FLAG_STPDET: STOP condition detected in slave mode + \arg I2C_ADD_FLAG_TC: transfer complete in master mode + \arg I2C_ADD_FLAG_TCR: transfer complete reload + \arg I2C_ADD_FLAG_BERR: bus error + \arg I2C_ADD_FLAG_LOSTARB: arbitration Lost + \arg I2C_ADD_FLAG_OUERR: overrun/underrun error in slave mode + \arg I2C_ADD_FLAG_PECERR: PEC error + \arg I2C_ADD_FLAG_TIMEOUT: timeout flag + \arg I2C_ADD_FLAG_SMBALT: SMBus Alert + \arg I2C_ADD_FLAG_I2CBSY: busy flag + \arg I2C_ADD_FLAG_TR: whether the I2C is a transmitter or a receiver in slave mode + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus i2c_add_flag_get(uint32_t i2c_add_periph, uint32_t flag) +{ + if(RESET != (I2C_ADD_STAT(i2c_add_periph) & flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear I2C flag status + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] flag: I2C flags + one or more parameters can be selected which are shown as below: + \arg I2C_ADD_FLAG_ADDSEND: address received matches in slave mode + \arg I2C_ADD_FLAG_NACK: not acknowledge flag + \arg I2C_ADD_FLAG_STPDET: STOP condition detected in slave mode + \arg I2C_ADD_FLAG_BERR: bus error + \arg I2C_ADD_FLAG_LOSTARB: arbitration Lost + \arg I2C_ADD_FLAG_OUERR: overrun/underrun error in slave mode + \arg I2C_ADD_FLAG_PECERR: PEC error + \arg I2C_ADD_FLAG_TIMEOUT: timeout flag + \arg I2C_ADD_FLAG_SMBALT: SMBus Alert + \param[out] none + \retval none +*/ +void i2c_add_flag_clear(uint32_t i2c_add_periph, uint32_t flag) +{ + I2C_ADD_STATC(i2c_add_periph) |= flag; +} + +/*! + \brief enable I2C interrupt + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] interrupt: I2C interrupts + one or more parameters can be selected which are shown as below: + \arg I2C_ADD_INT_ERR: error interrupt + \arg I2C_ADD_INT_TC: transfer complete interrupt + \arg I2C_ADD_INT_STPDET: stop detection interrupt + \arg I2C_ADD_INT_NACK: not acknowledge received interrupt + \arg I2C_ADD_INT_ADDM: address match interrupt + \arg I2C_ADD_INT_RBNE: receive interrupt + \arg I2C_ADD_INT_TI: transmit interrupt + \param[out] none + \retval none +*/ +void i2c_add_interrupt_enable(uint32_t i2c_add_periph, uint32_t interrupt) +{ + I2C_ADD_CTL0(i2c_add_periph) |= interrupt; +} + +/*! + \brief disable I2C interrupt + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] interrupt: I2C interrupts + one or more parameters can be selected which are shown as below: + \arg I2C_ADD_INT_ERR: error interrupt + \arg I2C_ADD_INT_TC: transfer complete interrupt + \arg I2C_ADD_INT_STPDET: stop detection interrupt + \arg I2C_ADD_INT_NACK: not acknowledge received interrupt + \arg I2C_ADD_INT_ADDM: address match interrupt + \arg I2C_ADD_INT_RBNE: receive interrupt + \arg I2C_ADD_INT_TI: transmit interrupt + \param[out] none + \retval none +*/ +void i2c_add_interrupt_disable(uint32_t i2c_add_periph, uint32_t interrupt) +{ + I2C_ADD_CTL0(i2c_add_periph) &= ~interrupt; +} + +/*! + \brief get I2C interrupt flag status + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] int_flag: I2C interrupt flags, refer to i2c_add_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg I2C_ADD_INT_FLAG_TI: transmit interrupt flag + \arg I2C_ADD_INT_FLAG_RBNE: I2C_ADD_RDATA is not empty during receiving interrupt flag + \arg I2C_ADD_INT_FLAG_ADDSEND: address received matches in slave mode interrupt flag + \arg I2C_ADD_INT_FLAG_NACK: not acknowledge interrupt flag + \arg I2C_ADD_INT_FLAG_STPDET: stop condition detected in slave mode interrupt flag + \arg I2C_ADD_INT_FLAG_TC: transfer complete in master mode interrupt flag + \arg I2C_ADD_INT_FLAG_TCR: transfer complete reload interrupt flag + \arg I2C_ADD_INT_FLAG_BERR: bus error interrupt flag + \arg I2C_ADD_INT_FLAG_LOSTARB: arbitration lost interrupt flag + \arg I2C_ADD_INT_FLAG_OUERR: overrun/underrun error in slave mode interrupt flag + \arg I2C_ADD_INT_FLAG_PECERR: PEC error interrupt flag + \arg I2C_ADD_INT_FLAG_TIMEOUT: timeout interrupt flag + \arg I2C_ADD_INT_FLAG_SMBALT: SMBus Alert interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus i2c_add_interrupt_flag_get(uint32_t i2c_add_periph, i2c_add_interrupt_flag_enum int_flag) +{ + uint32_t ret1 = RESET; + uint32_t ret2 = RESET; + + /* get the status of interrupt enable bit */ + ret1 = (I2C_ADD_REG_VAL(i2c_add_periph, int_flag) & BIT(I2C_ADD_BIT_POS(int_flag))); + /* get the status of interrupt flag */ + ret2 = (I2C_ADD_REG_VAL2(i2c_add_periph, int_flag) & BIT(I2C_ADD_BIT_POS2(int_flag))); + if(ret1 && ret2) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear I2C interrupt flag status + \param[in] i2c_add_periph: I2Cx(x=3,4,5) + \param[in] int_flag: I2C interrupt flags, refer to i2c_add_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg I2C_ADD_INT_FLAG_ADDSEND: address received matches in slave mode interrupt flag + \arg I2C_ADD_INT_FLAG_NACK: not acknowledge interrupt flag + \arg I2C_ADD_INT_FLAG_STPDET: stop condition detected in slave mode interrupt flag + \arg I2C_ADD_INT_FLAG_BERR: bus error interrupt flag + \arg I2C_ADD_INT_FLAG_LOSTARB: arbitration lost interrupt flag + \arg I2C_ADD_INT_FLAG_OUERR: overrun/underrun error in slave mode interrupt flag + \arg I2C_ADD_INT_FLAG_PECERR: PEC error interrupt flag + \arg I2C_ADD_INT_FLAG_TIMEOUT: timeout interrupt flag + \arg I2C_ADD_INT_FLAG_SMBALT: SMBus Alert interrupt flag + \param[out] none + \retval none +*/ +void i2c_add_interrupt_flag_clear(uint32_t i2c_add_periph, i2c_add_interrupt_flag_enum int_flag) +{ + I2C_ADD_STATC(i2c_add_periph) |= BIT(I2C_ADD_BIT_POS2(int_flag)); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_ipa.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_ipa.c new file mode 100644 index 0000000..40c6e76 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_ipa.c @@ -0,0 +1,636 @@ +/*! + \file gd32f5xx_ipa.c + \brief IPA driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_ipa.h" + +#define IPA_DEFAULT_VALUE 0x00000000U + +/*! + \brief deinitialize IPA registers + \param[in] none + \param[out] none + \retval none +*/ +void ipa_deinit(void) +{ + rcu_periph_reset_enable(RCU_IPARST); + rcu_periph_reset_disable(RCU_IPARST); +} + +/*! + \brief enable IPA transfer + \param[in] none + \param[out] none + \retval none +*/ +void ipa_transfer_enable(void) +{ + IPA_CTL |= IPA_CTL_TEN; +} + +/*! + \brief enable IPA transfer hang up + \param[in] none + \param[out] none + \retval none +*/ +void ipa_transfer_hangup_enable(void) +{ + IPA_CTL |= IPA_CTL_THU; +} + +/*! + \brief disable IPA transfer hang up + \param[in] none + \param[out] none + \retval none +*/ +void ipa_transfer_hangup_disable(void) +{ + IPA_CTL &= ~(IPA_CTL_THU); +} + +/*! + \brief enable IPA transfer stop + \param[in] none + \param[out] none + \retval none +*/ +void ipa_transfer_stop_enable(void) +{ + IPA_CTL |= IPA_CTL_TST; +} + +/*! + \brief disable IPA transfer stop + \param[in] none + \param[out] none + \retval none +*/ +void ipa_transfer_stop_disable(void) +{ + IPA_CTL &= ~(IPA_CTL_TST); +} +/*! + \brief enable IPA foreground LUT loading + \param[in] none + \param[out] none + \retval none +*/ +void ipa_foreground_lut_loading_enable(void) +{ + IPA_FPCTL |= IPA_FPCTL_FLLEN; +} + +/*! + \brief enable IPA background LUT loading + \param[in] none + \param[out] none + \retval none +*/ +void ipa_background_lut_loading_enable(void) +{ + IPA_BPCTL |= IPA_BPCTL_BLLEN; +} + +/*! + \brief set pixel format convert mode, the function is invalid when the IPA transfer is enabled + \param[in] pfcm: pixel format convert mode + only one parameter can be selected which is shown as below: + \arg IPA_FGTODE: foreground memory to destination memory without pixel format convert + \arg IPA_FGTODE_PF_CONVERT: foreground memory to destination memory with pixel format convert + \arg IPA_FGBGTODE: blending foreground and background memory to destination memory + \arg IPA_FILL_UP_DE: fill up destination memory with specific color + \param[out] none + \retval none +*/ +void ipa_pixel_format_convert_mode_set(uint32_t pfcm) +{ + IPA_CTL &= ~(IPA_CTL_PFCM); + IPA_CTL |= pfcm; +} + +/*! + \brief initialize the structure of IPA foreground parameter struct with the default values, it is + suggested that call this function after an ipa_foreground_parameter_struct structure is defined + \param[in] none + \param[out] foreground_struct: the data needed to initialize foreground + foreground_memaddr: foreground memory base address + foreground_lineoff: foreground line offset + foreground_prealpha: foreground pre-defined alpha value + foreground_alpha_algorithm: IPA_FG_ALPHA_MODE_0,IPA_FG_ALPHA_MODE_1,IPA_FG_ALPHA_MODE_2 + foreground_pf: foreground pixel format(FOREGROUND_PPF_ARGB8888,FOREGROUND_PPF_RGB888,FOREGROUND_PPF_RGB565, + FOREGROUND_PPF_ARG1555,FOREGROUND_PPF_ARGB4444,FOREGROUND_PPF_L8,FOREGROUND_PPF_AL44, + FOREGROUND_PPF_AL88,FOREGROUND_PPF_L4,FOREGROUND_PPF_A8,FOREGROUND_PPF_A4) + foreground_prered: foreground pre-defined red value + foreground_pregreen: foreground pre-defined green value + foreground_preblue: foreground pre-defined blue value + \retval none +*/ +void ipa_foreground_struct_para_init(ipa_foreground_parameter_struct *foreground_struct) +{ + /* initialize the struct parameters with default values */ + foreground_struct->foreground_memaddr = IPA_DEFAULT_VALUE; + foreground_struct->foreground_lineoff = IPA_DEFAULT_VALUE; + foreground_struct->foreground_prealpha = IPA_DEFAULT_VALUE; + foreground_struct->foreground_alpha_algorithm = IPA_FG_ALPHA_MODE_0; + foreground_struct->foreground_pf = FOREGROUND_PPF_ARGB8888; + foreground_struct->foreground_prered = IPA_DEFAULT_VALUE; + foreground_struct->foreground_pregreen = IPA_DEFAULT_VALUE; + foreground_struct->foreground_preblue = IPA_DEFAULT_VALUE; +} + +/*! + \brief initialize foreground parameters + \param[in] foreground_struct: the data needed to initialize foreground + foreground_memaddr: foreground memory base address + foreground_lineoff: foreground line offset + foreground_prealpha: foreground pre-defined alpha value + foreground_alpha_algorithm: IPA_FG_ALPHA_MODE_0,IPA_FG_ALPHA_MODE_1,IPA_FG_ALPHA_MODE_2 + foreground_pf: foreground pixel format(FOREGROUND_PPF_ARGB8888,FOREGROUND_PPF_RGB888,FOREGROUND_PPF_RGB565, + FOREGROUND_PPF_ARG1555,FOREGROUND_PPF_ARGB4444,FOREGROUND_PPF_L8,FOREGROUND_PPF_AL44, + FOREGROUND_PPF_AL88,FOREGROUND_PPF_L4,FOREGROUND_PPF_A8,FOREGROUND_PPF_A4) + foreground_prered: foreground pre-defined red value + foreground_pregreen: foreground pre-defined green value + foreground_preblue: foreground pre-defined blue value + \param[out] none + \retval none +*/ +void ipa_foreground_init(ipa_foreground_parameter_struct *foreground_struct) +{ + FlagStatus tempflag = RESET; + if(RESET != (IPA_CTL & IPA_CTL_TEN)) { + tempflag = SET; + /* reset the TEN in order to configure the following bits */ + IPA_CTL &= ~IPA_CTL_TEN; + } + + /* foreground memory base address configuration */ + IPA_FMADDR &= ~(IPA_FMADDR_FMADDR); + IPA_FMADDR = foreground_struct->foreground_memaddr; + /* foreground line offset configuration */ + IPA_FLOFF &= ~(IPA_FLOFF_FLOFF); + IPA_FLOFF = foreground_struct->foreground_lineoff; + /* foreground pixel format pre-defined alpha, alpha calculation algorithm configuration */ + IPA_FPCTL &= ~(IPA_FPCTL_FPDAV | IPA_FPCTL_FAVCA | IPA_FPCTL_FPF); + IPA_FPCTL |= (foreground_struct->foreground_prealpha << 24U); + IPA_FPCTL |= foreground_struct->foreground_alpha_algorithm; + IPA_FPCTL |= foreground_struct->foreground_pf; + /* foreground pre-defined red green blue configuration */ + IPA_FPV &= ~(IPA_FPV_FPDRV | IPA_FPV_FPDGV | IPA_FPV_FPDBV); + IPA_FPV |= ((foreground_struct->foreground_prered << 16U) | (foreground_struct->foreground_pregreen << 8U) + | (foreground_struct->foreground_preblue)); + + if(SET == tempflag) { + /* restore the state of TEN */ + IPA_CTL |= IPA_CTL_TEN; + } +} + +/*! + \brief initialize the structure of IPA background parameter struct with the default values, it is + suggested that call this function after an ipa_background_parameter_struct structure is defined + \param[in] none + \param[out] background_struct: the data needed to initialize background + background_memaddr: background memory base address + background_lineoff: background line offset + background_prealpha: background pre-defined alpha value + background_alpha_algorithm: IPA_BG_ALPHA_MODE_0,IPA_BG_ALPHA_MODE_1,IPA_BG_ALPHA_MODE_2 + background_pf: background pixel format(BACKGROUND_PPF_ARGB8888,BACKGROUND_PPF_RGB888,BACKGROUND_PPF_RGB565, + BACKGROUND_PPF_ARG1555,BACKGROUND_PPF_ARGB4444,BACKGROUND_PPF_L8,BACKGROUND_PPF_AL44, + BACKGROUND_PPF_AL88,BACKGROUND_PPF_L4,BACKGROUND_PPF_A8,BACKGROUND_PPF_A4) + background_prered: background pre-defined red value + background_pregreen: background pre-defined green value + background_preblue: background pre-defined blue value + \retval none +*/ +void ipa_background_struct_para_init(ipa_background_parameter_struct *background_struct) +{ + /* initialize the struct parameters with default values */ + background_struct->background_memaddr = IPA_DEFAULT_VALUE; + background_struct->background_lineoff = IPA_DEFAULT_VALUE; + background_struct->background_prealpha = IPA_DEFAULT_VALUE; + background_struct->background_alpha_algorithm = IPA_BG_ALPHA_MODE_0; + background_struct->background_pf = BACKGROUND_PPF_ARGB8888; + background_struct->background_prered = IPA_DEFAULT_VALUE; + background_struct->background_pregreen = IPA_DEFAULT_VALUE; + background_struct->background_preblue = IPA_DEFAULT_VALUE; +} + +/*! + \brief initialize background parameters + \param[in] background_struct: the data needed to initialize background + background_memaddr: background memory base address + background_lineoff: background line offset + background_prealpha: background pre-defined alpha value + background_alpha_algorithm: IPA_BG_ALPHA_MODE_0,IPA_FG_ALPHA_MODE_1,IPA_FG_ALPHA_MODE_2 + background_pf: background pixel format(BACKGROUND_PPF_ARGB8888,BACKGROUND_PPF_RGB888,BACKGROUND_PPF_RGB565, + BACKGROUND_PPF_ARG1555,BACKGROUND_PPF_ARGB4444,BACKGROUND_PPF_L8,BACKGROUND_PPF_AL44, + BACKGROUND_PPF_AL88,BACKGROUND_PPF_L4,BACKGROUND_PPF_A8,BACKGROUND_PPF_A4) + background_prered: background pre-defined red value + background_pregreen: background pre-defined green value + background_preblue: background pre-defined blue value + \param[out] none + \retval none +*/ +void ipa_background_init(ipa_background_parameter_struct *background_struct) +{ + FlagStatus tempflag = RESET; + if(RESET != (IPA_CTL & IPA_CTL_TEN)) { + tempflag = SET; + /* reset the TEN in order to configure the following bits */ + IPA_CTL &= ~IPA_CTL_TEN; + } + + /* background memory base address configuration */ + IPA_BMADDR &= ~(IPA_BMADDR_BMADDR); + IPA_BMADDR = background_struct->background_memaddr; + /* background line offset configuration */ + IPA_BLOFF &= ~(IPA_BLOFF_BLOFF); + IPA_BLOFF = background_struct->background_lineoff; + /* background pixel format pre-defined alpha, alpha calculation algorithm configuration */ + IPA_BPCTL &= ~(IPA_BPCTL_BPDAV | IPA_BPCTL_BAVCA | IPA_BPCTL_BPF); + IPA_BPCTL |= (background_struct->background_prealpha << 24U); + IPA_BPCTL |= background_struct->background_alpha_algorithm; + IPA_BPCTL |= background_struct->background_pf; + /* background pre-defined red green blue configuration */ + IPA_BPV &= ~(IPA_BPV_BPDRV | IPA_BPV_BPDGV | IPA_BPV_BPDBV); + IPA_BPV |= ((background_struct->background_prered << 16U) | (background_struct->background_pregreen << 8U) + | (background_struct->background_preblue)); + + if(SET == tempflag) { + /* restore the state of TEN */ + IPA_CTL |= IPA_CTL_TEN; + } +} + +/*! + \brief initialize the structure of IPA destination parameter struct with the default values, it is + suggested that call this function after an ipa_destination_parameter_struct structure is defined + \param[in] none + \param[out] destination_struct: the data needed to initialize destination parameter + destination_pf: IPA_DPF_ARGB8888,IPA_DPF_RGB888,IPA_DPF_RGB565,IPA_DPF_ARGB1555, + IPA_DPF_ARGB4444,refer to ipa_dpf_enum + destination_lineoff: destination line offset + destination_prealpha: destination pre-defined alpha value + destination_prered: destination pre-defined red value + destination_pregreen: destination pre-defined green value + destination_preblue: destination pre-defined blue value + destination_memaddr: destination memory base address + image_width: width of the image to be processed + image_height: height of the image to be processed + \retval none +*/ +void ipa_destination_struct_para_init(ipa_destination_parameter_struct *destination_struct) +{ + /* initialize the struct parameters with default values */ + destination_struct->destination_pf = IPA_DPF_ARGB8888; + destination_struct->destination_lineoff = IPA_DEFAULT_VALUE; + destination_struct->destination_prealpha = IPA_DEFAULT_VALUE; + destination_struct->destination_prered = IPA_DEFAULT_VALUE; + destination_struct->destination_pregreen = IPA_DEFAULT_VALUE; + destination_struct->destination_preblue = IPA_DEFAULT_VALUE; + destination_struct->destination_memaddr = IPA_DEFAULT_VALUE; + destination_struct->image_width = IPA_DEFAULT_VALUE; + destination_struct->image_height = IPA_DEFAULT_VALUE; +} + +/*! + \brief initialize destination parameters + \param[in] destination_struct: the data needed to initialize destination parameters + destination_pf: IPA_DPF_ARGB8888,IPA_DPF_RGB888,IPA_DPF_RGB565,IPA_DPF_ARGB1555, + IPA_DPF_ARGB4444,refer to ipa_dpf_enum + destination_lineoff: destination line offset + destination_prealpha: destination pre-defined alpha value + destination_prered: destination pre-defined red value + destination_pregreen: destination pre-defined green value + destination_preblue: destination pre-defined blue value + destination_memaddr: destination memory base address + image_width: width of the image to be processed + image_height: height of the image to be processed + \param[out] none + \retval none +*/ +void ipa_destination_init(ipa_destination_parameter_struct *destination_struct) +{ + uint32_t destination_pixelformat; + FlagStatus tempflag = RESET; + if(RESET != (IPA_CTL & IPA_CTL_TEN)) { + tempflag = SET; + /* reset the TEN in order to configure the following bits */ + IPA_CTL &= ~IPA_CTL_TEN; + } + + /* destination pixel format configuration */ + IPA_DPCTL &= ~(IPA_DPCTL_DPF); + IPA_DPCTL = destination_struct->destination_pf; + destination_pixelformat = destination_struct->destination_pf; + /* destination pixel format ARGB8888 */ + switch(destination_pixelformat) { + case IPA_DPF_ARGB8888: + IPA_DPV &= ~(IPA_DPV_DPDBV_0 | (IPA_DPV_DPDGV_0) | (IPA_DPV_DPDRV_0) | (IPA_DPV_DPDAV_0)); + IPA_DPV = (destination_struct->destination_preblue | (destination_struct->destination_pregreen << 8U) + | (destination_struct->destination_prered << 16U) + | (destination_struct->destination_prealpha << 24U)); + break; + /* destination pixel format RGB888 */ + case IPA_DPF_RGB888: + IPA_DPV &= ~(IPA_DPV_DPDBV_1 | (IPA_DPV_DPDGV_1) | (IPA_DPV_DPDRV_1)); + IPA_DPV = (destination_struct->destination_preblue | (destination_struct->destination_pregreen << 8U) + | (destination_struct->destination_prered << 16U)); + break; + /* destination pixel format RGB565 */ + case IPA_DPF_RGB565: + IPA_DPV &= ~(IPA_DPV_DPDBV_2 | (IPA_DPV_DPDGV_2) | (IPA_DPV_DPDRV_2)); + IPA_DPV = (destination_struct->destination_preblue | (destination_struct->destination_pregreen << 5U) + | (destination_struct->destination_prered << 11U)); + break; + /* destination pixel format ARGB1555 */ + case IPA_DPF_ARGB1555: + IPA_DPV &= ~(IPA_DPV_DPDBV_3 | (IPA_DPV_DPDGV_3) | (IPA_DPV_DPDRV_3) | (IPA_DPV_DPDAV_3)); + IPA_DPV = (destination_struct->destination_preblue | (destination_struct->destination_pregreen << 5U) + | (destination_struct->destination_prered << 10U) + | (destination_struct->destination_prealpha << 15U)); + break; + /* destination pixel format ARGB4444 */ + case IPA_DPF_ARGB4444: + IPA_DPV &= ~(IPA_DPV_DPDBV_4 | (IPA_DPV_DPDGV_4) | (IPA_DPV_DPDRV_4) | (IPA_DPV_DPDAV_4)); + IPA_DPV = (destination_struct->destination_preblue | (destination_struct->destination_pregreen << 4U) + | (destination_struct->destination_prered << 8U) + | (destination_struct->destination_prealpha << 12U)); + break; + default: + break; + } + /* destination memory base address configuration */ + IPA_DMADDR &= ~(IPA_DMADDR_DMADDR); + IPA_DMADDR = destination_struct->destination_memaddr; + /* destination line offset configuration */ + IPA_DLOFF &= ~(IPA_DLOFF_DLOFF); + IPA_DLOFF = destination_struct->destination_lineoff; + /* image size configuration */ + IPA_IMS &= ~(IPA_IMS_HEIGHT | IPA_IMS_WIDTH); + IPA_IMS |= ((destination_struct->image_width << 16U) | (destination_struct->image_height)); + + if(SET == tempflag) { + /* restore the state of TEN */ + IPA_CTL |= IPA_CTL_TEN; + } +} + +/*! + \brief initialize IPA foreground LUT parameters + \param[in] fg_lut_num: foreground LUT number of pixel + \param[in] fg_lut_pf: foreground LUT pixel format(IPA_LUT_PF_ARGB8888, IPA_LUT_PF_RGB888) + \param[in] fg_lut_addr: foreground LUT memory base address + \param[out] none + \retval none +*/ +void ipa_foreground_lut_init(uint8_t fg_lut_num, uint8_t fg_lut_pf, uint32_t fg_lut_addr) +{ + FlagStatus tempflag = RESET; + if(RESET != (IPA_FPCTL & IPA_FPCTL_FLLEN)) { + tempflag = SET; + /* reset the FLLEN in order to configure the following bits */ + IPA_FPCTL &= ~IPA_FPCTL_FLLEN; + } + + /* foreground LUT number of pixel configuration */ + IPA_FPCTL |= ((uint32_t)fg_lut_num << 8U); + /* foreground LUT pixel format configuration */ + if(IPA_LUT_PF_RGB888 == fg_lut_pf) { + IPA_FPCTL |= IPA_FPCTL_FLPF; + } else { + IPA_FPCTL &= ~(IPA_FPCTL_FLPF); + } + /* foreground LUT memory base address configuration */ + IPA_FLMADDR &= ~(IPA_FLMADDR_FLMADDR); + IPA_FLMADDR = fg_lut_addr; + + if(SET == tempflag) { + /* restore the state of FLLEN */ + IPA_FPCTL |= IPA_FPCTL_FLLEN; + } +} + +/*! + \brief initialize IPA background LUT parameters + \param[in] bg_lut_num: background LUT number of pixel + \param[in] bg_lut_pf: background LUT pixel format(IPA_LUT_PF_ARGB8888, IPA_LUT_PF_RGB888) + \param[in] bg_lut_addr: background LUT memory base address + \param[out] none + \retval none +*/ +void ipa_background_lut_init(uint8_t bg_lut_num, uint8_t bg_lut_pf, uint32_t bg_lut_addr) +{ + FlagStatus tempflag = RESET; + if(RESET != (IPA_BPCTL & IPA_BPCTL_BLLEN)) { + tempflag = SET; + /* reset the BLLEN in order to configure the following bits */ + IPA_BPCTL &= ~IPA_BPCTL_BLLEN; + } + + /* background LUT number of pixel configuration */ + IPA_BPCTL |= ((uint32_t)bg_lut_num << 8U); + /* background LUT pixel format configuration */ + if(IPA_LUT_PF_RGB888 == bg_lut_pf) { + IPA_BPCTL |= IPA_BPCTL_BLPF; + } else { + IPA_BPCTL &= ~(IPA_BPCTL_BLPF); + } + /* background LUT memory base address configuration */ + IPA_BLMADDR &= ~(IPA_BLMADDR_BLMADDR); + IPA_BLMADDR = bg_lut_addr; + + if(SET == tempflag) { + /* restore the state of BLLEN */ + IPA_BPCTL |= IPA_BPCTL_BLLEN; + } +} + +/*! + \brief configure IPA line mark + \param[in] line_num: line number + \param[out] none + \retval none +*/ +void ipa_line_mark_config(uint16_t line_num) +{ + IPA_LM &= ~(IPA_LM_LM); + IPA_LM = line_num; +} + +/*! + \brief inter-timer enable or disable + \param[in] timer_cfg: IPA_INTER_TIMER_ENABLE,IPA_INTER_TIMER_DISABLE + \param[out] none + \retval none +*/ +void ipa_inter_timer_config(uint8_t timer_cfg) +{ + if(IPA_INTER_TIMER_ENABLE == timer_cfg) { + IPA_ITCTL |= IPA_ITCTL_ITEN; + } else { + IPA_ITCTL &= ~(IPA_ITCTL_ITEN); + } +} + +/*! + \brief configure the number of clock cycles interval + \param[in] clk_num: the number of clock cycles + \param[out] none + \retval none +*/ +void ipa_interval_clock_num_config(uint8_t clk_num) +{ + /* NCCI[7:0] bits have no meaning if ITEN is '0' */ + IPA_ITCTL &= ~(IPA_ITCTL_NCCI); + IPA_ITCTL |= ((uint32_t)clk_num << 8U); +} + +/*! + \brief get IPA flag status in IPA_INTF register + \param[in] flag: IPA flags + one or more parameters can be selected which are shown as below: + \arg IPA_FLAG_TAE: transfer access error interrupt flag + \arg IPA_FLAG_FTF: full transfer finish interrupt flag + \arg IPA_FLAG_TLM: transfer line mark interrupt flag + \arg IPA_FLAG_LAC: LUT access conflict interrupt flag + \arg IPA_FLAG_LLF: LUT loading finish interrupt flag + \arg IPA_FLAG_WCF: wrong configuration interrupt flag + \param[out] none + \retval none +*/ +FlagStatus ipa_flag_get(uint32_t flag) +{ + if(RESET != (IPA_INTF & flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear IPA flag in IPA_INTF register + \param[in] flag: IPA flags + one or more parameters can be selected which are shown as below: + \arg IPA_FLAG_TAE: transfer access error interrupt flag + \arg IPA_FLAG_FTF: full transfer finish interrupt flag + \arg IPA_FLAG_TLM: transfer line mark interrupt flag + \arg IPA_FLAG_LAC: LUT access conflict interrupt flag + \arg IPA_FLAG_LLF: LUT loading finish interrupt flag + \arg IPA_FLAG_WCF: wrong configuration interrupt flag + \param[out] none + \retval none +*/ +void ipa_flag_clear(uint32_t flag) +{ + IPA_INTC |= (flag); +} + +/*! + \brief enable IPA interrupt + \param[in] int_flag: IPA interrupt flags + one or more parameters can be selected which are shown as below: + \arg IPA_INT_TAE: transfer access error interrupt + \arg IPA_INT_FTF: full transfer finish interrupt + \arg IPA_INT_TLM: transfer line mark interrupt + \arg IPA_INT_LAC: LUT access conflict interrupt + \arg IPA_INT_LLF: LUT loading finish interrupt + \arg IPA_INT_WCF: wrong configuration interrupt + \param[out] none + \retval none +*/ +void ipa_interrupt_enable(uint32_t int_flag) +{ + IPA_CTL |= (int_flag); +} + +/*! + \brief disable IPA interrupt + \param[in] int_flag: IPA interrupt flags + one or more parameters can be selected which are shown as below: + \arg IPA_INT_TAE: transfer access error interrupt + \arg IPA_INT_FTF: full transfer finish interrupt + \arg IPA_INT_TLM: transfer line mark interrupt + \arg IPA_INT_LAC: LUT access conflict interrupt + \arg IPA_INT_LLF: LUT loading finish interrupt + \arg IPA_INT_WCF: wrong configuration interrupt + \param[out] none + \retval none +*/ +void ipa_interrupt_disable(uint32_t int_flag) +{ + IPA_CTL &= ~(int_flag); +} + +/*! + \brief get IPA interrupt flag + \param[in] int_flag: IPA interrupt flag flags + one or more parameters can be selected which are shown as below: + \arg IPA_INT_FLAG_TAE: transfer access error interrupt flag + \arg IPA_INT_FLAG_FTF: full transfer finish interrupt flag + \arg IPA_INT_FLAG_TLM: transfer line mark interrupt flag + \arg IPA_INT_FLAG_LAC: LUT access conflict interrupt flag + \arg IPA_INT_FLAG_LLF: LUT loading finish interrupt flag + \arg IPA_INT_FLAG_WCF: wrong configuration interrupt flag + \param[out] none + \retval none +*/ +FlagStatus ipa_interrupt_flag_get(uint32_t int_flag) +{ + if(0U != (IPA_INTF & int_flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear IPA interrupt flag + \param[in] int_flag: IPA interrupt flag flags + one or more parameters can be selected which are shown as below: + \arg IPA_INT_FLAG_TAE: transfer access error interrupt flag + \arg IPA_INT_FLAG_FTF: full transfer finish interrupt flag + \arg IPA_INT_FLAG_TLM: transfer line mark interrupt flag + \arg IPA_INT_FLAG_LAC: LUT access conflict interrupt flag + \arg IPA_INT_FLAG_LLF: LUT loading finish interrupt flag + \arg IPA_INT_FLAG_WCF: wrong configuration interrupt flag + \param[out] none + \retval none +*/ +void ipa_interrupt_flag_clear(uint32_t int_flag) +{ + IPA_INTC |= (int_flag); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_iref.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_iref.c new file mode 100644 index 0000000..27382f4 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_iref.c @@ -0,0 +1,124 @@ +/*! + \file gd32f5xx_iref.c + \brief IREF driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_iref.h" + +/*! + \brief deinitialize IREF + \param[in] none + \param[out] none + \retval none +*/ +void iref_deinit(void) +{ + rcu_periph_reset_enable(RCU_IREFRST); + rcu_periph_reset_disable(RCU_IREFRST); +} + +/*! + \brief enable IREF + \param[in] none + \param[out] none + \retval none +*/ +void iref_enable(void) +{ + IREF_CTL |= IREF_CTL_CREN; +} + +/*! + \brief disable IREF + \param[in] none + \param[out] none + \retval none +*/ +void iref_disable(void) +{ + IREF_CTL &= ~IREF_CTL_CREN; +} + +/*! + \brief set IREF mode + \param[in] step + \arg IREF_MODE_LOW_POWER: 1uA step + \arg IREF_MODE_HIGH_CURRENT: 8uA step + \param[out] none + \retval none +*/ +void iref_mode_set(uint32_t step) +{ + IREF_CTL &= ~IREF_CTL_SSEL; + IREF_CTL |= step; +} + +/*! + \brief set IREF current precision trim value + \param[in] precisiontrim + \arg IREF_CUR_PRECISION_TRIM_X(x=0..31): (-15+ x)% + \param[out] none + \retval none +*/ +void iref_precision_trim_value_set(uint32_t precisiontrim) +{ + IREF_CTL &= ~IREF_CTL_CPT; + IREF_CTL |= precisiontrim; +} + +/*! + \brief set IREF sink current mode + \param[in] sinkmode + \arg IREF_SOURCE_CURRENT : source current. + \arg IREF_SINK_CURRENT: sink current + \param[out] none + \retval none +*/ +void iref_sink_set(uint32_t sinkmode) +{ + IREF_CTL &= ~IREF_CTL_SCMOD; + IREF_CTL |= sinkmode; +} + +/*! + \brief set IREF step data + \param[in] stepdata + \arg IREF_CUR_STEP_DATA_X:(x=0..63): step*x + \param[out] none + \retval none +*/ + +void iref_step_data_config(uint32_t stepdata) +{ + IREF_CTL &= ~IREF_CTL_CSDT; + IREF_CTL |= stepdata; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_misc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_misc.c new file mode 100644 index 0000000..9e4f1a5 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_misc.c @@ -0,0 +1,173 @@ +/*! + \file gd32f5xx_misc.c + \brief MISC driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_misc.h" + +/*! + \brief set the priority group + \param[in] nvic_prigroup: the NVIC priority group + \arg NVIC_PRIGROUP_PRE0_SUB4:0 bits for pre-emption priority 4 bits for subpriority + \arg NVIC_PRIGROUP_PRE1_SUB3:1 bits for pre-emption priority 3 bits for subpriority + \arg NVIC_PRIGROUP_PRE2_SUB2:2 bits for pre-emption priority 2 bits for subpriority + \arg NVIC_PRIGROUP_PRE3_SUB1:3 bits for pre-emption priority 1 bits for subpriority + \arg NVIC_PRIGROUP_PRE4_SUB0:4 bits for pre-emption priority 0 bits for subpriority + \param[out] none + \retval none +*/ +void nvic_priority_group_set(uint32_t nvic_prigroup) +{ + /* set the priority group value */ + SCB->AIRCR = NVIC_AIRCR_VECTKEY_MASK | nvic_prigroup; +} + +/*! + \brief enable NVIC interrupt request + \param[in] nvic_irq: the NVIC interrupt request, detailed in IRQn_Type + \param[in] nvic_irq_pre_priority: the pre-emption priority needed to set + \param[in] nvic_irq_sub_priority: the subpriority needed to set + \param[out] none + \retval none +*/ +void nvic_irq_enable(uint8_t nvic_irq, uint8_t nvic_irq_pre_priority, + uint8_t nvic_irq_sub_priority) +{ + uint32_t temp_priority = 0x00U, temp_pre = 0x00U, temp_sub = 0x00U; + /* use the priority group value to get the temp_pre and the temp_sub */ + if(((SCB->AIRCR) & (uint32_t)0x700U) == NVIC_PRIGROUP_PRE0_SUB4) { + temp_pre = 0x0U; + temp_sub = 0x4U; + } else if(((SCB->AIRCR) & (uint32_t)0x700U) == NVIC_PRIGROUP_PRE1_SUB3) { + temp_pre = 0x1U; + temp_sub = 0x3U; + } else if(((SCB->AIRCR) & (uint32_t)0x700U) == NVIC_PRIGROUP_PRE2_SUB2) { + temp_pre = 0x2U; + temp_sub = 0x2U; + } else if(((SCB->AIRCR) & (uint32_t)0x700U) == NVIC_PRIGROUP_PRE3_SUB1) { + temp_pre = 0x3U; + temp_sub = 0x1U; + } else if(((SCB->AIRCR) & (uint32_t)0x700U) == NVIC_PRIGROUP_PRE4_SUB0) { + temp_pre = 0x4U; + temp_sub = 0x0U; + } else { + nvic_priority_group_set(NVIC_PRIGROUP_PRE2_SUB2); + temp_pre = 0x2U; + temp_sub = 0x2U; + } + /* get the temp_priority to fill the NVIC->IP register */ + temp_priority = (uint32_t)nvic_irq_pre_priority << (0x4U - temp_pre); + temp_priority |= nvic_irq_sub_priority & (0x0FU >> (0x4U - temp_sub)); + temp_priority = temp_priority << 0x04U; + NVIC->IPR[nvic_irq] = (uint8_t)temp_priority; + /* enable the selected IRQ */ + NVIC->ISER[nvic_irq >> 0x05U] = (uint32_t)0x01U << (nvic_irq & (uint8_t)0x1FU); +} + +/*! + \brief disable NVIC interrupt request + \param[in] nvic_irq: the NVIC interrupt request, detailed in IRQn_Type + \param[out] none + \retval none +*/ +void nvic_irq_disable(uint8_t nvic_irq) +{ + /* disable the selected IRQ.*/ + NVIC->ICER[nvic_irq >> 0x05] = (uint32_t)0x01 << (nvic_irq & (uint8_t)0x1F); +} + +/*! + \brief set the NVIC vector table base address + \param[in] nvic_vict_tab: the RAM or FLASH base address + \arg NVIC_VECTTAB_RAM: RAM base address + \are NVIC_VECTTAB_FLASH: Flash base address + \param[in] offset: Vector Table offset + \param[out] none + \retval none +*/ +void nvic_vector_table_set(uint32_t nvic_vict_tab, uint32_t offset) +{ + SCB->VTOR = nvic_vict_tab | (offset & NVIC_VECTTAB_OFFSET_MASK); + __DSB(); +} + +/*! + \brief set the state of the low power mode + \param[in] lowpower_mode: the low power mode state + \arg SCB_LPM_SLEEP_EXIT_ISR: if chose this para, the system always enter low power + mode by exiting from ISR + \arg SCB_LPM_DEEPSLEEP: if chose this para, the system will enter the DEEPSLEEP mode + \arg SCB_LPM_WAKE_BY_ALL_INT: if chose this para, the lowpower mode can be woke up + by all the enable and disable interrupts + \param[out] none + \retval none +*/ +void system_lowpower_set(uint8_t lowpower_mode) +{ + SCB->SCR |= (uint32_t)lowpower_mode; +} + +/*! + \brief reset the state of the low power mode + \param[in] lowpower_mode: the low power mode state + \arg SCB_LPM_SLEEP_EXIT_ISR: if chose this para, the system will exit low power + mode by exiting from ISR + \arg SCB_LPM_DEEPSLEEP: if chose this para, the system will enter the SLEEP mode + \arg SCB_LPM_WAKE_BY_ALL_INT: if chose this para, the lowpower mode only can be + woke up by the enable interrupts + \param[out] none + \retval none +*/ +void system_lowpower_reset(uint8_t lowpower_mode) +{ + SCB->SCR &= (~(uint32_t)lowpower_mode); +} + +/*! + \brief set the systick clock source + \param[in] systick_clksource: the systick clock source needed to choose + \arg SYSTICK_CLKSOURCE_HCLK: systick clock source is from HCLK + \arg SYSTICK_CLKSOURCE_HCLK_DIV8: systick clock source is from HCLK/8 + \param[out] none + \retval none +*/ + +void systick_clksource_set(uint32_t systick_clksource) +{ + if(SYSTICK_CLKSOURCE_HCLK == systick_clksource) { + /* set the systick clock source from HCLK */ + SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK; + } else { + /* set the systick clock source from HCLK/8 */ + SysTick->CTRL &= SYSTICK_CLKSOURCE_HCLK_DIV8; + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_pkcau.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_pkcau.c new file mode 100644 index 0000000..6410388 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_pkcau.c @@ -0,0 +1,1270 @@ +/*! + \file gd32f5xx_pkcau.c + \brief PKCAU driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_pkcau.h" + +/* read result from PKCAU RAM */ +static void pkcau_memcpy_value(uint32_t offset, uint32_t value); +/* copy operand with EOS or ROS to PKCAU RAM */ +static void pkcau_memcpy_operand(uint32_t offset, const uint8_t operand[], uint32_t size); +/* read result from PKCAU RAM */ +static void pkcau_memread(uint32_t offset, uint8_t buf[], uint32_t size); + +/*! + \brief reset PKCAU + \param[in] none + \param[out] none + \retval none +*/ +void pkcau_deinit(void) +{ + rcu_periph_reset_enable(RCU_PKCAURST); + rcu_periph_reset_disable(RCU_PKCAURST); +} + +/*! + \brief initialize montgomery parameter structure with a default value + \param[in] none + \param[out] init_para: initialize montgomery parameter struct + \retval none +*/ +void pkcau_mont_struct_para_init(pkcau_mont_parameter_struct *init_para) +{ + /* initialize the member of montgomery parameter structure with the default value */ + init_para->modulus_n = 0U; + init_para->modulus_n_len = 0U; +} + +/*! + \brief initialize modular parameter structure with a default value + \param[in] none + \param[out] init_para: initialize modular parameter struct + \retval none +*/ +void pkcau_mod_struct_para_init(pkcau_mod_parameter_struct *init_para) +{ + /* initialize the member of modular parameter structure with the default value */ + init_para->oprd_a = 0U; + init_para->oprd_a_len = 0U; + init_para->oprd_b = 0U; + init_para->oprd_b_len = 0U; + init_para->modulus_n = 0U; + init_para->modulus_n_len = 0U; +} + +/*! + \brief initialize modular exponentiation parameter structure with a default value + \param[in] none + \param[out] init_para: initialize modular exponentiation parameter struct + \retval none +*/ +void pkcau_mod_exp_struct_para_init(pkcau_mod_exp_parameter_struct *init_para) +{ + /* initialize the member of modular exponentiation parameter structure with the default value */ + init_para->oprd_a = 0U; + init_para->oprd_a_len = 0U; + init_para->exp_e = 0U; + init_para->e_len = 0U; + init_para->modulus_n = 0U; + init_para->modulus_n_len = 0U; + init_para->mont_para = 0U; + init_para->mont_para_len = 0U; +} + +/*! + \brief initialize arithmetic parameter structure with a default value + \param[in] none + \param[out] init_para: initialize arithmetic parameter struct + \retval none +*/ +void pkcau_arithmetic_struct_para_init(pkcau_arithmetic_parameter_struct *init_para) +{ + /* initialize the member of arithmetic parameter structure with the default value */ + init_para->oprd_a = 0U; + init_para->oprd_a_len = 0U; + init_para->oprd_b = 0U; + init_para->oprd_b_len = 0U; +} + +/*! + \brief initialize CRT parameter structure with a default value + \param[in] none + \param[out] init_para: initialize CRT parameter struct + \retval none +*/ +void pkcau_crt_struct_para_init(pkcau_crt_parameter_struct *init_para) +{ + /* initialize the member of arithmetic parameter structure with the default value */ + init_para->oprd_a = 0U; + init_para->oprd_a_len = 0U; + init_para->oprd_dp = 0U; + init_para->oprd_dp_len = 0U; + init_para->oprd_dq = 0U; + init_para->oprd_dq_len = 0U; + init_para->oprd_qinv = 0U; + init_para->oprd_qinv_len = 0U; + init_para->oprd_p = 0U; + init_para->oprd_p_len = 0U; + init_para->oprd_q = 0U; + init_para->oprd_q_len = 0U; +} + +/*! + \brief initialize ECC curve parameter structure with a default value + \param[in] none + \param[out] init_para: initialize ECC curve parameter struct + \retval none +*/ +void pkcau_ec_group_struct_para_init(pkcau_ec_group_parameter_struct *init_para) +{ + /* initialize the member of ECC curve parameter structure with the default value */ + init_para->modulus_p = 0U; + init_para->modulus_p_len = 0U; + init_para->coff_a = 0U; + init_para->coff_a_len = 0U; + init_para->coff_b = 0U; + init_para->coff_b_len = 0U; + init_para->base_point_x = 0U; + init_para->base_point_x_len = 0U; + init_para->base_point_y = 0U; + init_para->base_point_y_len = 0U; + init_para->order_n = 0U; + init_para->order_n_len = 0U; + init_para->a_sign = 0U; + init_para->multi_k = 0U; + init_para->multi_k_len = 0U; + init_para->integer_k = 0U; + init_para->integer_k_len = 0U; + init_para->private_key_d = 0U; + init_para->private_key_d_len = 0U; + init_para->mont_para = 0U; + init_para->mont_para_len = 0U; +} + +/*! + \brief initialize point parameter structure with a default value + \param[in] none + \param[out] init_para: initialize point parameter struct + \retval none +*/ +void pkcau_point_struct_para_init(pkcau_point_parameter_struct *init_para) +{ + /* initialize the member of point parameter structure with the default value */ + init_para->point_x = 0U; + init_para->point_x_len = 0U; + init_para->point_y = 0U; + init_para->point_y_len = 0U; +} + +/*! + \brief initialize signature parameter structure with a default value + \param[in] none + \param[out] init_para: initialize signature parameter struct + \retval none +*/ +void pkcau_signature_struct_para_init(pkcau_signature_parameter_struct *init_para) +{ + /* initialize the member of signature parameter structure with the default value */ + init_para->sign_r = 0U; + init_para->sign_r_len = 0U; + init_para->sign_s = 0U; + init_para->sign_s_len = 0U; +} + +/*! + \brief initialize hash parameter structure with a default value + \param[in] none + \param[out] init_para: initialize hash parameter struct + \retval none +*/ +void pkcau_hash_struct_para_init(pkcau_hash_parameter_struct *init_para) +{ + /* initialize the member of hash parameter structure with the default value */ + init_para->hash_z = 0U; + init_para->hash_z_len = 0U; +} + +/*! + \brief initialize ECC out parameter structure with a default value + \param[in] none + \param[out] init_para: initialize ECC out parameter struct + \retval none +*/ +void pkcau_ecc_out_struct_para_init(pkcau_ecc_out_struct *init_para) +{ + /* initialize ecc output parameter structure with a default value */ + init_para->sign_extra = 0U; + init_para->point_x = 0U; + init_para->point_y = 0U; + init_para->sign_r = 0U; + init_para->sign_s = 0U; +} + +/*! + \brief enable PKCAU + \param[in] none + \param[out] none + \retval none +*/ +void pkcau_enable(void) +{ + PKCAU_CTL |= PKCAU_CTL_PKCAUEN; +} + +/*! + \brief disable PKCAU + \param[in] none + \param[out] none + \retval none +*/ +void pkcau_disable(void) +{ + PKCAU_CTL &= ~PKCAU_CTL_PKCAUEN; +} + +/*! + \brief start operation + \param[in] none + \param[out] none + \retval none +*/ +void pkcau_start(void) +{ + PKCAU_CTL |= PKCAU_CTL_START; +} + +/*! + \brief configure the PKCAU operation mode + \param[in] mode: PKCAU operation mode + only one parameter can be selected which is shown as below: + \arg PKCAU_MODE_MOD_EXP: Montgomery parameter computation then modular exponentiation + \arg PKCAU_MODE_MONT_PARAM: Montgomery parameter computation only + \arg PKCAU_MODE_MOD_EXP_FAST: modular exponentiation only + \arg PKCAU_MODE_CRT_EXP: RSA CRT exponentiation + \arg PKCAU_MODE_MOD_INVERSION: modular inversion + \arg PKCAU_MODE_ARITHMETIC_ADD: arithmetic addition + \arg PKCAU_MODE_ARITHMETIC_SUB: arithmetic subtraction + \arg PKCAU_MODE_ARITHMETIC_MUL: arithmetic multiplication + \arg PKCAU_MODE_ARITHMETIC_COMP: arithmetic comparison + \arg PKCAU_MODE_MOD_REDUCTION: modular reduction + \arg PKCAU_MODE_MOD_ADD: modular addition + \arg PKCAU_MODE_MOD_SUB: modular subtraction + \arg PKCAU_MODE_MONT_MUL: Montgomery multiplication + \arg PKCAU_MODE_ECC_MUL: Montgomery parameter computation then ECC scalar multiplication + \arg PKCAU_MODE_ECC_MUL_FAST: ECC scalar multiplication only + \arg PKCAU_MODE_ECDSA_SIGN: ECDSA sign + \arg PKCAU_MODE_ECDSA_VERIFICATION: ECDSA verification + \arg PKCAU_MODE_POINT_CHECK: point on elliptic curve Fp check + \retval none +*/ +void pkcau_mode_set(uint32_t mode) +{ + PKCAU_CTL &= ~PKCAU_CTL_MODESEL; + PKCAU_CTL |= mode; +} + +/*! + \brief execute montgomery parameter operation + This function can only be used when interrupt is not enabled + \param[in] mont_para: PKCAU montgomery parameter struct + modulus_n: modulus value n + modulus_n_len: modulus length in byte + \param[out] results: output buffer + \retval none +*/ +void pkcau_mont_param_operation(pkcau_mont_parameter_struct *mont_para, uint8_t *results) +{ + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the modulus length in bit to PKCAU RAM */ + pkcau_memcpy_value(0x00000404U, (mont_para->modulus_n_len << 3)); + + /* write the modulus value n to PKCAU RAM */ + pkcau_memcpy_operand(0x00000D5CU, mont_para->modulus_n, mont_para->modulus_n_len); + /* configure the operation mode */ + pkcau_mode_set(PKCAU_MODE_MONT_PARAM); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0x594U, (uint8_t *)results, mont_para->modulus_n_len); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); +} + +/*! + \brief execute modular operation, include modular addition, modular subtraction and montgomery multiplication + This function can only be used when interrupt is not enabled + \param[in] mod_para: PKCAU modular parameter struct + oprd_a: operand A + oprd_a_len: operand A length in byte + oprd_b: operand B + oprd_b_len: operand B length in byte + modulus_n: modulus value n + modulus_n_len: modulus length in byte + \param[in] mode: modular operation mode + only one parameter can be selected which is shown as below: + \arg PKCAU_MODE_MOD_ADD: modular addition + \arg PKCAU_MODE_MOD_SUB: modular subtraction + \arg PKCAU_MODE_MONT_MUL: Montgomery multiplication + \param[out] results: output buffer + \retval none +*/ +void pkcau_mod_operation(pkcau_mod_parameter_struct *mod_para, uint32_t mode, uint8_t *results) +{ + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the modulus length in bit to PKCAU RAM */ + pkcau_memcpy_value(0x00000404U, (mod_para->modulus_n_len << 3)); + + /* write the operand A, operand B and modulus value n to PKCAU RAM */ + pkcau_memcpy_operand(0x000008B4U, mod_para->oprd_a, mod_para->oprd_a_len); + pkcau_memcpy_operand(0x00000A44U, mod_para->oprd_b, mod_para->oprd_b_len); + pkcau_memcpy_operand(0x00000D5CU, mod_para->modulus_n, mod_para->modulus_n_len); + /* configure the operation mode */ + pkcau_mode_set(mode); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0xBD0U, (uint8_t *)results, mod_para->modulus_n_len); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); +} + +/*! + \brief execute modular exponentiation operation + This function can only be used when interrupt is not enabled + \param[in] mod_exp_para: PKCAU exponentiation parameter struct for fast mode + oprd_a: operand A + oprd_a_len: operand A length in byte + exp_e: exponent e + e_len: exponent length in byte + modulus_n: modulus value n + modulus_n_len: modulus length in byte + mont_para: exponentiation parameter R2 mod n + mont_para_len: montgomery parameter length in byte + \param[in] mode: modular exponentiation operation mode + only one parameter can be selected which is shown as below: + \arg PKCAU_MODE_MOD_EXP_FAST: montgomery parameter computation then modular exponentiation + \arg PKCAU_MODE_MOD_EXP: modular exponentiation only + \param[out] results: output buffer + \retval none +*/ +void pkcau_mod_exp_operation(pkcau_mod_exp_parameter_struct *mod_exp_para, uint32_t mode, uint8_t *results) +{ + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the exponent length and modulus length in bit to PKCAU RAM */ + pkcau_memcpy_value(0x00000400U, (mod_exp_para->e_len << 3)); + pkcau_memcpy_value(0x00000404U, (mod_exp_para->modulus_n_len << 3)); + + /* write the operand A, exponent e and modulus value n to PKCAU RAM */ + pkcau_memcpy_operand(0x00000A44U, mod_exp_para->oprd_a, mod_exp_para->oprd_a_len); + pkcau_memcpy_operand(0x00000BD0U, mod_exp_para->exp_e, mod_exp_para->e_len); + pkcau_memcpy_operand(0x00000D5CU, mod_exp_para->modulus_n, mod_exp_para->modulus_n_len); + /* write the montgomery parameter to PKCAU RAM */ + if(mode == PKCAU_MODE_MOD_EXP_FAST) { + pkcau_memcpy_operand(0x00000594U, mod_exp_para->mont_para, mod_exp_para->mont_para_len); + } + /* configure the operation mode */ + pkcau_mode_set(mode); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0x724U, (uint8_t *)results, mod_exp_para->modulus_n_len); + + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); +} + +/*! + \brief execute modular inversion operation + This function can only be used when interrupt is not enabled + \param[in] mod_inver_para: PKCAU modular inversion parameter struct + oprd_a: operand A + oprd_a_len: operand A length in byte + modulus_n: modulus value n + modulus_n_len: modulus length in byte + \param[out] results: output buffer + \retval none +*/ +void pkcau_mod_inver_operation(pkcau_mod_parameter_struct *mod_inver_para, uint8_t *results) +{ + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the modulus length in bit to PKCAU RAM */ + pkcau_memcpy_value(0x00000404U, (mod_inver_para->modulus_n_len) << 3); + + /* write the operand A and modulus value n to PKCAU RAM */ + pkcau_memcpy_operand(0x000008B4U, mod_inver_para->oprd_a, mod_inver_para->oprd_a_len); + pkcau_memcpy_operand(0x00000A44U, mod_inver_para->modulus_n, mod_inver_para->modulus_n_len); + /* configure the operation mode */ + pkcau_mode_set(PKCAU_MODE_MOD_INVERSION); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0xBD0U, (uint8_t *)results, mod_inver_para->modulus_n_len); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); +} + +/*! + \brief execute modular reduction operation + This function can only be used when interrupt is not enabled + \param[in] mod_reduc_para: PKCAU modular reduction parameter struct + oprd_a: operand A + oprd_a_len: length of operand A in byte + modulus_n: modulus value n + modulus_n_len: modulus length in byte + \param[out] results: output buffer + \retval none +*/ +void pkcau_mod_reduc_operation(pkcau_mod_parameter_struct *mod_reduc_para, uint8_t *results) +{ + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the modulus length and length of operand A in bit to PKCAU RAM */ + pkcau_memcpy_value(0x00000400U, (mod_reduc_para->oprd_a_len) << 3); + pkcau_memcpy_value(0x00000404U, (mod_reduc_para->modulus_n_len) << 3); + + /* write the operand A and modulus value n to PKCAU RAM */ + pkcau_memcpy_operand(0x000008B4U, mod_reduc_para->oprd_a, mod_reduc_para->oprd_a_len); + pkcau_memcpy_operand(0x00000A44U, mod_reduc_para->modulus_n, mod_reduc_para->modulus_n_len); + /* configure the operation mode */ + pkcau_mode_set(PKCAU_MODE_MOD_REDUCTION); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0xBD0U, (uint8_t *)results, mod_reduc_para->modulus_n_len); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); +} + +/*! + \brief execute arithmetic operation + This function can only be used when interrupt is not enabled + \param[in] arithmetic_para: PKCAU arithmetic parameter struct + oprd_a: operand A + oprd_a_len: length of operand A in byte + oprd_b: operand B + oprd_b_len: length of operand B in byte + \param[in] mode: arithmetic operation mode + only one parameter can be selected which is shown as below: + \arg PKCAU_MODE_ARITHMETIC_ADD: arithmetic addition + \arg PKCAU_MODE_ARITHMETIC_SUB: arithmetic subtraction + \arg PKCAU_MODE_ARITHMETIC_MUL: arithmetic multiplication + \arg PKCAU_MODE_ARITHMETIC_COMP: arithmetic comparison + \param[out] results: output buffer + \retval none +*/ +void pkcau_arithmetic_operation(pkcau_arithmetic_parameter_struct *arithmetic_para, uint32_t mode, uint8_t *results) +{ + uint32_t size = 0U; + + uint32_t max_len = (arithmetic_para->oprd_a_len > arithmetic_para->oprd_b_len) ? \ + arithmetic_para->oprd_a_len : arithmetic_para->oprd_b_len; + + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* calculate number of byte to read */ + switch(mode) { + case PKCAU_MODE_ARITHMETIC_ADD: + size = max_len + 1U; + break; + case PKCAU_MODE_ARITHMETIC_SUB: + size = max_len; + break; + case PKCAU_MODE_ARITHMETIC_MUL: + size = arithmetic_para->oprd_a_len + arithmetic_para->oprd_b_len; + break; + case PKCAU_MODE_ARITHMETIC_COMP: + size = 1U; + break; + default: + break; + } + + /* write the length of operand in bit to PKCAU RAM */ + pkcau_memcpy_value(0x00000404U, max_len << 3); + + /* write the operand A and operand B to PKCAU RAM */ + pkcau_memcpy_operand(0x000008B4U, arithmetic_para->oprd_a, arithmetic_para->oprd_a_len); + pkcau_memcpy_operand(0x00000A44U, arithmetic_para->oprd_b, arithmetic_para->oprd_b_len); + /* configure the operation mode */ + pkcau_mode_set(mode); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0xBD0U, (uint8_t *)results, size); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); +} + +/*! + \brief execute RSA CRT exponentiation operation + This function can only be used when interrupt is not enabled + \param[in] crt_para: PKCAU modular CRT parameter struct + oprd_a: operand A + oprd_a_len: length of operand A in byte + oprd_dp: operand dp + oprd_dp_len: length of operand dp in byte + oprd_dq:operand dq + oprd_dq_len: length of operand dq in byte + oprd_qinv: operand qinv + oprd_qinv_len: length of operand qinv in byte + oprd_p: prime operand p + oprd_p_len: length of operand p in byte + oprd_q: prime operand q + oprd_q_len: length of operand q in byte + \param[out] results: output buffer + \retval none +*/ +void pkcau_crt_exp_operation(pkcau_crt_parameter_struct *crt_para, uint8_t *results) +{ + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the modulus length in bit to PKCAU RAM */ + pkcau_memcpy_value(0x00000404U, (crt_para->oprd_a_len << 3)); + + /* write the operand dp, dq, qinv, p and q to PKCAU RAM */ + pkcau_memcpy_operand(0x0000065CU, crt_para->oprd_dp, crt_para->oprd_dp_len); + pkcau_memcpy_operand(0x00000BD0U, crt_para->oprd_dq, crt_para->oprd_dq_len); + pkcau_memcpy_operand(0x000007ECU, crt_para->oprd_qinv, crt_para->oprd_qinv_len); + pkcau_memcpy_operand(0x0000097CU, crt_para->oprd_p, crt_para->oprd_p_len); + pkcau_memcpy_operand(0x00000D5CU, crt_para->oprd_q, crt_para->oprd_q_len); + /* write the operand A to PKCAU RAM */ + pkcau_memcpy_operand(0x00000EECU, crt_para->oprd_a, crt_para->oprd_a_len); + /* configure the operation mode */ + pkcau_mode_set(PKCAU_MODE_CRT_EXP); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0x724U, (uint8_t *)results, crt_para->oprd_a_len); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); +} + +/*! + \brief execute point check operation + This function can only be used when interrupt is not enabled + \param[in] point_para: PKCAU point struct + point_x: point coordinate x + point_x_len: point coordinate x length in byte + point_y: point coordinate y + point_y_len: point coordinate y length in byte + \param[in] curve_group_para: PKCAU ECC curve parameter struct + modulus_p: curve modulus p + modulus_p_len: curve modulus p length in byte + coff_a: curve coefficient a + coff_a_len: curve coefficient a length in byte + coff_b: curve coefficient b + coff_b_len: curve coefficient b length in byte + base_point_x: curve base point coordinate x + base_point_x_len: curve base point coordinate x length in byte + base_point_y: curve base point coordinate y + base_point_y_len: curve base point coordinate y length in byte + order_n: curve prime order n + order_n_len: curve prime order n length in byte + a_sign: curve coefficient a sign + multi_k: scalar multiplier k + multi_k_len: scalar multiplier k length in byte + integer_k: integer k length in byte + integer_k_len: integer k length in byte + private_key_d: private key d + private_key_d_len: private key d length in byte + mont_para: montgomery parameter R2 mod n + mont_para_len: montgomery parameter R2 mod n length in byte + \param[out] none + \retval flag indicating whether the point is on an elliptic curve or not +*/ +uint8_t pkcau_point_check_operation(pkcau_point_parameter_struct *point_para, + const pkcau_ec_group_parameter_struct *curve_group_para) +{ + uint8_t res = 1U; + + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the modulus length in bit to PKCAU RAM */ + pkcau_memcpy_value(0x00000404U, (curve_group_para->modulus_p_len << 3)); + /* write the sign of curve coefficient a to PKCAU RAM */ + pkcau_memcpy_value(0x00000408U, curve_group_para->a_sign); + + /* write the curve coefficient a, curve coefficient b and curve modulus p to PKCAU RAM */ + pkcau_memcpy_operand(0x0000040CU, curve_group_para->coff_a, curve_group_para->coff_a_len); + pkcau_memcpy_operand(0x000007FCU, curve_group_para->coff_b, curve_group_para->coff_b_len); + pkcau_memcpy_operand(0x00000460U, curve_group_para->modulus_p, curve_group_para->modulus_p_len); + /* write the point coordinate x and point coordinate y to PKCAU RAM */ + pkcau_memcpy_operand(0x0000055CU, point_para->point_x, point_para->point_x_len); + pkcau_memcpy_operand(0x000005B0U, point_para->point_y, point_para->point_y_len); + /* configure the operation mode */ + pkcau_mode_set(PKCAU_MODE_POINT_CHECK); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0x400U, (uint8_t *)&res, 1U); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); + + return res; +} + +/*! + \brief execute point multiplication operation + This function can only be used when interrupt is not enabled + \param[in] point_para: PKCAU point struct + point_x: point coordinate x + point_x_len: point coordinate x length in byte + point_y: point coordinate y + point_y_len: point coordinate y length in byte + \param[in] curve_group_para: PKCAU ECC curve parameter struct + modulus_p: curve modulus p + modulus_p_len: curve modulus p length in byte + coff_a: curve coefficient a + coff_a_len: curve coefficient a length in byte + coff_b: curve coefficient b + coff_b_len: curve coefficient b length in byte + base_point_x: curve base point coordinate x + base_point_x_len: curve base point coordinate x length in byte + base_point_y: curve base point coordinate y + base_point_y_len: curve base point coordinate y length in byte + order_n: curve prime order n + order_n_len: curve prime order n length in byte + a_sign: curve coefficient a sign + + multi_k: scalar multiplier k + multi_k_len: scalar multiplier k length in byte + integer_k: integer k length in byte + integer_k_len: integer k length in byte + private_key_d: private key d + private_key_d_len: private key d length in byte + mont_para: montgomery parameter R2 mod n + mont_para_len: montgomery parameter R2 mod n length in byte + \param[in] mode: point multiplication operation mode + only one parameter can be selected which is shown as below: + \arg PKCAU_MODE_ECC_SCALAR_MUL_FAST: montgomery parameter computation then ECC scalar multiplication + \arg PKCAU_MODE_ECC_SCALAR_MUL: ECC scalar multiplication only + \param[out] result: ecdsa signature, ecc scalar multiplication output structure + sign_extra: flag of extended ECDSA sign (extra outputs) + sign_r: pointer to signature part r + sign_s: pointer to signature part s + point_x: pointer to point kP coordinate x + point_y: pointer to point kP coordinate y + \retval none +*/ +void pkcau_point_mul_operation(pkcau_point_parameter_struct *point_para, + const pkcau_ec_group_parameter_struct *curve_group_para, \ + uint32_t mode, pkcau_ecc_out_struct *result) +{ + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the length of scalar multiplier k, curve modulus p length in bit and curve coefficient a sign to PKCAU RAM */ + pkcau_memcpy_value(0x00000400U, (curve_group_para->multi_k_len << 3)); + pkcau_memcpy_value(0x00000404U, (curve_group_para->modulus_p_len << 3)); + pkcau_memcpy_value(0x00000408U, curve_group_para->a_sign); + + /* write the curve coefficient a, curve modulus p, scalar multiplier k, point coordinate x and point coordinate y to PKCAU RAM */ + pkcau_memcpy_operand(0x0000040CU, curve_group_para->coff_a, curve_group_para->coff_a_len); + pkcau_memcpy_operand(0x00000460U, curve_group_para->modulus_p, curve_group_para->modulus_p_len); + pkcau_memcpy_operand(0x00000508U, curve_group_para->multi_k, curve_group_para->multi_k_len); + pkcau_memcpy_operand(0x0000055CU, point_para->point_x, point_para->point_x_len); + pkcau_memcpy_operand(0x000005B0U, point_para->point_y, point_para->point_y_len); + if(mode == PKCAU_MODE_ECC_SCALAR_MUL_FAST) { + pkcau_memcpy_operand(0x000004B4U, curve_group_para->mont_para, curve_group_para->mont_para_len); + } + /* configure the operation mode */ + pkcau_mode_set(mode); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0x55CU, (uint8_t *)result->point_x, curve_group_para->modulus_p_len); + pkcau_memread(0x5B0U, (uint8_t *)result->point_y, curve_group_para->modulus_p_len); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); +} + +/*! + \brief execute ECDSA sign operation + This function can only be used when interrupt is not enabled + \param[in] hash_para: hash struct + hash_z: hash value z + hash_z_len: hash value z length in byte + \param[in] curve_group_para: PKCAU ECC curve paramter struct + modulus_p: curve modulus p + modulus_p_len: curve modulus p length in byte + coff_a: curve coefficient a + coff_a_len: curve coefficient a length in byte + coff_b: curve coefficient b + coff_b_len: curve coefficient b length in byte + base_point_x: curve base point coordinate x + base_point_x_len: curve base point coordinate x length in byte + base_point_y: curve base point coordinate y + base_point_y_len: curve base point coordinate y length in byte + order_n: curve prime order n + order_n_len: curve prime order n length in byte + a_sign: curve coefficient a sign + multi_k: scalar multiplier k + multi_k_len: scalar multiplier k length in byte + integer_k: integer k length in byte + integer_k_len: integer k length in byte + private_key_d: private key d + private_key_d_len: private key d length in byte + mont_para: montgomery parameter R2 mod n + mont_para_len: montgomery parameter R2 mod n length in byte + \param[out] result: ecdsa signature, ecc scalar multiplication output structure + sign_extra: flag of extended ECDSA sign (extra outputs) + sign_r: pointer to signature part r + sign_s: pointer to signature part s + point_x: pointer to point kP coordinate x + point_y: pointer to point kP coordinate y + \retval flag indicating whether the signature operation was successful +*/ +uint8_t pkcau_ecdsa_sign_operation(pkcau_hash_parameter_struct *hash_para, \ + const pkcau_ec_group_parameter_struct *curve_group_para, \ + pkcau_ecc_out_struct *result) +{ + uint8_t res = 2U; + + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + + /* write the curve prime order n length, curve modulus p length in bit and curve coefficient a sign to PKCAU RAM */ + pkcau_memcpy_value(0x00000400U, (curve_group_para->order_n_len << 3)); + pkcau_memcpy_value(0x00000404U, (curve_group_para->modulus_p_len << 3)); + pkcau_memcpy_value(0x00000408U, curve_group_para->a_sign); + + /* write the curve coefficient a to PKCAU RAM */ + pkcau_memcpy_operand(0x0000040CU, curve_group_para->coff_a, curve_group_para->coff_a_len); + /* write the curve modulus p to PKCAU RAM */ + pkcau_memcpy_operand(0x00000460U, curve_group_para->modulus_p, curve_group_para->modulus_p_len); + /* write the integer k to PKCAU RAM */ + pkcau_memcpy_operand(0x00000508U, curve_group_para->integer_k, curve_group_para->integer_k_len); + /* write the curve base point coordinate x to PKCAU RAM */ + pkcau_memcpy_operand(0x0000055CU, curve_group_para->base_point_x, curve_group_para->base_point_x_len); + /* write the curve base point coordinate y to PKCAU RAM */ + pkcau_memcpy_operand(0x000005B0U, curve_group_para->base_point_y, curve_group_para->base_point_y_len); + /* write the hash value z and hash value z length in byte to PKCAU RAM */ + pkcau_memcpy_operand(0x00000DE8U, hash_para->hash_z, hash_para->hash_z_len); + /* write the private key d to PKCAU RAM */ + pkcau_memcpy_operand(0x00000E3CU, curve_group_para->private_key_d, curve_group_para->private_key_d_len); + /* write the curve prime order n to PKCAU RAM */ + pkcau_memcpy_operand(0x00000E94U, curve_group_para->order_n, curve_group_para->order_n_len); + /* configure the operation mode */ + pkcau_mode_set(PKCAU_MODE_ECDSA_SIGN); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + /* read results from RAM address */ + pkcau_memread(0x700U, (uint8_t *)result->sign_r, curve_group_para->order_n_len); + pkcau_memread(0x754U, (uint8_t *)result->sign_s, curve_group_para->order_n_len); + pkcau_memread(0xEE8U, (uint8_t *)&res, 1U); + if(0U != result->sign_extra) { + pkcau_memread(0x103CU, (uint8_t *)result->point_x, curve_group_para->order_n_len); + pkcau_memread(0x1090U, (uint8_t *)result->point_y, curve_group_para->order_n_len); + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); + + return res; +} + +/*! + \brief execute ECDSA verification operation + This function can only be used when interrupt is not enabled + \param[in] point_para: PKCAU point struct + point_x: point coordinate x + point_x_len: point coordinate x length in byte + point_y: point coordinate y + point_y_len: point coordinate y length in byte + \param[in] hash_para: hash struct + hash_z: hash value z + hash_z_len: hash value z length in byte + \param[in] signature_para: signature struct + sign_r: signature part r + sign_r_len: signature part r lnegth in byte + sign_s: signature part s + sign_s_len: signature part s lnegth in byte + \param[in] curve_group_para: PKCAU ECC curve paramter struct + modulus_p: curve modulus p + modulus_p_len: curve modulus p length in byte + coff_a: curve coefficient a + coff_a_len: curve coefficient a length in byte + coff_b: curve coefficient b + coff_b_len: curve coefficient b length in byte + base_point_x: curve base point coordinate x + base_point_x_len: curve base point coordinate x length in byte + base_point_y: curve base point coordinate y + base_point_y_len: curve base point coordinate y length in byte + order_n: curve prime order n + order_n_len: curve prime order n length in byte + a_sign: curve coefficient a sign + + multi_k: scalar multiplier k + multi_k_len: scalar multiplier k length in byte + integer_k: integer k length in byte + integer_k_len: integer k length in byte + private_key_d: private key d + private_key_d_len: private key d length in byte + mont_para: montgomery parameter R2 mod n + mont_para_len: montgomery parameter R2 mod n length in byte + \param[out] none + \retval flag indicating whether the signature verification operation was successful +*/ +uint8_t pkcau_ecdsa_verification_operation(pkcau_point_parameter_struct *point_para, \ + pkcau_hash_parameter_struct *hash_para, \ + pkcau_signature_parameter_struct *signature_para, \ + const pkcau_ec_group_parameter_struct *curve_group_para) +{ + uint8_t res = 1U; + + /* reset PKCAU */ + pkcau_deinit(); + /* enable PKCAU */ + pkcau_enable(); + /* wait for PKCAU busy flag to reset */ + while(RESET != pkcau_flag_get(PKCAU_FLAG_BUSY)){ + } + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + + /* write the curve prime order n length, curve modulus p length in bit and curve coefficient a sign to PKCAU RAM */ + pkcau_memcpy_value(0x00000404U, (curve_group_para->order_n_len << 3)); + pkcau_memcpy_value(0x000004B4U, (curve_group_para->modulus_p_len << 3)); + pkcau_memcpy_value(0x0000045CU, curve_group_para->a_sign); + + /* write the curve coefficient a to PKCAU RAM */ + pkcau_memcpy_operand(0x00000460U, curve_group_para->coff_a, curve_group_para->coff_a_len); + /* write the curve modulus p to PKCAU RAM */ + pkcau_memcpy_operand(0x000004B8U, curve_group_para->modulus_p, curve_group_para->modulus_p_len); + /* write the curve base point coordinate x to PKCAU RAM */ + pkcau_memcpy_operand(0x000005E8U, curve_group_para->base_point_x, curve_group_para->base_point_x_len); + /* write the curve base point coordinate y to PKCAU RAM */ + pkcau_memcpy_operand(0x0000063CU, curve_group_para->base_point_y, curve_group_para->base_point_y_len); + /* write the point coordinate x to PKCAU RAM */ + pkcau_memcpy_operand(0x00000F40U, point_para->point_x, point_para->point_x_len); + /* write the point coordinate y to PKCAU RAM */ + pkcau_memcpy_operand(0x00000F94U, point_para->point_y, point_para->point_y_len); + /* write the signature part r to PKCAU RAM */ + pkcau_memcpy_operand(0x000001098U, signature_para->sign_r, signature_para->sign_r_len); + /* write the signature part s to PKCAU RAM */ + pkcau_memcpy_operand(0x00000A44U, signature_para->sign_s, signature_para->sign_s_len); + /* write the hash value z and hash value z length in byte to PKCAU RAM */ + pkcau_memcpy_operand(0x00000FE8U, hash_para->hash_z, hash_para->hash_z_len); + /* write the curve prime order n to PKCAU RAM */ + pkcau_memcpy_operand(0x00000D5CU, curve_group_para->order_n, curve_group_para->order_n_len); + /* configure the operation mode */ + pkcau_mode_set(PKCAU_MODE_ECDSA_VERIFICATION); + /* start computation */ + pkcau_start(); + + /* wait for PKCAU operation completed */ + while(SET != pkcau_flag_get(PKCAU_FLAG_END)){ + } + pkcau_memread(0x5B0U, (uint8_t *)&res, 1U); + /* clear end flag */ + pkcau_flag_clear(PKCAU_FLAG_END); + /* disable PKCAU */ + pkcau_disable(); + + return res; +} + +/*! + \brief get PKCAU flag status + \param[in] flag: PKCAU flags + only one parameter can be selected which is shown as below: + \arg PKCAU_FLAG_ADDRERR: address error flag + \arg PKCAU_FLAG_RAMERR: PKCAU RAM error flag + \arg PKCAU_FLAG_END: end of PKCAU operation flag + \arg PKCAU_FLAG_BUSY: busy flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus pkcau_flag_get(uint32_t flag) +{ + if(RESET != (PKCAU_STAT & flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear PKCAU flag status + \param[in] flag: PKCAU flags + one or more parameters can be selected which is shown as below: + \arg PKCAU_FLAG_ADDRERR: address error flag + \arg PKCAU_FLAG_RAMERR: PKCAU RAM error flag + \arg PKCAU_FLAG_END: end of PKCAU operation flag + \param[out] none + \retval none +*/ +void pkcau_flag_clear(uint32_t flag) +{ + switch(flag) { + /* clear address error flag */ + case PKCAU_FLAG_ADDRERR: + PKCAU_STATC |= PKCAU_STATC_ADDRERRC; + break; + /* clear PKCAU RAM error flag */ + case PKCAU_FLAG_RAMERR: + PKCAU_STATC |= PKCAU_STATC_RAMERRC; + break; + /* clear end of PKCAU operation flag */ + case PKCAU_FLAG_END: + PKCAU_STATC |= PKCAU_STATC_ENDFC; + break; + default : + break; + } +} + +/*! + \brief enable PKCAU interrupt + \param[in] interrupt: interrupt type + one or more parameters can be selected which is shown as below: + \arg PKCAU_INT_ADDRERR: address error interrupt + \arg PKCAU_INT_RAMERR: PKCAU RAM error interrupt + \arg PKCAU_INT_END: end of PKCAU operation interrupt + \param[out] none + \retval none +*/ +void pkcau_interrupt_enable(uint32_t interrupt) +{ + PKCAU_CTL |= interrupt; +} + +/*! + \brief disable PKCAU interrupt + \param[in] interrupt: interrupt type + one or more parameters can be selected which is shown as below: + \arg PKCAU_INT_ADDRERR: address error interrupt + \arg PKCAU_INT_RAMERR: PKCAU RAM error interrupt + \arg PKCAU_INT_END: end of PKCAU operation interrupt + \param[out] none + \retval none +*/ +void pkcau_interrupt_disable(uint32_t interrupt) +{ + PKCAU_CTL &= ~(interrupt); +} + +/*! + \brief get PKCAU interrupt flag status + \param[in] int_flag: PKCAU interrupt flags + only one parameter can be selected which is shown as below: + \arg PKCAU_INT_FLAG_ADDRERR: address error interrupt flag + \arg PKCAU_INT_FLAG_RAMERR: PKCAU RAM error interrupt flag + \arg PKCAU_INT_FLAG_END: end of PKCAU operation interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus pkcau_interrupt_flag_get(uint32_t int_flag) +{ + uint32_t reg1 = PKCAU_CTL; + uint32_t reg2 = PKCAU_STAT; + + switch(int_flag) { + /* clear address error interrupt flag */ + case PKCAU_INT_FLAG_ADDRERR: + reg1 = reg1 & PKCAU_CTL_ADDRERRIE; + reg2 = reg2 & PKCAU_STAT_ADDRERR; + break; + /* clear RAM error interrupt flag */ + case PKCAU_INT_FLAG_RAMERR: + reg1 = reg1 & PKCAU_CTL_RAMERRIE; + reg2 = reg2 & PKCAU_STAT_RAMERR; + break; + /* clear end of PKCAU operation interrupt flag */ + case PKCAU_INT_FLAG_ENDF: + reg1 = reg1 & PKCAU_CTL_ENDIE; + reg2 = reg2 & PKCAU_STAT_ENDF; + break; + default : + break; + } + /*get PKCAU interrupt flag status */ + if(reg1 && reg2) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear PKCAU interrupt flag status + \param[in] int_flag: PKCAU interrupt flags + only one parameter can be selected which is shown as below: + \arg PKCAU_INT_FLAG_ADDRERR: address error interrupt flag + \arg PKCAU_INT_FLAG_RAMERR: PKCAU RAM error interrupt flag + \arg PKCAU_INT_FLAG_END: end of PKCAU operation interrupt flag + \param[out] none + \retval none +*/ +void pkcau_interrupt_flag_clear(uint32_t int_flag) +{ + switch(int_flag) { + /* clear address error interrupt flag */ + case PKCAU_INT_FLAG_ADDRERR: + PKCAU_STATC |= PKCAU_STATC_ADDRERRC; + break; + /* clear PKCAU RAM error interrupt flag */ + case PKCAU_INT_FLAG_RAMERR: + PKCAU_STATC |= PKCAU_STATC_RAMERRC; + break; + /* clear end of PKCAU operation interrupt flag */ + case PKCAU_INT_FLAG_ENDF: + PKCAU_STATC |= PKCAU_STATC_ENDFC; + break; + default: + break; + } +} + +/*! + \brief copy normal 32-bit value to PKCAU RAM + \param[in] offset: RAM address offset to PKCAU base address + \param[in] value: the value needed to write into PKCAU RAM + \param[out] none + \retval none +*/ +static void pkcau_memcpy_value(uint32_t offset, uint32_t value) +{ + uint32_t *addr = (uint32_t *)((uint32_t)(PKCAU_BASE + offset)); + *addr = value; +} + +/*! + \brief copy operand with EOS or ROS to PKCAU RAM + \param[in] offset: RAM address offset to PKCAU base address + \param[in] operand: the big endian operand vector, the left most byte of the value should be in the first element of the vector. + If input data is little endian, please flip it in application code. + \param[in] size: operand vector length in byte + \retval none +*/ +static void pkcau_memcpy_operand(uint32_t offset, const uint8_t operand[], uint32_t size) +{ + uint32_t data = 0U, i = 0U, j = 0U; + + while(size >= 4U) { + /* convert the big endian operand vector to little endian parameter to input to PKCAU RAM */ + data = (uint32_t)((uint32_t)operand[size - 1U] | ((uint32_t)operand[size - 2U] << 8U) | (( + uint32_t)operand[size - 3U] << 16U) | ((uint32_t)operand[size - 4U] << 24U)); + *(uint32_t *)((uint32_t)(PKCAU_BASE + offset + i)) = data; + i = i + 4U; + size -= 4U; + } + /* convert the big endian operand vector to little endian parameter to input to PKCAU RAM which is not a multiple of four */ + if(size > 0U) { + data = 0U; + for(j = 0U; j < size; j++) { + data = (uint32_t)((data << 8U) | (uint32_t)operand[j]); + } + *(uint32_t *)((uint32_t)(PKCAU_BASE + offset + i)) = data; + i = i + 4U; + } + + /* an additional word 0x00000000 is expected by the PKCAU */ + *(uint32_t *)((uint32_t)(PKCAU_BASE + offset + i)) = 0x00000000U; +} + +/*! + \brief read result from PKCAU RAM + \param[in] offset: RAM address offset to PKCAU base address + \param[out] buf: big endian result buffer, the left most byte from the PKCAU should be in the first element of buffer + If need output data is little endian, please flip it in application code. + \param[in] size: number of byte to read + \retval none +*/ +static void pkcau_memread(uint32_t offset, uint8_t buf[], uint32_t size) +{ + uint32_t data = 0U, i = 0U, j = 0U; + + /* read data from PKCAU RAM */ + while(size >= 4U) { + data = *(uint32_t *)((uint32_t)(PKCAU_BASE + offset + i)); + i = i + 4U; + + /* data in PKCAU RAM is big endian */ + buf[size - 1U] = (uint8_t)(data & 0xffU); + buf[size - 2U] = (uint8_t)((data >> 8U) & 0xffU); + buf[size - 3U] = (uint8_t)((data >> 16U) & 0xffU); + buf[size - 4U] = (uint8_t)((data >> 24U) & 0xffU); + size -= 4U; + } + /* read data from PKCAU RAM which is not a multiple of four */ + if(size > 0U) { + data = *(uint32_t *)((uint32_t)(PKCAU_BASE + offset + i)); + for(j = 0U; j < size; j++) { + buf[j] = (uint8_t)((data >> ((size - 1U - j) * 8U)) & 0xffU); + } + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_pmu.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_pmu.c new file mode 100644 index 0000000..2e61c11 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_pmu.c @@ -0,0 +1,394 @@ +/*! + \file gd32f5xx_pmu.c + \brief PMU driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_pmu.h" + +/*! + \brief reset PMU registers + \param[in] none + \param[out] none + \retval none +*/ +void pmu_deinit(void) +{ + /* reset PMU */ + rcu_periph_reset_enable(RCU_PMURST); + rcu_periph_reset_disable(RCU_PMURST); +} + +/*! + \brief select low voltage detector threshold + \param[in] lvdt_n: + \arg PMU_LVDT_0: voltage threshold is 2.1V + \arg PMU_LVDT_1: voltage threshold is 2.3V + \arg PMU_LVDT_2: voltage threshold is 2.4V + \arg PMU_LVDT_3: voltage threshold is 2.6V + \arg PMU_LVDT_4: voltage threshold is 2.7V + \arg PMU_LVDT_5: voltage threshold is 2.9V + \arg PMU_LVDT_6: voltage threshold is 3.0V + \arg PMU_LVDT_7: voltage threshold is 3.1V + \param[out] none + \retval none +*/ +void pmu_lvd_select(uint32_t lvdt_n) +{ + /* disable LVD */ + PMU_CTL &= ~PMU_CTL_LVDEN; + /* clear LVDT bits */ + PMU_CTL &= ~PMU_CTL_LVDT; + /* set LVDT bits according to pmu_lvdt_n */ + PMU_CTL |= lvdt_n; + /* enable LVD */ + PMU_CTL |= PMU_CTL_LVDEN; +} + +/*! + \brief disable PMU lvd + \param[in] none + \param[out] none + \retval none +*/ +void pmu_lvd_disable(void) +{ + /* disable LVD */ + PMU_CTL &= ~PMU_CTL_LVDEN; +} + +/*! + \brief select LDO output voltage + this bit set by software when the main PLL closed, before closing PLL, change the system clock to IRC16M or HXTAL + \param[in] ldo_output: + \arg PMU_LDOVS_LOW: low-driver mode enable in deep-sleep mode + \arg PMU_LDOVS_MID: mid-driver mode disable in deep-sleep mode + \arg PMU_LDOVS_HIGH: high-driver mode disable in deep-sleep mode + \param[out] none + \retval none +*/ +void pmu_ldo_output_select(uint32_t ldo_output) +{ + PMU_CTL &= ~PMU_CTL_LDOVS; + PMU_CTL |= ldo_output; +} + +/*! + \brief enable high-driver mode + this bit set by software only when IRC16M or HXTAL used as system clock + \param[in] none + \param[out] none + \retval none +*/ +void pmu_highdriver_mode_enable(void) +{ + PMU_CTL |= PMU_CTL_HDEN; +} + +/*! + \brief disable high-driver mode + \param[in] none + \param[out] none + \retval none +*/ +void pmu_highdriver_mode_disable(void) +{ + PMU_CTL &= ~PMU_CTL_HDEN; +} + +/*! + \brief switch high-driver mode + this bit set by software only when IRC16M or HXTAL used as system clock + \param[in] highdr_switch: + \arg PMU_HIGHDR_SWITCH_NONE: disable high-driver mode switch + \arg PMU_HIGHDR_SWITCH_EN: enable high-driver mode switch + \param[out] none + \retval none +*/ +void pmu_highdriver_switch_select(uint32_t highdr_switch) +{ + /* wait for HDRF flag set */ + while(SET != pmu_flag_get(PMU_FLAG_HDRF)) { + } + PMU_CTL &= ~PMU_CTL_HDS; + PMU_CTL |= highdr_switch; +} + +/*! + \brief enable low-driver mode in deep-sleep + \param[in] none + \param[out] none + \retval none +*/ +void pmu_lowdriver_mode_enable(void) +{ + PMU_CTL |= PMU_CTL_LDEN; +} + +/*! + \brief disable low-driver mode in deep-sleep + \param[in] none + \param[out] none + \retval none +*/ +void pmu_lowdriver_mode_disable(void) +{ + PMU_CTL &= ~PMU_CTL_LDEN; +} + +/*! + \brief in deep-sleep mode, driver mode when use low power LDO + \param[in] mode: + \arg PMU_NORMALDR_LOWPWR: normal driver when use low power LDO + \arg PMU_LOWDR_LOWPWR: low-driver mode enabled when LDEN is 11 and use low power LDO + \param[out] none + \retval none +*/ +void pmu_lowpower_driver_config(uint32_t mode) +{ + PMU_CTL &= ~PMU_CTL_LDLP; + PMU_CTL |= mode; +} + +/*! + \brief in deep-sleep mode, driver mode when use normal power LDO + \param[in] mode: + \arg PMU_NORMALDR_NORMALPWR: normal driver when use normal power LDO + \arg PMU_LOWDR_NORMALPWR: low-driver mode enabled when LDEN is 11 and use normal power LDO + \param[out] none + \retval none +*/ +void pmu_normalpower_driver_config(uint32_t mode) +{ + PMU_CTL &= ~PMU_CTL_LDNP; + PMU_CTL |= mode; +} + +/*! + \brief PMU work in sleep mode + \param[in] sleepmodecmd: + \arg WFI_CMD: use WFI command + \arg WFE_CMD: use WFE command + \param[out] none + \retval none +*/ +void pmu_to_sleepmode(uint8_t sleepmodecmd) +{ + /* clear sleepdeep bit of Cortex-M33 system control register */ + SCB->SCR &= ~((uint32_t)SCB_SCR_SLEEPDEEP_Msk); + + /* select WFI or WFE command to enter sleep mode */ + if(WFI_CMD == sleepmodecmd) { + __WFI(); + } else { + __WFE(); + __WFE(); + } +} + +/*! + \brief PMU work in deep-sleep mode + \param[in] ldo + \arg PMU_LDO_NORMAL: LDO normal work when pmu enter deep-sleep mode + \arg PMU_LDO_LOWPOWER: LDO work at low power mode when pmu enter deep-sleep mode + \param[in] lowdrive: + only one parameter can be selected which is shown as below: + \arg PMU_LOWDRIVER_DISABLE: Low-driver mode disable in deep-sleep mode + \arg PMU_LOWDRIVER_ENABLE: Low-driver mode enable in deep-sleep mode + \param[in] deepsleepmodecmd: + \arg WFI_CMD: use WFI command + \arg WFE_CMD: use WFE command + \param[out] none + \retval none +*/ +void pmu_to_deepsleepmode(uint32_t ldo, uint32_t lowdrive, uint8_t deepsleepmodecmd) +{ + /* clear stbmod and ldolp bits */ + PMU_CTL &= ~((uint32_t)(PMU_CTL_STBMOD | PMU_CTL_LDOLP | PMU_CTL_LDEN | PMU_CTL_LDNP | PMU_CTL_LDLP)); + + /* set ldolp bit according to pmu_ldo */ + PMU_CTL |= ldo; + + /* configure low drive mode in deep-sleep mode */ + if(PMU_LOWDRIVER_ENABLE == lowdrive) { + if(PMU_LDO_NORMAL == ldo) { + PMU_CTL |= (uint32_t)(PMU_CTL_LDEN | PMU_CTL_LDNP); + } else { + PMU_CTL |= (uint32_t)(PMU_CTL_LDEN | PMU_CTL_LDLP); + } + } + /* set sleepdeep bit of Cortex-M33 system control register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; + + /* select WFI or WFE command to enter deep-sleep mode */ + if(WFI_CMD == deepsleepmodecmd) { + __WFI(); + } else { + __SEV(); + __WFE(); + __WFE(); + } + + /* reset sleepdeep bit of Cortex-M33 system control register */ + SCB->SCR &= ~((uint32_t)SCB_SCR_SLEEPDEEP_Msk); +} + +/*! + \brief pmu work in standby mode + \param[in] none + \param[out] none + \retval none +*/ +void pmu_to_standbymode(void) +{ + /* set stbmod bit */ + PMU_CTL |= PMU_CTL_STBMOD; + + /* reset wakeup flag */ + PMU_CTL |= PMU_CTL_WURST; + + /* set sleepdeep bit of Cortex-M33 system control register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; + + REG32(0xE000E010U) &= 0x00010004U; + REG32(0xE000E180U) = 0XFFFFFFF3U; + REG32(0xE000E184U) = 0XFFFFFDFFU; + REG32(0xE000E188U) = 0xFFFFFFFFU; + REG32(0xE000E18CU) = 0xFFFFFFFFU; + + /* select WFI command to enter standby mode */ + __WFI(); +} + +/*! + \brief enable PMU wakeup pin + \param[in] none + \param[out] none + \retval none +*/ +void pmu_wakeup_pin_enable(void) +{ + PMU_CS |= PMU_CS_WUPEN; +} + +/*! + \brief disable PMU wakeup pin + \param[in] none + \param[out] none + \retval none +*/ +void pmu_wakeup_pin_disable(void) +{ + PMU_CS &= ~PMU_CS_WUPEN; +} + +/*! + \brief backup SRAM LDO on + \param[in] bkp_ldo: + \arg PMU_BLDOON_OFF: backup SRAM LDO closed + \arg PMU_BLDOON_ON: open the backup SRAM LDO + \param[out] none + \retval none +*/ +void pmu_backup_ldo_config(uint32_t bkp_ldo) +{ + PMU_CS &= ~PMU_CS_BLDOON; + PMU_CS |= bkp_ldo; +} + +/*! + \brief enable write access to the registers in backup domain + \param[in] none + \param[out] none + \retval none +*/ +void pmu_backup_write_enable(void) +{ + PMU_CTL |= PMU_CTL_BKPWEN; +} + +/*! + \brief disable write access to the registers in backup domain + \param[in] none + \param[out] none + \retval none +*/ +void pmu_backup_write_disable(void) +{ + PMU_CTL &= ~PMU_CTL_BKPWEN; +} + +/*! + \brief get flag state + \param[in] flag: + \arg PMU_FLAG_WAKEUP: wakeup flag + \arg PMU_FLAG_STANDBY: standby flag + \arg PMU_FLAG_LVD: lvd flag + \arg PMU_FLAG_BLDORF: backup SRAM LDO ready flag + \arg PMU_FLAG_LDOVSRF: LDO voltage select ready flag + \arg PMU_FLAG_HDRF: high-driver ready flag + \arg PMU_FLAG_HDSRF: high-driver switch ready flag + \arg PMU_FLAG_LDRF: low-driver mode ready flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus pmu_flag_get(uint32_t flag) +{ + if(PMU_CS & flag) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear flag bit + \param[in] flag: + \arg PMU_FLAG_RESET_WAKEUP: reset wakeup flag + \arg PMU_FLAG_RESET_STANDBY: reset standby flag + \param[out] none + \retval none +*/ +void pmu_flag_clear(uint32_t flag) +{ + switch(flag) { + case PMU_FLAG_RESET_WAKEUP: + /* reset wakeup flag */ + PMU_CTL |= PMU_CTL_WURST; + break; + case PMU_FLAG_RESET_STANDBY: + /* reset standby flag */ + PMU_CTL |= PMU_CTL_STBRST; + break; + default : + break; + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_rcu.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_rcu.c new file mode 100644 index 0000000..71f46a6 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_rcu.c @@ -0,0 +1,1473 @@ +/*! + \file gd32f5xx_rcu.c + \brief RCU driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_rcu.h" + +/* define clock source */ +#define SEL_IRC16M ((uint16_t)0U) /* IRC16M is selected as CK_SYS */ +#define SEL_HXTAL ((uint16_t)1U) /* HXTAL is selected as CK_SYS */ +#define SEL_PLLP ((uint16_t)2U) /* PLLP is selected as CK_SYS */ +/* define startup timeout count */ +#define OSC_STARTUP_TIMEOUT ((uint32_t)0x000fffffU) +#define LXTAL_STARTUP_TIMEOUT ((uint32_t)0x0fffffffU) + +/* RCU IRC16M adjust value mask and offset*/ +#define RCU_IRC16M_ADJUST_MASK ((uint8_t)0x1FU) +#define RCU_IRC16M_ADJUST_OFFSET ((uint32_t)3U) + +/*! + \brief deinitialize the RCU + \param[in] none + \param[out] none + \retval none +*/ +void rcu_deinit(void) +{ + /* enable IRC16M */ + RCU_CTL |= RCU_CTL_IRC16MEN; + rcu_osci_stab_wait(RCU_IRC16M); + RCU_CFG0 &= ~RCU_CFG0_SCS; + + /* reset CTL register */ + RCU_CTL &= ~(RCU_CTL_HXTALEN | RCU_CTL_CKMEN | RCU_CTL_PLLEN | RCU_CTL_PLLI2SEN + | RCU_CTL_PLLSAIEN); + RCU_CTL &= ~(RCU_CTL_HXTALBPS); + /* reset CFG0 register */ + RCU_CFG0 &= ~(RCU_CFG0_SCS | RCU_CFG0_AHBPSC | RCU_CFG0_APB1PSC | RCU_CFG0_APB2PSC | + RCU_CFG0_RTCDIV | RCU_CFG0_CKOUT0SEL | RCU_CFG0_I2SSEL | RCU_CFG0_CKOUT0DIV | + RCU_CFG0_CKOUT1DIV | RCU_CFG0_CKOUT1SEL); + /* reset PLL register */ + RCU_PLL = 0x24003010U; + /* reset PLLI2S register */ + RCU_PLLI2S = 0x24003000U; + /* reset PLLSAI register */ + RCU_PLLSAI = 0x24003010U; + /* reset INT register */ + RCU_INT = 0x00000000U; + /* reset CFG1 register */ + RCU_CFG1 &= ~(RCU_CFG1_PLLSAIRDIV | RCU_CFG1_TIMERSEL); +} + +/*! + \brief enable the peripherals clock + \param[in] periph: RCU peripherals, refer to rcu_periph_enum + only one parameter can be selected which is shown as below: + \arg RCU_GPIOx (x = A, B, C, D, E, F, G, H, I): GPIO ports clock + \arg RCU_CRC: CRC clock + \arg RCU_BKPSRAM: BKPSRAM clock + \arg RCU_TCMSRAM: TCMSRAM clock + \arg RCU_DMAx (x=0,1): DMA clock + \arg RCU_IPA: IPA clock + \arg RCU_ENET: ENET clock + \arg RCU_ENETTX: ENETTX clock + \arg RCU_ENETRX: ENETRX clock + \arg RCU_ENETPTP: ENETPTP clock + \arg RCU_USBHS: USBHS clock + \arg RCU_USBHSULPI: USBHSULPI clock + \arg RCU_DCI: DCI clock + \arg RCU_PKCAU: PKCAU clock + \arg RCU_CAU: CAU clock + \arg RCU_HAU: HAU clock + \arg RCU_TRNG: TRNG clock + \arg RCU_USBFS: USBFS clock + \arg RCU_EXMC: EXMC clock + \arg RCU_TIMERx (x = 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13): TIMER clock + \arg RCU_WWDGT: WWDGT clock + \arg RCU_SPIx (x = 0, 1, 2, 3, 4, 5): SPI clock + \arg RCU_SAI: SAI clock + \arg RCU_USARTx (x = 0, 1, 2, 5): USART clock + \arg RCU_UARTx (x = 3, 4, 6, 7): UART clock + \arg RCU_I2Cx (x = 0, 1, 2, 3, 4, 5): I2C clock + \arg RCU_CANx (x = 0, 1): CAN clock + \arg RCU_PMU: PMU clock + \arg RCU_DAC: DAC clock + \arg RCU_RTC: RTC clock + \arg RCU_ADCx (x = 0, 1, 2): ADC clock + \arg RCU_SDIO: SDIO clock + \arg RCU_SYSCFG: SYSCFG clock + \arg RCU_TLI: TLI clock + \arg RCU_CTC: CTC clock + \arg RCU_IREF: IREF clock + \param[out] none + \retval none +*/ +void rcu_periph_clock_enable(rcu_periph_enum periph) +{ + RCU_REG_VAL(periph) |= BIT(RCU_BIT_POS(periph)); +} + +/*! + \brief disable the peripherals clock + \param[in] periph: RCU peripherals, refer to rcu_periph_enum + only one parameter can be selected which is shown as below: + \arg RCU_GPIOx (x = A, B, C, D, E, F, G, H, I): GPIO ports clock + \arg RCU_CRC: CRC clock + \arg RCU_BKPSRAM: BKPSRAM clock + \arg RCU_TCMSRAM: TCMSRAM clock + \arg RCU_DMAx (x=0,1): DMA clock + \arg RCU_IPA: IPA clock + \arg RCU_ENET: ENET clock + \arg RCU_ENETTX: ENETTX clock + \arg RCU_ENETRX: ENETRX clock + \arg RCU_ENETPTP: ENETPTP clock + \arg RCU_USBHS: USBHS clock + \arg RCU_USBHSULPI: USBHSULPI clock + \arg RCU_DCI: DCI clock + \arg RCU_PKCAU: PKCAU clock + \arg RCU_CAU: CAU clock + \arg RCU_HAU: HAU clock + \arg RCU_TRNG: TRNG clock + \arg RCU_USBFS: USBFS clock + \arg RCU_EXMC: EXMC clock + \arg RCU_TIMERx (x = 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13): TIMER clock + \arg RCU_WWDGT: WWDGT clock + \arg RCU_SPIx (x = 0, 1, 2, 3, 4, 5): SPI clock + \arg RCU_SAI: SAI clock + \arg RCU_USARTx (x = 0, 1, 2, 5): USART clock + \arg RCU_UARTx (x = 3, 4, 6, 7): UART clock + \arg RCU_I2Cx (x = 0, 1, 2, 3, 4, 5): I2C clock + \arg RCU_CANx (x = 0, 1): CAN clock + \arg RCU_PMU: PMU clock + \arg RCU_DAC: DAC clock + \arg RCU_RTC: RTC clock + \arg RCU_ADCx (x = 0, 1, 2): ADC clock + \arg RCU_SDIO: SDIO clock + \arg RCU_SYSCFG: SYSCFG clock + \arg RCU_TLI: TLI clock + \arg RCU_CTC: CTC clock + \arg RCU_IREF: IREF clock + \param[out] none + \retval none +*/ +void rcu_periph_clock_disable(rcu_periph_enum periph) +{ + RCU_REG_VAL(periph) &= ~BIT(RCU_BIT_POS(periph)); +} + +/*! + \brief enable the peripherals clock when sleep mode + \param[in] periph: RCU peripherals, refer to rcu_periph_sleep_enum + only one parameter can be selected which is shown as below: + \arg RCU_GPIOx_SLP (x = A, B, C, D, E, F, G, H, I): GPIO ports clock + \arg RCU_CRC_SLP: CRC clock + \arg RCU_FMC_SLP: FMC clock + \arg RCU_SRAM0_SLP: SRAM0 clock + \arg RCU_SRAM1_SLP: SRAM1 clock + \arg RCU_BKPSRAM: BKPSRAM clock + \arg RCU_SRAM2_SLP: SRAM2 clock + \arg RCU_DMAx_SLP (x=0,1): DMA clock + \arg RCU_IPA_SLP: IPA clock + \arg RCU_ENET_SLP: ENET clock + \arg RCU_ENETTX_SLP: ENETTX clock + \arg RCU_ENETRX_SLP: ENETRX clock + \arg RCU_ENETPTP_SLP: ENETPTP clock + \arg RCU_USBHS_SLP: USBHS clock + \arg RCU_USBHSULPI_SLP: USBHSULPI clock + \arg RCU_DCI_SLP: DCI clock + \arg RCU_PKCAU_SLP: PKCAU clock + \arg RCU_CAU_SLP: CAU clock + \arg RCU_HAU_SLP: HAU clock + \arg RCU_TRNG_SLP: TRNG clock + \arg RCU_USBFS_SLP: USBFS clock + \arg RCU_EXMC_SLP: EXMC clock + \arg RCU_TIMERx_SLP (x = 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13): TIMER clock + \arg RCU_WWDGT_SLP: WWDGT clock + \arg RCU_SPIx_SLP (x = 0, 1, 2, 3, 4, 5): SPI clock + \arg RCU_SAI_SLP: SAI clock + \arg RCU_USARTx_SLP (x = 0, 1, 2, 5): USART clock + \arg RCU_UARTx_SLP (x = 3, 4, 6, 7): UART clock + \arg RCU_I2Cx_SLP (x = 0, 1, 2, 3, 4, 5): I2C clock + \arg RCU_CANx_SLP (x = 0, 1): CAN clock + \arg RCU_PMU_SLP: PMU clock + \arg RCU_DAC_SLP: DAC clock + \arg RCU_RTC_SLP: RTC clock + \arg RCU_ADCx_SLP (x = 0, 1, 2): ADC clock + \arg RCU_SDIO_SLP: SDIO clock + \arg RCU_SYSCFG_SLP: SYSCFG clock + \arg RCU_TLI_SLP: TLI clock + \arg RCU_CTC_SLP: CTC clock + \arg RCU_IREF_SLP: IREF clock + \param[out] none + \retval none +*/ +void rcu_periph_clock_sleep_enable(rcu_periph_sleep_enum periph) +{ + RCU_REG_VAL(periph) |= BIT(RCU_BIT_POS(periph)); +} + +/*! + \brief disable the peripherals clock when sleep mode + \param[in] periph: RCU peripherals, refer to rcu_periph_sleep_enum + only one parameter can be selected which is shown as below: + \arg RCU_GPIOx_SLP (x = A, B, C, D, E, F, G, H, I): GPIO ports clock + \arg RCU_CRC_SLP: CRC clock + \arg RCU_FMC_SLP: FMC clock + \arg RCU_SRAM0_SLP: SRAM0 clock + \arg RCU_SRAM1_SLP: SRAM1 clock + \arg RCU_BKPSRAM: BKPSRAM clock + \arg RCU_SRAM2_SLP: SRAM2 clock + \arg RCU_DMAx_SLP (x=0,1): DMA clock + \arg RCU_IPA_SLP: IPA clock + \arg RCU_ENET_SLP: ENET clock + \arg RCU_ENETTX_SLP: ENETTX clock + \arg RCU_ENETRX_SLP: ENETRX clock + \arg RCU_ENETPTP_SLP: ENETPTP clock + \arg RCU_USBHS_SLP: USBHS clock + \arg RCU_USBHSULPI_SLP: USBHSULPI clock + \arg RCU_DCI_SLP: DCI clock + \arg RCU_PKCAU_SLP: PKCAU clock + \arg RCU_CAU_SLP: CAU clock + \arg RCU_HAU_SLP: HAU clock + \arg RCU_TRNG_SLP: TRNG clock + \arg RCU_USBFS_SLP: USBFS clock + \arg RCU_EXMC_SLP: EXMC clock + \arg RCU_TIMERx_SLP (x = 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13): TIMER clock + \arg RCU_WWDGT_SLP: WWDGT clock + \arg RCU_SPIx_SLP (x = 0, 1, 2, 3, 4, 5): SPI clock + \arg RCU_SAI_SLP: SAI clock + \arg RCU_USARTx_SLP (x = 0, 1, 2, 5): USART clock + \arg RCU_UARTx_SLP (x = 3, 4, 6, 7): UART clock + \arg RCU_I2Cx_SLP (x = 0, 1, 2, 3, 4, 5): I2C clock + \arg RCU_CANx_SLP (x = 0, 1): CAN clock + \arg RCU_PMU_SLP: PMU clock + \arg RCU_DAC_SLP: DAC clock + \arg RCU_RTC_SLP: RTC clock + \arg RCU_ADCx_SLP (x = 0, 1, 2): ADC clock + \arg RCU_SDIO_SLP: SDIO clock + \arg RCU_SYSCFG_SLP: SYSCFG clock + \arg RCU_TLI_SLP: TLI clock + \arg RCU_CTC_SLP: CTC clock + \arg RCU_IREF_SLP: IREF clock + \param[out] none + \retval none +*/ +void rcu_periph_clock_sleep_disable(rcu_periph_sleep_enum periph) +{ + RCU_REG_VAL(periph) &= ~BIT(RCU_BIT_POS(periph)); +} + +/*! + \brief reset the peripherals + \param[in] periph_reset: RCU peripherals reset, refer to rcu_periph_reset_enum + only one parameter can be selected which is shown as below: + \arg RCU_GPIOxRST (x = A, B, C, D, E, F, G, H, I): reset GPIO ports + \arg RCU_CRCRST: reset CRC + \arg RCU_DMAxRST (x=0,1): reset DMA + \arg RCU_IPARST: reset IPA + \arg RCU_ENETRST: reset ENET + \arg RCU_USBHSRST: reset USBHS + \arg RCU_DCIRST: reset DCI + \arg RCU_PKCAURST: reset PKCAU + \arg RCU_CAURST: reset CAU + \arg RCU_HAURST: reset HAU + \arg RCU_TRNGRST: reset TRNG + \arg RCU_USBFSRST: reset USBFS + \arg RCU_EXMCRST: reset EXMC + \arg RCU_TIMERxRST (x = 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13): reset TIMER + \arg RCU_WWDGTRST: reset WWDGT + \arg RCU_SPIxRST (x = 0, 1, 2, 3, 4, 5): reset SPI + \arg RCU_SAIRST (x = 0, 1, 2, 3, 4, 5): reset SAI + \arg RCU_USARTxRST (x = 0, 1, 2, 5): reset USART + \arg RCU_UARTxRST (x = 3, 4, 6, 7): reset UART + \arg RCU_I2CxRST (x = 0, 1, 2, 3, 4, 5): reset I2C + \arg RCU_CANxRST (x = 0, 1): reset CAN + \arg RCU_PMURST: reset PMU + \arg RCU_DACRST: reset DAC + \arg RCU_ADCRST (x = 0, 1, 2): reset ADC + \arg RCU_SDIORST: reset SDIO + \arg RCU_SYSCFGRST: reset SYSCFG + \arg RCU_TLIRST: reset TLI + \arg RCU_CTCRST: reset CTC + \arg RCU_IREFRST: reset IREF + \param[out] none + \retval none +*/ +void rcu_periph_reset_enable(rcu_periph_reset_enum periph_reset) +{ + RCU_REG_VAL(periph_reset) |= BIT(RCU_BIT_POS(periph_reset)); +} + +/*! + \brief disable reset the peripheral + \param[in] periph_reset: RCU peripherals reset, refer to rcu_periph_reset_enum + only one parameter can be selected which is shown as below: + \arg RCU_GPIOxRST (x = A, B, C, D, E, F, G, H, I): reset GPIO ports + \arg RCU_CRCRST: reset CRC + \arg RCU_DMAxRST (x=0,1): reset DMA + \arg RCU_IPARST: reset IPA + \arg RCU_ENETRST: reset ENET + \arg RCU_USBHSRST: reset USBHS + \arg RCU_DCIRST: reset DCI + \arg RCU_PKCAURST: reset PKCAU + \arg RCU_CAURST: reset CAU + \arg RCU_HAURST: reset HAU + \arg RCU_TRNGRST: reset TRNG + \arg RCU_USBFSRST: reset USBFS + \arg RCU_EXMCRST: reset EXMC + \arg RCU_TIMERxRST (x = 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13): reset TIMER + \arg RCU_WWDGTRST: reset WWDGT + \arg RCU_SPIxRST (x = 0, 1, 2, 3, 4, 5): reset SPI + \arg RCU_SAIRST (x = 0, 1, 2, 3, 4, 5): reset SAI + \arg RCU_USARTxRST (x = 0, 1, 2, 5): reset USART + \arg RCU_UARTxRST (x = 3, 4, 6, 7): reset UART + \arg RCU_I2CxRST (x = 0, 1, 2, 3, 4, 5): reset I2C + \arg RCU_CANxRST (x = 0, 1): reset CAN + \arg RCU_PMURST: reset PMU + \arg RCU_DACRST: reset DAC + \arg RCU_ADCRST (x = 0, 1, 2): reset ADC + \arg RCU_SDIORST: reset SDIO + \arg RCU_SYSCFGRST: reset SYSCFG + \arg RCU_TLIRST: reset TLI + \arg RCU_CTCRST: reset CTC + \arg RCU_IREFRST: reset IREF + \param[out] none + \retval none +*/ +void rcu_periph_reset_disable(rcu_periph_reset_enum periph_reset) +{ + RCU_REG_VAL(periph_reset) &= ~BIT(RCU_BIT_POS(periph_reset)); +} + +/*! + \brief reset the BKP + \param[in] none + \param[out] none + \retval none +*/ +void rcu_bkp_reset_enable(void) +{ + RCU_BDCTL |= RCU_BDCTL_BKPRST; +} + +/*! + \brief disable the BKP reset + \param[in] none + \param[out] none + \retval none +*/ +void rcu_bkp_reset_disable(void) +{ + RCU_BDCTL &= ~RCU_BDCTL_BKPRST; +} + +/*! + \brief configure the system clock source + \param[in] ck_sys: system clock source select + only one parameter can be selected which is shown as below: + \arg RCU_CKSYSSRC_IRC16M: select CK_IRC16M as the CK_SYS source + \arg RCU_CKSYSSRC_HXTAL: select CK_HXTAL as the CK_SYS source + \arg RCU_CKSYSSRC_PLLP: select CK_PLLP as the CK_SYS source + \param[out] none + \retval none +*/ +void rcu_system_clock_source_config(uint32_t ck_sys) +{ + uint32_t reg; + + reg = RCU_CFG0; + /* reset the SCS bits and set according to ck_sys */ + reg &= ~RCU_CFG0_SCS; + RCU_CFG0 = (reg | ck_sys); +} + +/*! + \brief get the system clock source + \param[in] none + \param[out] none + \retval which clock is selected as CK_SYS source + \arg RCU_SCSS_IRC16M: CK_IRC16M is selected as the CK_SYS source + \arg RCU_SCSS_HXTAL: CK_HXTAL is selected as the CK_SYS source + \arg RCU_SCSS_PLLP: CK_PLLP is selected as the CK_SYS source +*/ +uint32_t rcu_system_clock_source_get(void) +{ + return (RCU_CFG0 & RCU_CFG0_SCSS); +} + +/*! + \brief configure the AHB clock prescaler selection + \param[in] ck_ahb: AHB clock prescaler selection + only one parameter can be selected which is shown as below: + \arg RCU_AHB_CKSYS_DIVx (x = 1, 2, 4, 8, 16, 64, 128, 256, 512): select CK_SYS / x as CK_AHB + \param[out] none + \retval none +*/ +void rcu_ahb_clock_config(uint32_t ck_ahb) +{ + uint32_t reg; + + reg = RCU_CFG0; + /* reset the AHBPSC bits and set according to ck_ahb */ + reg &= ~RCU_CFG0_AHBPSC; + RCU_CFG0 = (reg | ck_ahb); +} + +/*! + \brief configure the APB1 clock prescaler selection + \param[in] ck_apb1: APB1 clock prescaler selection + only one parameter can be selected which is shown as below: + \arg RCU_APB1_CKAHB_DIV1: select CK_AHB as CK_APB1 + \arg RCU_APB1_CKAHB_DIV2: select CK_AHB / 2 as CK_APB1 + \arg RCU_APB1_CKAHB_DIV4: select CK_AHB / 4 as CK_APB1 + \arg RCU_APB1_CKAHB_DIV8: select CK_AHB / 8 as CK_APB1 + \arg RCU_APB1_CKAHB_DIV16: select CK_AHB / 16 as CK_APB1 + \param[out] none + \retval none +*/ +void rcu_apb1_clock_config(uint32_t ck_apb1) +{ + uint32_t reg; + + reg = RCU_CFG0; + /* reset the APB1PSC and set according to ck_apb1 */ + reg &= ~RCU_CFG0_APB1PSC; + RCU_CFG0 = (reg | ck_apb1); +} + +/*! + \brief configure the APB2 clock prescaler selection + \param[in] ck_apb2: APB2 clock prescaler selection + only one parameter can be selected which is shown as below: + \arg RCU_APB2_CKAHB_DIV1: select CK_AHB as CK_APB2 + \arg RCU_APB2_CKAHB_DIV2: select CK_AHB / 2 as CK_APB2 + \arg RCU_APB2_CKAHB_DIV4: select CK_AHB / 4 as CK_APB2 + \arg RCU_APB2_CKAHB_DIV8: select CK_AHB / 8 as CK_APB2 + \arg RCU_APB2_CKAHB_DIV16: select CK_AHB / 16 as CK_APB2 + \param[out] none + \retval none +*/ +void rcu_apb2_clock_config(uint32_t ck_apb2) +{ + uint32_t reg; + + reg = RCU_CFG0; + /* reset the APB2PSC and set according to ck_apb2 */ + reg &= ~RCU_CFG0_APB2PSC; + RCU_CFG0 = (reg | ck_apb2); +} + +/*! + \brief configure the CK_OUT0 clock source and divider + \param[in] ckout0_src: CK_OUT0 clock source selection + only one parameter can be selected which is shown as below: + \arg RCU_CKOUT0SRC_IRC16M: IRC16M selected + \arg RCU_CKOUT0SRC_LXTAL: LXTAL selected + \arg RCU_CKOUT0SRC_HXTAL: HXTAL selected + \arg RCU_CKOUT0SRC_PLLP: PLLP selected + \param[in] ckout0_div: CK_OUT0 divider + \arg RCU_CKOUT0_DIVx(x = 1, 2, 3, 4, 5): CK_OUT0 is divided by x + \param[out] none + \retval none +*/ +void rcu_ckout0_config(uint32_t ckout0_src, uint32_t ckout0_div) +{ + uint32_t reg; + + reg = RCU_CFG0; + /* reset the CKOUT0SRC, CKOUT0DIV and set according to ckout0_src and ckout0_div */ + reg &= ~(RCU_CFG0_CKOUT0SEL | RCU_CFG0_CKOUT0DIV); + RCU_CFG0 = (reg | ckout0_src | ckout0_div); +} + +/*! + \brief configure the CK_OUT1 clock source and divider + \param[in] ckout1_src: CK_OUT1 clock source selection + only one parameter can be selected which is shown as below: + \arg RCU_CKOUT1SRC_SYSTEMCLOCK: system clock selected + \arg RCU_CKOUT1SRC_PLLI2SR: PLLI2SR selected + \arg RCU_CKOUT1SRC_HXTAL: HXTAL selected + \arg RCU_CKOUT1SRC_PLLP: PLLP selected + \param[in] ckout1_div: CK_OUT1 divider + \arg RCU_CKOUT1_DIVx(x = 1, 2, 3, 4, 5): CK_OUT1 is divided by x + \param[out] none + \retval none +*/ +void rcu_ckout1_config(uint32_t ckout1_src, uint32_t ckout1_div) +{ + uint32_t reg; + + reg = RCU_CFG0; + /* reset the CKOUT1SRC, CKOUT1DIV and set according to ckout1_src and ckout1_div */ + reg &= ~(RCU_CFG0_CKOUT1SEL | RCU_CFG0_CKOUT1DIV); + RCU_CFG0 = (reg | ckout1_src | ckout1_div); +} + +/*! + \brief configure the main PLL clock + \param[in] pll_src: PLL clock source selection + \arg RCU_PLLSRC_IRC16M: select IRC16M as PLL source clock + \arg RCU_PLLSRC_HXTAL: select HXTAL as PLL source clock + \param[in] pll_psc: the PLL VCO source clock prescaler + \arg this parameter should be selected between 2 and 63 + \param[in] pll_n: the PLL VCO clock multi factor + \arg this parameter should be selected between 64 and 500 + \param[in] pll_p: the PLLP output frequency division factor from PLL VCO clock + \arg this parameter should be selected 2,4,6,8 + \param[in] pll_q: the PLL Q output frequency division factor from PLL VCO clock + \arg this parameter should be selected between 2 and 15 + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus rcu_pll_config(uint32_t pll_src, uint32_t pll_psc, uint32_t pll_n, uint32_t pll_p, uint32_t pll_q) +{ + uint32_t ss_modulation_inc; + uint32_t ss_modulation_reg; + + ss_modulation_inc = 0U; + ss_modulation_reg = RCU_PLLSSCTL; + + /* calculate the minimum factor of PLLN */ + if((ss_modulation_reg & RCU_PLLSSCTL_SSCGON) == RCU_PLLSSCTL_SSCGON) { + if((ss_modulation_reg & RCU_SS_TYPE_DOWN) == RCU_SS_TYPE_DOWN) { + ss_modulation_inc += RCU_SS_MODULATION_DOWN_INC; + } else { + ss_modulation_inc += RCU_SS_MODULATION_CENTER_INC; + } + } + + /* check the function parameter */ + if(CHECK_PLL_PSC_VALID(pll_psc) && CHECK_PLL_N_VALID(pll_n, ss_modulation_inc) && + CHECK_PLL_P_VALID(pll_p) && CHECK_PLL_Q_VALID(pll_q)) { + RCU_PLL = pll_psc | (pll_n << 6) | (((pll_p >> 1) - 1U) << 16) | + (pll_src) | (pll_q << 24); + } else { + /* return status */ + return ERROR; + } + + /* return status */ + return SUCCESS; +} + +/*! + \brief configure the PLLI2S_Q clock + \param[in] plli2s_n: the PLLI2S VCO clock multi factor + \arg this parameter should be selected between 50 and 500 + \param[in] plli2s_q: the PLLI2S Q output frequency division factor from PLLI2S VCO clock + \arg this parameter should be selected between 2 and 15 + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus rcu_plli2s_q_config(uint32_t plli2s_n, uint32_t plli2s_q) +{ + /* check the function parameter */ + if(CHECK_PLLI2S_N_VALID(plli2s_n) && CHECK_PLLI2S_Q_VALID(plli2s_q)) { + RCU_PLLI2S = (plli2s_n << 6) | (plli2s_q << 24); + } else { + /* return status */ + return ERROR; + } + + /* return status */ + return SUCCESS; +} + +/*! + \brief configure the PLLI2S_R clock + \param[in] plli2s_n: the PLLI2S VCO clock multi factor + \arg this parameter should be selected between 50 and 500 + \param[in] plli2s_r: the PLLI2S R output frequency division factor from PLLI2S VCO clock + \arg this parameter should be selected between 2 and 7 + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus rcu_plli2s_r_config(uint32_t plli2s_n, uint32_t plli2s_r) +{ + /* check the function parameter */ + if(CHECK_PLLI2S_N_VALID(plli2s_n) && CHECK_PLLI2S_R_VALID(plli2s_r)) { + RCU_PLLI2S = (plli2s_n << 6) | (plli2s_r << 28); + } else { + /* return status */ + return ERROR; + } + + /* return status */ + return SUCCESS; +} + +/*! + \brief configure the PLLSAI_P clock + \param[in] pllsai_n: the PLLSAI VCO clock multi factor + \arg this parameter should be selected between 50 and 500 + \param[in] pllsai_p: the PLLSAI P output frequency division factor from PLL VCO clock + \arg this parameter should be selected 2,4,6,8 + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus rcu_pllsai_p_config(uint32_t pllsai_n, uint32_t pllsai_p) +{ + /* check the function parameter */ + if(CHECK_PLLSAI_N_VALID(pllsai_n) && CHECK_PLLSAI_P_VALID(pllsai_p)) { + RCU_PLLSAI = (pllsai_n << 6U) | (((pllsai_p >> 1U) - 1U) << 16U); + } else { + /* return status */ + return ERROR; + } + + /* return status */ + return SUCCESS; +} + +/*! + \brief configure the PLLSAI_Q clock + \param[in] pllsai_n: the PLLSAI VCO clock multi factor + \arg this parameter should be selected between 50 and 500 + \param[in] pllsai_q: the PLLSAI Q output frequency division factor from PLL VCO clock + \arg this parameter should be selected between 2 and 15 + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus rcu_pllsai_q_config(uint32_t pllsai_n, uint32_t pllsai_q) +{ + /* check the function parameter */ + if(CHECK_PLLSAI_N_VALID(pllsai_n) && CHECK_PLLSAI_Q_VALID(pllsai_q)) { + RCU_PLLSAI = (pllsai_n << 6U) | (pllsai_q << 24U); + } else { + /* return status */ + return ERROR; + } + + /* return status */ + return SUCCESS; +} + +/*! + \brief configure the PLLSAI_R clock + \param[in] pllsai_n: the PLLSAI VCO clock multi factor + \arg this parameter should be selected between 50 and 500 + \param[in] pllsai_r: the PLLSAI R output frequency division factor from PLL VCO clock + \arg this parameter should be selected between 2 and 7 + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus rcu_pllsai_r_config(uint32_t pllsai_n, uint32_t pllsai_r) +{ + /* check the function parameter */ + if(CHECK_PLLSAI_N_VALID(pllsai_n) && CHECK_PLLSAI_R_VALID(pllsai_r)) { + RCU_PLLSAI = (pllsai_n << 6U) | (pllsai_r << 28U); + } else { + /* return status */ + return ERROR; + } + + /* return status */ + return SUCCESS; +} + +/*! + \brief configure the RTC clock source selection + \param[in] rtc_clock_source: RTC clock source selection + only one parameter can be selected which is shown as below: + \arg RCU_RTCSRC_NONE: no clock selected + \arg RCU_RTCSRC_LXTAL: CK_LXTAL selected as RTC source clock + \arg RCU_RTCSRC_IRC32K: CK_IRC32K selected as RTC source clock + \arg RCU_RTCSRC_HXTAL_DIV_RTCDIV: CK_HXTAL / RTCDIV selected as RTC source clock + \param[out] none + \retval none +*/ +void rcu_rtc_clock_config(uint32_t rtc_clock_source) +{ + uint32_t reg; + + reg = RCU_BDCTL; + /* reset the RTCSRC bits and set according to rtc_clock_source */ + reg &= ~RCU_BDCTL_RTCSRC; + RCU_BDCTL = (reg | rtc_clock_source); +} + +/*! + \brief configure the frequency division of RTC clock when HXTAL was selected as its clock source + \param[in] rtc_div: RTC clock frequency division + only one parameter can be selected which is shown as below: + \arg RCU_RTC_HXTAL_NONE: no clock for RTC + \arg RCU_RTC_HXTAL_DIVx: RTCDIV clock select CK_HXTAL / x, x = 2....31 + \param[out] none + \retval none +*/ +void rcu_rtc_div_config(uint32_t rtc_div) +{ + uint32_t reg; + + reg = RCU_CFG0; + /* reset the RTCDIV bits and set according to rtc_div value */ + reg &= ~RCU_CFG0_RTCDIV; + RCU_CFG0 = (reg | rtc_div); +} + + +/*! + \brief configure the I2S clock source selection + \param[in] i2s_clock_source: I2S clock source selection + only one parameter can be selected which is shown as below: + \arg RCU_I2SSRC_PLLI2S: CK_PLLI2S selected as I2S source clock + \arg RCU_I2SSRC_I2S_CKIN: external i2s_ckin pin selected as I2S source clock + \param[out] none + \retval none +*/ +void rcu_i2s_clock_config(uint32_t i2s_clock_source) +{ + uint32_t reg; + + reg = RCU_CFG0; + /* reset the I2SSEL bit and set according to i2s_clock_source */ + reg &= ~RCU_CFG0_I2SSEL; + RCU_CFG0 = (reg | i2s_clock_source); +} + +/*! + \brief configure the I2Cx(x=3,4,5) clock source selection + \param[in] i2c_idx: IDX_I2Cx(x=3,4,5) + \param[in] ck_i2c: I2C clock source selection + only one parameter can be selected which is shown as below: + \arg RCU_I2CSRC_CKAPB1: CK_I2C select CK_APB1 + \arg RCU_I2CSRC_PLLSAIR: CK_I2C select CK_PLLSAIR + \arg RCU_I2CSRC_IRC16M: CK_I2C select IRC16M + \param[out] none + \retval none +*/ +void rcu_i2c_clock_config(i2c_idx_enum i2c_idx, uint32_t ck_i2c) +{ + switch(i2c_idx) { + case IDX_I2C3: + /* reset the I2C3SEL bits and set according to ck_i2c */ + RCU_CFG2 &= ~RCU_CFG2_I2C3SEL; + RCU_CFG2 |= ck_i2c; + break; + case IDX_I2C4: + /* reset the I2C4SEL bits and set according to ck_i2c */ + RCU_CFG2 &= ~RCU_CFG2_I2C4SEL; + RCU_CFG2 |= (uint32_t)ck_i2c << 2U; + break; + case IDX_I2C5: + /* reset the I2C5SEL bits and set according to ck_i2c */ + RCU_CFG2 &= ~RCU_CFG2_I2C5SEL; + RCU_CFG2 |= (uint32_t)ck_i2c << 4U; + break; + default: + break; + } +} + +/*! + \brief configure the SAI clock source selection + \param[in] sai_clock_source: SAI clock source selection + only one parameter can be selected which is shown as below: + \arg RCU_SAISRC_PLLSAIQ: CK_PLLSAIQ selected as SAI source clock + \arg RCU_SAISRC_PLLI2SQ: CK_PLLI2SQ selected as SAI source clock + \arg RCU_SAISRC_I2S_CKIN: CK_I2S_CKIN selected as SAI source clock + \param[out] none + \retval none +*/ +void rcu_sai_clock_config(uint32_t sai_clock_source) +{ + + uint32_t reg; + + reg = RCU_CFG1; + /* reset the SAISEL bit and set according to sai_clock_source */ + reg &= ~RCU_CFG1_SAISEL; + RCU_CFG1 = (reg | sai_clock_source); +} + +/*! + \brief configure the CK48M clock source selection + \param[in] ck48m_clock_source: CK48M clock source selection + only one parameter can be selected which is shown as below: + \arg RCU_CK48MSRC_PLL48M: CK_PLL48M selected as CK48M source clock + \arg RCU_CK48MSRC_IRC48M: CK_IRC48M selected as CK48M source clock + \param[out] none + \retval none +*/ +void rcu_ck48m_clock_config(uint32_t ck48m_clock_source) +{ + uint32_t reg; + + reg = RCU_ADDCTL; + /* reset the CK48MSEL bit and set according to i2s_clock_source */ + reg &= ~RCU_ADDCTL_CK48MSEL; + RCU_ADDCTL = (reg | ck48m_clock_source); +} + +/*! + \brief configure the PLL48M clock source selection + \param[in] pll48m_clock_source: PLL48M clock source selection + only one parameter can be selected which is shown as below: + \arg RCU_PLL48MSRC_PLLQ: CK_PLLQ selected as PLL48M source clock + \arg RCU_PLL48MSRC_PLLSAIP: CK_PLLSAIP selected as PLL48M source clock + \param[out] none + \retval none +*/ +void rcu_pll48m_clock_config(uint32_t pll48m_clock_source) +{ + uint32_t reg; + + reg = RCU_ADDCTL; + /* reset the PLL48MSEL bit and set according to pll48m_clock_source */ + reg &= ~RCU_ADDCTL_PLL48MSEL; + RCU_ADDCTL = (reg | pll48m_clock_source); +} + +/*! + \brief configure the TIMER clock prescaler selection + \param[in] timer_clock_prescaler: TIMER clock selection + only one parameter can be selected which is shown as below: + \arg RCU_TIMER_PSC_MUL2: if APB1PSC/APB2PSC in RCU_CFG0 register is 0b0xx(CK_APBx = CK_AHB) + or 0b100(CK_APBx = CK_AHB/2), the TIMER clock is equal to CK_AHB(CK_TIMERx = CK_AHB). + or else, the TIMER clock is twice the corresponding APB clock (TIMER in APB1 domain: CK_TIMERx = 2 x CK_APB1; + TIMER in APB2 domain: CK_TIMERx = 2 x CK_APB2) + \arg RCU_TIMER_PSC_MUL4: if APB1PSC/APB2PSC in RCU_CFG0 register is 0b0xx(CK_APBx = CK_AHB), + 0b100(CK_APBx = CK_AHB/2), or 0b101(CK_APBx = CK_AHB/4), the TIMER clock is equal to CK_AHB(CK_TIMERx = CK_AHB). + or else, the TIMER clock is four timers the corresponding APB clock (TIMER in APB1 domain: CK_TIMERx = 4 x CK_APB1; + TIMER in APB2 domain: CK_TIMERx = 4 x CK_APB2) + \param[out] none + \retval none +*/ +void rcu_timer_clock_prescaler_config(uint32_t timer_clock_prescaler) +{ + /* configure the TIMERSEL bit and select the TIMER clock prescaler */ + if(timer_clock_prescaler == RCU_TIMER_PSC_MUL2) { + RCU_CFG1 &= timer_clock_prescaler; + } else { + RCU_CFG1 |= timer_clock_prescaler; + } +} + +/*! + \brief configure the PLLSAIR divider used as input of TLI + \param[in] pllsai_r_div: PLLSAIR divider used as input of TLI + only one parameter can be selected which is shown as below: + \arg RCU_PLLSAIR_DIVx(x=2,4,8,16): PLLSAIR divided x used as input of TLI + \param[out] none + \retval none +*/ +void rcu_tli_clock_div_config(uint32_t pllsai_r_div) +{ + uint32_t reg; + + reg = RCU_CFG1; + /* reset the PLLSAIRDIV bit and set according to pllsai_r_div */ + reg &= ~RCU_CFG1_PLLSAIRDIV; + RCU_CFG1 = (reg | pllsai_r_div); +} + +/*! + \brief configure the LXTAL drive capability + \param[in] lxtal_dricap: drive capability of LXTAL + only one parameter can be selected which is shown as below: + \arg RCU_LXTALDRI_LOWER_DRIVE: lower driving capability + \arg RCU_LXTALDRI_HIGHER_DRIVE: higher driving capability + \param[out] none + \retval none +*/ +void rcu_lxtal_drive_capability_config(uint32_t lxtal_dricap) +{ + uint32_t reg; + + reg = RCU_BDCTL; + + /* reset the LXTALDRI bits and set according to lxtal_dricap */ + reg &= ~RCU_BDCTL_LXTALDRI; + RCU_BDCTL = (reg | lxtal_dricap); +} + +/*! + \brief wait for oscillator stabilization flags is SET or oscillator startup is timeout + \param[in] osci: oscillator types, refer to rcu_osci_type_enum + only one parameter can be selected which is shown as below: + \arg RCU_HXTAL: HXTAL + \arg RCU_LXTAL: LXTAL + \arg RCU_IRC16M: IRC16M + \arg RCU_IRC48M: IRC48M + \arg RCU_IRC32K: IRC32K + \arg RCU_PLL_CK: PLL + \arg RCU_PLLI2S_CK: PLLI2S + \arg RCU_PLLSAI_CK: PLLSAI + \param[out] none + \retval ErrStatus: SUCCESS or ERROR +*/ +ErrStatus rcu_osci_stab_wait(rcu_osci_type_enum osci) +{ + uint32_t stb_cnt = 0U; + ErrStatus reval = ERROR; + FlagStatus osci_stat = RESET; + + switch(osci) { + /* wait HXTAL stable */ + case RCU_HXTAL: + while((RESET == osci_stat) && (HXTAL_STARTUP_TIMEOUT != stb_cnt)) { + osci_stat = rcu_flag_get(RCU_FLAG_HXTALSTB); + stb_cnt++; + } + + /* check whether flag is set */ + if(RESET != rcu_flag_get(RCU_FLAG_HXTALSTB)) { + reval = SUCCESS; + } + break; + /* wait LXTAL stable */ + case RCU_LXTAL: + while((RESET == osci_stat) && (LXTAL_STARTUP_TIMEOUT != stb_cnt)) { + osci_stat = rcu_flag_get(RCU_FLAG_LXTALSTB); + stb_cnt++; + } + + /* check whether flag is set */ + if(RESET != rcu_flag_get(RCU_FLAG_LXTALSTB)) { + reval = SUCCESS; + } + break; + /* wait IRC16M stable */ + case RCU_IRC16M: + while((RESET == osci_stat) && (IRC16M_STARTUP_TIMEOUT != stb_cnt)) { + osci_stat = rcu_flag_get(RCU_FLAG_IRC16MSTB); + stb_cnt++; + } + + /* check whether flag is set */ + if(RESET != rcu_flag_get(RCU_FLAG_IRC16MSTB)) { + reval = SUCCESS; + } + break; + /* wait IRC48M stable */ + case RCU_IRC48M: + while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) { + osci_stat = rcu_flag_get(RCU_FLAG_IRC48MSTB); + stb_cnt++; + } + + /* check whether flag is set */ + if(RESET != rcu_flag_get(RCU_FLAG_IRC48MSTB)) { + reval = SUCCESS; + } + break; + /* wait IRC32K stable */ + case RCU_IRC32K: + while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) { + osci_stat = rcu_flag_get(RCU_FLAG_IRC32KSTB); + stb_cnt++; + } + + /* check whether flag is set */ + if(RESET != rcu_flag_get(RCU_FLAG_IRC32KSTB)) { + reval = SUCCESS; + } + break; + /* wait PLL stable */ + case RCU_PLL_CK: + while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) { + osci_stat = rcu_flag_get(RCU_FLAG_PLLSTB); + stb_cnt++; + } + + /* check whether flag is set */ + if(RESET != rcu_flag_get(RCU_FLAG_PLLSTB)) { + reval = SUCCESS; + } + break; + /* wait PLLI2S stable */ + case RCU_PLLI2S_CK: + while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) { + osci_stat = rcu_flag_get(RCU_FLAG_PLLI2SSTB); + stb_cnt++; + } + + /* check whether flag is set */ + if(RESET != rcu_flag_get(RCU_FLAG_PLLI2SSTB)) { + reval = SUCCESS; + } + break; + /* wait PLLSAI stable */ + case RCU_PLLSAI_CK: + while((RESET == osci_stat) && (OSC_STARTUP_TIMEOUT != stb_cnt)) { + osci_stat = rcu_flag_get(RCU_FLAG_PLLSAISTB); + stb_cnt++; + } + + /* check whether flag is set */ + if(RESET != rcu_flag_get(RCU_FLAG_PLLSAISTB)) { + reval = SUCCESS; + } + break; + + default: + break; + } + + /* return value */ + return reval; +} + +/*! + \brief turn on the oscillator + \param[in] osci: oscillator types, refer to rcu_osci_type_enum + only one parameter can be selected which is shown as below: + \arg RCU_HXTAL: HXTAL + \arg RCU_LXTAL: LXTAL + \arg RCU_IRC16M: IRC16M + \arg RCU_IRC48M: IRC48M + \arg RCU_IRC32K: IRC32K + \arg RCU_PLL_CK: PLL + \arg RCU_PLLI2S_CK: PLLI2S + \arg RCU_PLLSAI_CK: PLLSAI + \param[out] none + \retval none +*/ +void rcu_osci_on(rcu_osci_type_enum osci) +{ + RCU_REG_VAL(osci) |= BIT(RCU_BIT_POS(osci)); +} + +/*! + \brief turn off the oscillator + \param[in] osci: oscillator types, refer to rcu_osci_type_enum + only one parameter can be selected which is shown as below: + \arg RCU_HXTAL: HXTAL + \arg RCU_LXTAL: LXTAL + \arg RCU_IRC16M: IRC16M + \arg RCU_IRC48M: IRC48M + \arg RCU_IRC32K: IRC32K + \arg RCU_PLL_CK: PLL + \arg RCU_PLLI2S_CK: PLLI2S + \arg RCU_PLLSAI_CK: PLLSAI + \param[out] none + \retval none +*/ +void rcu_osci_off(rcu_osci_type_enum osci) +{ + RCU_REG_VAL(osci) &= ~BIT(RCU_BIT_POS(osci)); +} + +/*! + \brief enable the oscillator bypass mode, HXTALEN or LXTALEN must be reset before it + \param[in] osci: oscillator types, refer to rcu_osci_type_enum + only one parameter can be selected which is shown as below: + \arg RCU_HXTAL: high speed crystal oscillator(HXTAL) + \arg RCU_LXTAL: low speed crystal oscillator(LXTAL) + \param[out] none + \retval none +*/ +void rcu_osci_bypass_mode_enable(rcu_osci_type_enum osci) +{ + uint32_t reg; + + switch(osci) { + /* enable HXTAL to bypass mode */ + case RCU_HXTAL: + reg = RCU_CTL; + RCU_CTL &= ~RCU_CTL_HXTALEN; + RCU_CTL = (reg | RCU_CTL_HXTALBPS); + break; + /* enable LXTAL to bypass mode */ + case RCU_LXTAL: + reg = RCU_BDCTL; + RCU_BDCTL &= ~RCU_BDCTL_LXTALEN; + RCU_BDCTL = (reg | RCU_BDCTL_LXTALBPS); + break; + case RCU_IRC16M: + case RCU_IRC48M: + case RCU_IRC32K: + case RCU_PLL_CK: + case RCU_PLLI2S_CK: + case RCU_PLLSAI_CK: + break; + default: + break; + } +} + +/*! + \brief disable the oscillator bypass mode, HXTALEN or LXTALEN must be reset before it + \param[in] osci: oscillator types, refer to rcu_osci_type_enum + only one parameter can be selected which is shown as below: + \arg RCU_HXTAL: high speed crystal oscillator(HXTAL) + \arg RCU_LXTAL: low speed crystal oscillator(LXTAL) + \param[out] none + \retval none +*/ +void rcu_osci_bypass_mode_disable(rcu_osci_type_enum osci) +{ + uint32_t reg; + + switch(osci) { + /* disable HXTAL to bypass mode */ + case RCU_HXTAL: + reg = RCU_CTL; + RCU_CTL &= ~RCU_CTL_HXTALEN; + RCU_CTL = (reg & ~RCU_CTL_HXTALBPS); + break; + /* disable LXTAL to bypass mode */ + case RCU_LXTAL: + reg = RCU_BDCTL; + RCU_BDCTL &= ~RCU_BDCTL_LXTALEN; + RCU_BDCTL = (reg & ~RCU_BDCTL_LXTALBPS); + break; + case RCU_IRC16M: + case RCU_IRC48M: + case RCU_IRC32K: + case RCU_PLL_CK: + case RCU_PLLI2S_CK: + case RCU_PLLSAI_CK: + break; + default: + break; + } +} + +/*! + \brief set the IRC16M adjust value + \param[in] irc16m_adjval: IRC16M adjust value, must be between 0 and 0x1F + \arg 0x00 - 0x1F + \param[out] none + \retval none +*/ +void rcu_irc16m_adjust_value_set(uint32_t irc16m_adjval) +{ + uint32_t reg; + + reg = RCU_CTL; + /* reset the IRC16MADJ bits and set according to irc16m_adjval */ + reg &= ~RCU_CTL_IRC16MADJ; + RCU_CTL = (reg | ((irc16m_adjval & RCU_IRC16M_ADJUST_MASK) << RCU_IRC16M_ADJUST_OFFSET)); +} + +/*! + \brief configure the spread spectrum modulation for the main PLL clock + \param[in] spread_spectrum_type: PLL spread spectrum modulation type select + \arg RCU_SS_TYPE_CENTER: center spread type is selected + \arg RCU_SS_TYPE_DOWN: down spread type is selected + \param[in] modstep: configure PLL spread spectrum modulation profile amplitude and frequency + \arg This parameter should be selected between 0 and 7FFF.The following criteria must be met: MODSTEP*MODCNT <=2^15-1 + \param[in] modcnt: configure PLL spread spectrum modulation profile amplitude and frequency + \arg This parameter should be selected between 0 and 1FFF.The following criteria must be met: MODSTEP*MODCNT <=2^15-1 + \param[out] none + \retval none +*/ +void rcu_spread_spectrum_config(uint32_t spread_spectrum_type, uint32_t modstep, uint32_t modcnt) +{ + uint32_t reg; + + reg = RCU_PLLSSCTL; + /* reset the RCU_PLLSSCTL register bits */ + reg &= ~(RCU_PLLSSCTL_MODCNT | RCU_PLLSSCTL_MODSTEP | RCU_PLLSSCTL_SS_TYPE); + RCU_PLLSSCTL = (reg | spread_spectrum_type | modstep << 13 | modcnt); +} + +/*! + \brief enable the spread spectrum modulation for the main PLL clock + \param[in] none + \param[out] none + \retval none +*/ +void rcu_spread_spectrum_enable(void) +{ + RCU_PLLSSCTL |= RCU_PLLSSCTL_SSCGON; +} + +/*! + \brief disable the spread spectrum modulation for the main PLL clock + \param[in] none + \param[out] none + \retval none +*/ +void rcu_spread_spectrum_disable(void) +{ + RCU_PLLSSCTL &= ~RCU_PLLSSCTL_SSCGON; +} + +/*! + \brief enable the HXTAL clock monitor + \param[in] none + \param[out] none + \retval none +*/ +void rcu_hxtal_clock_monitor_enable(void) +{ + RCU_CTL |= RCU_CTL_CKMEN; +} + +/*! + \brief disable the HXTAL clock monitor + \param[in] none + \param[out] none + \retval none +*/ +void rcu_hxtal_clock_monitor_disable(void) +{ + RCU_CTL &= ~RCU_CTL_CKMEN; +} + +/*! + \brief unlock the voltage key + \param[in] none + \param[out] none + \retval none +*/ +void rcu_voltage_key_unlock(void) +{ + RCU_VKEY = RCU_VKEY_UNLOCK; +} + +/*! + \brief set the deep sleep mode voltage + \param[in] dsvol: deep sleep mode voltage + only one parameter can be selected which is shown as below: + \arg RCU_DEEPSLEEP_V_0: the core voltage is default value + \arg RCU_DEEPSLEEP_V_1: the core voltage is (default value-0.1)V(customers are not recommended to use it) + \arg RCU_DEEPSLEEP_V_2: the core voltage is (default value-0.2)V(customers are not recommended to use it) + \arg RCU_DEEPSLEEP_V_3: the core voltage is (default value-0.3)V(customers are not recommended to use it) + \param[out] none + \retval none +*/ +void rcu_deepsleep_voltage_set(uint32_t dsvol) +{ + dsvol &= RCU_DSV_DSLPVS; + RCU_DSV = dsvol; +} + +/*! + \brief get the system clock, bus and peripheral clock frequency + \param[in] clock: the clock frequency which to get + only one parameter can be selected which is shown as below: + \arg CK_SYS: system clock frequency + \arg CK_AHB: AHB clock frequency + \arg CK_APB1: APB1 clock frequency + \arg CK_APB2: APB2 clock frequency + \param[out] none + \retval clock frequency of system, AHB, APB1, APB2 +*/ +uint32_t rcu_clock_freq_get(rcu_clock_freq_enum clock) +{ + uint32_t sws, ck_freq = 0U; + uint32_t cksys_freq, ahb_freq, apb1_freq, apb2_freq; + uint32_t pllpsc, plln, pllsel, pllp, ck_src, idx, clk_exp; + + /* exponent of AHB, APB1 and APB2 clock divider */ + const uint8_t ahb_exp[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + const uint8_t apb1_exp[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + const uint8_t apb2_exp[8] = {0, 0, 0, 0, 1, 2, 3, 4}; + + sws = GET_BITS(RCU_CFG0, 2, 3); + switch(sws) { + /* IRC16M is selected as CK_SYS */ + case SEL_IRC16M: + cksys_freq = IRC16M_VALUE; + break; + /* HXTAL is selected as CK_SYS */ + case SEL_HXTAL: + cksys_freq = HXTAL_VALUE; + break; + /* PLLP is selected as CK_SYS */ + case SEL_PLLP: + /* get the value of PLLPSC[5:0] */ + pllpsc = GET_BITS(RCU_PLL, 0U, 5U); + plln = GET_BITS(RCU_PLL, 6U, 14U); + pllp = (GET_BITS(RCU_PLL, 16U, 17U) + 1U) * 2U; + /* PLL clock source selection, HXTAL or IRC16M/2 */ + pllsel = (RCU_PLL & RCU_PLL_PLLSEL); + if(RCU_PLLSRC_HXTAL == pllsel) { + ck_src = HXTAL_VALUE; + } else { + ck_src = IRC16M_VALUE; + } + cksys_freq = ((ck_src / pllpsc) * plln) / pllp; + break; + /* IRC16M is selected as CK_SYS */ + default: + cksys_freq = IRC16M_VALUE; + break; + } + /* calculate AHB clock frequency */ + idx = GET_BITS(RCU_CFG0, 4, 7); + clk_exp = ahb_exp[idx]; + ahb_freq = cksys_freq >> clk_exp; + + /* calculate APB1 clock frequency */ + idx = GET_BITS(RCU_CFG0, 10, 12); + clk_exp = apb1_exp[idx]; + apb1_freq = ahb_freq >> clk_exp; + + /* calculate APB2 clock frequency */ + idx = GET_BITS(RCU_CFG0, 13, 15); + clk_exp = apb2_exp[idx]; + apb2_freq = ahb_freq >> clk_exp; + + /* return the clocks frequency */ + switch(clock) { + case CK_SYS: + ck_freq = cksys_freq; + break; + case CK_AHB: + ck_freq = ahb_freq; + break; + case CK_APB1: + ck_freq = apb1_freq; + break; + case CK_APB2: + ck_freq = apb2_freq; + break; + default: + break; + } + return ck_freq; +} + +/*! + \brief get the clock stabilization and periphral reset flags + \param[in] flag: the clock stabilization and periphral reset flags, refer to rcu_flag_enum + only one parameter can be selected which is shown as below: + \arg RCU_FLAG_IRC16MSTB: IRC16M stabilization flag + \arg RCU_FLAG_HXTALSTB: HXTAL stabilization flag + \arg RCU_FLAG_PLLSTB: PLL stabilization flag + \arg RCU_FLAG_PLLI2SSTB: PLLI2S stabilization flag + \arg RCU_FLAG_PLLSAISTB: PLLSAI stabilization flag + \arg RCU_FLAG_LXTALSTB: LXTAL stabilization flag + \arg RCU_FLAG_IRC32KSTB: IRC32K stabilization flag + \arg RCU_FLAG_IRC48MSTB: IRC48M stabilization flag + \arg RCU_FLAG_BORRST: BOR reset flags + \arg RCU_FLAG_EPRST: external PIN reset flag + \arg RCU_FLAG_PORRST: Power reset flag + \arg RCU_FLAG_SWRST: software reset flag + \arg RCU_FLAG_FWDGTRST: free watchdog timer reset flag + \arg RCU_FLAG_WWDGTRST: window watchdog timer reset flag + \arg RCU_FLAG_LPRST: low-power reset flag + \param[out] none + \retval none +*/ +FlagStatus rcu_flag_get(rcu_flag_enum flag) +{ + /* get the rcu flag */ + if(RESET != (RCU_REG_VAL(flag) & BIT(RCU_BIT_POS(flag)))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear all the reset flag + \param[in] none + \param[out] none + \retval none +*/ +void rcu_all_reset_flag_clear(void) +{ + RCU_RSTSCK |= RCU_RSTSCK_RSTFC; +} + +/*! + \brief get the clock stabilization interrupt and ckm flags + \param[in] int_flag: interrupt and ckm flags, refer to rcu_int_flag_enum + only one parameter can be selected which is shown as below: + \arg RCU_INT_FLAG_IRC32KSTB: IRC32K stabilization interrupt flag + \arg RCU_INT_FLAG_LXTALSTB: LXTAL stabilization interrupt flag + \arg RCU_INT_FLAG_IRC16MSTB: IRC16M stabilization interrupt flag + \arg RCU_INT_FLAG_HXTALSTB: HXTAL stabilization interrupt flag + \arg RCU_INT_FLAG_PLLSTB: PLL stabilization interrupt flag + \arg RCU_INT_FLAG_PLLI2SSTB: PLLI2S stabilization interrupt flag + \arg RCU_INT_FLAG_PLLSAISTB: PLLSAI stabilization interrupt flag + \arg RCU_INT_FLAG_CKM: HXTAL clock stuck interrupt flag + \arg RCU_INT_FLAG_IRC48MSTB: IRC48M stabilization interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus rcu_interrupt_flag_get(rcu_int_flag_enum int_flag) +{ + /* get the rcu interrupt flag */ + if(RESET != (RCU_REG_VAL(int_flag) & BIT(RCU_BIT_POS(int_flag)))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear the interrupt flags + \param[in] int_flag: clock stabilization and stuck interrupt flags clear, refer to rcu_int_flag_clear_enum + only one parameter can be selected which is shown as below: + \arg RCU_INT_FLAG_IRC32KSTB_CLR: IRC32K stabilization interrupt flag clear + \arg RCU_INT_FLAG_LXTALSTB_CLR: LXTAL stabilization interrupt flag clear + \arg RCU_INT_FLAG_IRC16MSTB_CLR: IRC16M stabilization interrupt flag clear + \arg RCU_INT_FLAG_HXTALSTB_CLR: HXTAL stabilization interrupt flag clear + \arg RCU_INT_FLAG_PLLSTB_CLR: PLL stabilization interrupt flag clear + \arg RCU_INT_FLAG_PLLI2SSTB_CLR: PLLI2S stabilization interrupt flag clear + \arg RCU_INT_FLAG_PLLSAISTB_CLR: PLLSAI stabilization interrupt flag clear + \arg RCU_INT_FLAG_CKM_CLR: clock stuck interrupt flag clear + \arg RCU_INT_FLAG_IRC48MSTB_CLR: IRC48M stabilization interrupt flag clear + \param[out] none + \retval none +*/ +void rcu_interrupt_flag_clear(rcu_int_flag_clear_enum int_flag) +{ + RCU_REG_VAL(int_flag) |= BIT(RCU_BIT_POS(int_flag)); +} + +/*! + \brief enable the stabilization interrupt + \param[in] interrupt: clock stabilization interrupt, refer to rcu_int_enum + Only one parameter can be selected which is shown as below: + \arg RCU_INT_IRC32KSTB: IRC32K stabilization interrupt enable + \arg RCU_INT_LXTALSTB: LXTAL stabilization interrupt enable + \arg RCU_INT_IRC16MSTB: IRC16M stabilization interrupt enable + \arg RCU_INT_HXTALSTB: HXTAL stabilization interrupt enable + \arg RCU_INT_PLLSTB: PLL stabilization interrupt enable + \arg RCU_INT_PLLI2SSTB: PLLI2S stabilization interrupt enable + \arg RCU_INT_PLLSAISTB: PLLSAI stabilization interrupt enable + \arg RCU_INT_IRC48MSTB: IRC48M stabilization interrupt enable + \param[out] none + \retval none +*/ +void rcu_interrupt_enable(rcu_int_enum interrupt) +{ + RCU_REG_VAL(interrupt) |= BIT(RCU_BIT_POS(interrupt)); +} + +/*! + \brief disable the stabilization interrupt + \param[in] interrupt: clock stabilization interrupt, refer to rcu_int_enum + only one parameter can be selected which is shown as below: + \arg RCU_INT_IRC32KSTB: IRC32K stabilization interrupt disable + \arg RCU_INT_LXTALSTB: LXTAL stabilization interrupt disable + \arg RCU_INT_IRC16MSTB: IRC16M stabilization interrupt disable + \arg RCU_INT_HXTALSTB: HXTAL stabilization interrupt disable + \arg RCU_INT_PLLSTB: PLL stabilization interrupt disable + \arg RCU_INT_PLLI2SSTB: PLLI2S stabilization interrupt disable + \arg RCU_INT_PLLSAISTB: PLLSAI stabilization interrupt disable + \arg RCU_INT_IRC48MSTB: IRC48M stabilization interrupt disable + \param[out] none + \retval none +*/ +void rcu_interrupt_disable(rcu_int_enum interrupt) +{ + RCU_REG_VAL(interrupt) &= ~BIT(RCU_BIT_POS(interrupt)); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_rtc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_rtc.c new file mode 100644 index 0000000..112720a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_rtc.c @@ -0,0 +1,1291 @@ +/*! + \file gd32f5xx_rtc.c + \brief RTC driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_rtc.h" + +/* RTC timeout value */ +#define RTC_WTWF_TIMEOUT ((uint32_t)0x00004000U) /*!< wakeup timer can be write flag timeout */ +#define RTC_INITM_TIMEOUT ((uint32_t)0x00004000U) /*!< initialization state flag timeout */ +#define RTC_RSYNF_TIMEOUT ((uint32_t)0x00008000U) /*!< register synchronization flag timeout */ +#define RTC_HRFC_TIMEOUT ((uint32_t)0x20000000U) /*!< recalibration pending flag timeout */ +#define RTC_SHIFTCTL_TIMEOUT ((uint32_t)0x00001000U) /*!< shift function operation pending flag timeout */ +#define RTC_ALRMXWF_TIMEOUT ((uint32_t)0x00008000U) /*!< alarm configuration can be write flag timeout */ + +/*! + \brief reset most of the RTC registers + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_deinit(void) +{ + ErrStatus error_status = ERROR; + volatile uint32_t time_index = RTC_WTWF_TIMEOUT; + uint32_t flag_status = RESET; + /* RTC_TAMP register is not under write protection */ + RTC_TAMP = RTC_REGISTER_RESET; + + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* enter init mode */ + error_status = rtc_init_mode_enter(); + + if(ERROR != error_status) { + /* reset RTC_CTL register, but RTC_CTL[2��0] */ + RTC_CTL &= (RTC_REGISTER_RESET | RTC_CTL_WTCS); + /* before reset RTC_TIME and RTC_DATE, BPSHAD bit in RTC_CTL should be reset as the condition. + in order to read calendar from shadow register, not the real registers being reset */ + RTC_TIME = RTC_REGISTER_RESET; + RTC_DATE = RTC_DATE_RESET; + + RTC_PSC = RTC_PSC_RESET; + /* only when RTC_CTL_WTEN=0 and RTC_STAT_WTWF=1 can write RTC_CTL[2��0] */ + /* wait until the WTWF flag to be set */ + do { + flag_status = RTC_STAT & RTC_STAT_WTWF; + } while((--time_index > 0U) && ((uint32_t)RESET == flag_status)); + + if((uint32_t)RESET == flag_status) { + error_status = ERROR; + } else { + RTC_CTL &= RTC_REGISTER_RESET; + RTC_WUT = RTC_WUT_RESET; + RTC_COSC = RTC_REGISTER_RESET; + /* to write RTC_ALRMxSS register, ALRMxEN bit in RTC_CTL register should be reset as the condition */ + RTC_ALRM0TD = RTC_REGISTER_RESET; + RTC_ALRM1TD = RTC_REGISTER_RESET; + RTC_ALRM0SS = RTC_REGISTER_RESET; + RTC_ALRM1SS = RTC_REGISTER_RESET; + /* reset RTC_STAT register, also exit init mode. + at the same time, RTC_STAT_SOPF bit is reset, as the condition to reset RTC_SHIFTCTL register later */ + RTC_STAT = RTC_STAT_RESET; + /* reset RTC_SHIFTCTL and RTC_HRFC register, this can be done without the init mode */ + RTC_SHIFTCTL = RTC_REGISTER_RESET; + RTC_HRFC = RTC_REGISTER_RESET; + error_status = rtc_register_sync_wait(); + } + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} + +/*! + \brief initialize RTC registers + \param[in] rtc_initpara_struct: pointer to a rtc_parameter_struct structure which contains + parameters for initialization of the rtc peripheral + members of the structure and the member values are shown as below: + year: 0x0 - 0x99(BCD format) + month: RTC_JAN, RTC_FEB, RTC_MAR, RTC_APR, RTC_MAY, RTC_JUN, + RTC_JUL, RTC_AUG, RTC_SEP, RTC_OCT, RTC_NOV, RTC_DEC + date: 0x1 - 0x31(BCD format) + day_of_week: RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY + RTC_FRIDAY, RTC_SATURDAY, RTC_SUNDAY + hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format chose + minute: 0x0 - 0x59(BCD format) + second: 0x0 - 0x59(BCD format) + factor_asyn: 0x0 - 0x7F + factor_syn: 0x0 - 0x7FFF + am_pm: RTC_AM, RTC_PM + display_format: RTC_24HOUR, RTC_12HOUR + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_init(rtc_parameter_struct *rtc_initpara_struct) +{ + ErrStatus error_status = ERROR; + uint32_t reg_time = 0U, reg_date = 0U; + + reg_date = (DATE_YR(rtc_initpara_struct->year) | \ + DATE_DOW(rtc_initpara_struct->day_of_week) | \ + DATE_MON(rtc_initpara_struct->month) | \ + DATE_DAY(rtc_initpara_struct->date)); + + reg_time = (rtc_initpara_struct->am_pm | \ + TIME_HR(rtc_initpara_struct->hour) | \ + TIME_MN(rtc_initpara_struct->minute) | \ + TIME_SC(rtc_initpara_struct->second)); + + /* 1st: disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* 2nd: enter init mode */ + error_status = rtc_init_mode_enter(); + + if(ERROR != error_status) { + RTC_PSC = (uint32_t)(PSC_FACTOR_A(rtc_initpara_struct->factor_asyn) | \ + PSC_FACTOR_S(rtc_initpara_struct->factor_syn)); + + RTC_TIME = (uint32_t)reg_time; + RTC_DATE = (uint32_t)reg_date; + + RTC_CTL &= (uint32_t)(~RTC_CTL_CS); + RTC_CTL |= rtc_initpara_struct->display_format; + + /* 3rd: exit init mode */ + rtc_init_mode_exit(); + + /* 4th: wait the RSYNF flag to set */ + error_status = rtc_register_sync_wait(); + } + + /* 5th: enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} + +/*! + \brief enter RTC init mode + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_init_mode_enter(void) +{ + volatile uint32_t time_index = RTC_INITM_TIMEOUT; + uint32_t flag_status = RESET; + ErrStatus error_status = ERROR; + + /* check whether it has been in init mode */ + if((uint32_t)RESET == (RTC_STAT & RTC_STAT_INITF)) { + RTC_STAT |= RTC_STAT_INITM; + + /* wait until the INITF flag to be set */ + do { + flag_status = RTC_STAT & RTC_STAT_INITF; + } while((--time_index > 0U) && ((uint32_t)RESET == flag_status)); + + if((uint32_t)RESET != flag_status) { + error_status = SUCCESS; + } + } else { + error_status = SUCCESS; + } + return error_status; +} + +/*! + \brief exit RTC init mode + \param[in] none + \param[out] none + \retval none +*/ +void rtc_init_mode_exit(void) +{ + RTC_STAT &= (uint32_t)(~RTC_STAT_INITM); +} + +/*! + \brief wait until RTC_TIME and RTC_DATE registers are synchronized with APB clock, and the shadow + registers are updated + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_register_sync_wait(void) +{ + volatile uint32_t time_index = RTC_RSYNF_TIMEOUT; + uint32_t flag_status = RESET; + ErrStatus error_status = ERROR; + + if((uint32_t)RESET == (RTC_CTL & RTC_CTL_BPSHAD)) { + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* firstly clear RSYNF flag */ + RTC_STAT &= (uint32_t)(~RTC_STAT_RSYNF); + + /* wait until RSYNF flag to be set */ + do { + flag_status = RTC_STAT & RTC_STAT_RSYNF; + } while((--time_index > 0U) && ((uint32_t)RESET == flag_status)); + + if((uint32_t)RESET != flag_status) { + error_status = SUCCESS; + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + } else { + error_status = SUCCESS; + } + + return error_status; +} + +/*! + \brief get current time and date + \param[in] none + \param[out] rtc_initpara_struct: pointer to a rtc_parameter_struct structure which contains + parameters for initialization of the rtc peripheral + members of the structure and the member values are shown as below: + year: 0x0 - 0x99(BCD format) + month: RTC_JAN, RTC_FEB, RTC_MAR, RTC_APR, RTC_MAY, RTC_JUN, + RTC_JUL, RTC_AUG, RTC_SEP, RTC_OCT, RTC_NOV, RTC_DEC + date: 0x1 - 0x31(BCD format) + day_of_week: RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY + RTC_FRIDAY, RTC_SATURDAY, RTC_SUNDAY + hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format chose + minute: 0x0 - 0x59(BCD format) + second: 0x0 - 0x59(BCD format) + factor_asyn: 0x0 - 0x7F + factor_syn: 0x0 - 0x7FFF + am_pm: RTC_AM, RTC_PM + display_format: RTC_24HOUR, RTC_12HOUR + \retval none +*/ +void rtc_current_time_get(rtc_parameter_struct *rtc_initpara_struct) +{ + uint32_t temp_tr = 0U, temp_dr = 0U, temp_pscr = 0U, temp_ctlr = 0U; + + temp_tr = (uint32_t)RTC_TIME; + temp_dr = (uint32_t)RTC_DATE; + temp_pscr = (uint32_t)RTC_PSC; + temp_ctlr = (uint32_t)RTC_CTL; + + /* get current time and construct rtc_parameter_struct structure */ + rtc_initpara_struct->year = (uint8_t)GET_DATE_YR(temp_dr); + rtc_initpara_struct->month = (uint8_t)GET_DATE_MON(temp_dr); + rtc_initpara_struct->date = (uint8_t)GET_DATE_DAY(temp_dr); + rtc_initpara_struct->day_of_week = (uint8_t)GET_DATE_DOW(temp_dr); + rtc_initpara_struct->hour = (uint8_t)GET_TIME_HR(temp_tr); + rtc_initpara_struct->minute = (uint8_t)GET_TIME_MN(temp_tr); + rtc_initpara_struct->second = (uint8_t)GET_TIME_SC(temp_tr); + rtc_initpara_struct->factor_asyn = (uint16_t)GET_PSC_FACTOR_A(temp_pscr); + rtc_initpara_struct->factor_syn = (uint16_t)GET_PSC_FACTOR_S(temp_pscr); + rtc_initpara_struct->am_pm = (uint32_t)(temp_tr & RTC_TIME_PM); + rtc_initpara_struct->display_format = (uint32_t)(temp_ctlr & RTC_CTL_CS); +} + +/*! + \brief get current subsecond value + \param[in] none + \param[out] none + \retval current subsecond value +*/ +uint32_t rtc_subsecond_get(void) +{ + uint32_t reg = 0U; + /* if BPSHAD bit is reset, reading RTC_SS will lock RTC_TIME and RTC_DATE automatically */ + reg = (uint32_t)RTC_SS; + /* read RTC_DATE to unlock the 3 shadow registers */ + (void)(RTC_DATE); + + return reg; +} + +/*! + \brief configure RTC alarm + \param[in] rtc_alarm: RTC_ALARM0 or RTC_ALARM1 + \param[in] rtc_alarm_time: pointer to a rtc_alarm_struct structure which contains + parameters for RTC alarm configuration + members of the structure and the member values are shown as below: + alarm_mask: RTC_ALARM_NONE_MASK, RTC_ALARM_DATE_MASK, RTC_ALARM_HOUR_MASK + RTC_ALARM_MINUTE_MASK, RTC_ALARM_SECOND_MASK, RTC_ALARM_ALL_MASK + weekday_or_date: RTC_ALARM_DATE_SELECTED, RTC_ALARM_WEEKDAY_SELECTED + alarm_day: 1) 0x1 - 0x31(BCD format) if RTC_ALARM_DATE_SELECTED is set + 2) RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY, RTC_FRIDAY, + RTC_SATURDAY, RTC_SUNDAY if RTC_ALARM_WEEKDAY_SELECTED is set + alarm_hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format + alarm_minute: 0x0 - 0x59(BCD format) + alarm_second: 0x0 - 0x59(BCD format) + am_pm: RTC_AM, RTC_PM + \param[out] none + \retval none +*/ +void rtc_alarm_config(uint8_t rtc_alarm, rtc_alarm_struct *rtc_alarm_time) +{ + uint32_t reg_alrmtd = 0U; + + reg_alrmtd = (rtc_alarm_time->alarm_mask | \ + rtc_alarm_time->weekday_or_date | \ + rtc_alarm_time->am_pm | \ + ALRMTD_DAY(rtc_alarm_time->alarm_day) | \ + ALRMTD_HR(rtc_alarm_time->alarm_hour) | \ + ALRMTD_MN(rtc_alarm_time->alarm_minute) | \ + ALRMTD_SC(rtc_alarm_time->alarm_second)); + + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + if(RTC_ALARM0 == rtc_alarm) { + RTC_ALRM0TD = (uint32_t)reg_alrmtd; + + } else { + RTC_ALRM1TD = (uint32_t)reg_alrmtd; + } + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief configure subsecond of RTC alarm + \param[in] rtc_alarm: RTC_ALARM0 or RTC_ALARM1 + \param[in] mask_subsecond: alarm subsecond mask + \arg RTC_MASKSSC_0_14: mask alarm subsecond configuration + \arg RTC_MASKSSC_1_14: mask RTC_ALRMXSS_SSC[14:1], and RTC_ALRMXSS_SSC[0] is to be compared + \arg RTC_MASKSSC_2_14: mask RTC_ALRMXSS_SSC[14:2], and RTC_ALRMXSS_SSC[1:0] is to be compared + \arg RTC_MASKSSC_3_14: mask RTC_ALRMXSS_SSC[14:3], and RTC_ALRMXSS_SSC[2:0] is to be compared + \arg RTC_MASKSSC_4_14: mask RTC_ALRMXSS_SSC[14:4]], and RTC_ALRMXSS_SSC[3:0] is to be compared + \arg RTC_MASKSSC_5_14: mask RTC_ALRMXSS_SSC[14:5], and RTC_ALRMXSS_SSC[4:0] is to be compared + \arg RTC_MASKSSC_6_14: mask RTC_ALRMXSS_SSC[14:6], and RTC_ALRMXSS_SSC[5:0] is to be compared + \arg RTC_MASKSSC_7_14: mask RTC_ALRMXSS_SSC[14:7], and RTC_ALRMXSS_SSC[6:0] is to be compared + \arg RTC_MASKSSC_8_14: mask RTC_ALRMXSS_SSC[14:8], and RTC_ALRMXSS_SSC[7:0] is to be compared + \arg RTC_MASKSSC_9_14: mask RTC_ALRMXSS_SSC[14:9], and RTC_ALRMXSS_SSC[8:0] is to be compared + \arg RTC_MASKSSC_10_14: mask RTC_ALRMXSS_SSC[14:10], and RTC_ALRMXSS_SSC[9:0] is to be compared + \arg RTC_MASKSSC_11_14: mask RTC_ALRMXSS_SSC[14:11], and RTC_ALRMXSS_SSC[10:0] is to be compared + \arg RTC_MASKSSC_12_14: mask RTC_ALRMXSS_SSC[14:12], and RTC_ALRMXSS_SSC[11:0] is to be compared + \arg RTC_MASKSSC_13_14: mask RTC_ALRMXSS_SSC[14:13], and RTC_ALRMXSS_SSC[12:0] is to be compared + \arg RTC_MASKSSC_14: mask RTC_ALRMXSS_SSC[14], and RTC_ALRMXSS_SSC[13:0] is to be compared + \arg RTC_MASKSSC_NONE: mask none, and RTC_ALRMXSS_SSC[14:0] is to be compared + \param[in] subsecond: alarm subsecond value(0x000 - 0x7FFF) + \param[out] none + \retval none +*/ +void rtc_alarm_subsecond_config(uint8_t rtc_alarm, uint32_t mask_subsecond, uint32_t subsecond) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + if(RTC_ALARM0 == rtc_alarm) { + RTC_ALRM0SS = mask_subsecond | subsecond; + } else { + RTC_ALRM1SS = mask_subsecond | subsecond; + } + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief get RTC alarm + \param[in] rtc_alarm: RTC_ALARM0 or RTC_ALARM1 + \param[out] rtc_alarm_time: pointer to a rtc_alarm_struct structure which contains + parameters for RTC alarm configuration + members of the structure and the member values are shown as below: + alarm_mask: RTC_ALARM_NONE_MASK, RTC_ALARM_DATE_MASK, RTC_ALARM_HOUR_MASK + RTC_ALARM_MINUTE_MASK, RTC_ALARM_SECOND_MASK, RTC_ALARM_ALL_MASK + weekday_or_date: RTC_ALARM_DATE_SELECTED, RTC_ALARM_WEEKDAY_SELECTED + alarm_day: 1) 0x1 - 0x31(BCD format) if RTC_ALARM_DATE_SELECTED is set + 2) RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY, RTC_FRIDAY, + RTC_SATURDAY, RTC_SUNDAY if RTC_ALARM_WEEKDAY_SELECTED is set + alarm_hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format + alarm_minute: 0x0 - 0x59(BCD format) + alarm_second: 0x0 - 0x59(BCD format) + am_pm: RTC_AM, RTC_PM + \retval none +*/ +void rtc_alarm_get(uint8_t rtc_alarm, rtc_alarm_struct *rtc_alarm_time) +{ + uint32_t reg_alrmtd = 0U; + + /* get the value of RTC_ALRM0TD register */ + if(RTC_ALARM0 == rtc_alarm) { + reg_alrmtd = RTC_ALRM0TD; + } else { + reg_alrmtd = RTC_ALRM1TD; + } + /* get alarm parameters and construct the rtc_alarm_struct structure */ + rtc_alarm_time->alarm_mask = reg_alrmtd & RTC_ALARM_ALL_MASK; + rtc_alarm_time->am_pm = (uint32_t)(reg_alrmtd & RTC_ALRMXTD_PM); + rtc_alarm_time->weekday_or_date = (uint32_t)(reg_alrmtd & RTC_ALRMXTD_DOWS); + rtc_alarm_time->alarm_day = (uint8_t)GET_ALRMTD_DAY(reg_alrmtd); + rtc_alarm_time->alarm_hour = (uint8_t)GET_ALRMTD_HR(reg_alrmtd); + rtc_alarm_time->alarm_minute = (uint8_t)GET_ALRMTD_MN(reg_alrmtd); + rtc_alarm_time->alarm_second = (uint8_t)GET_ALRMTD_SC(reg_alrmtd); +} + +/*! + \brief get RTC alarm subsecond + \param[in] rtc_alarm: RTC_ALARM0 or RTC_ALARM1 + \param[out] none + \retval RTC alarm subsecond value +*/ +uint32_t rtc_alarm_subsecond_get(uint8_t rtc_alarm) +{ + if(RTC_ALARM0 == rtc_alarm) { + return ((uint32_t)(RTC_ALRM0SS & RTC_ALRM0SS_SSC)); + } else { + return ((uint32_t)(RTC_ALRM1SS & RTC_ALRM1SS_SSC)); + } +} + +/*! + \brief enable RTC alarm + \param[in] rtc_alarm: RTC_ALARM0 or RTC_ALARM1 + \param[out] none + \retval none +*/ +void rtc_alarm_enable(uint8_t rtc_alarm) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + if(RTC_ALARM0 == rtc_alarm) { + RTC_CTL |= RTC_CTL_ALRM0EN; + } else { + RTC_CTL |= RTC_CTL_ALRM1EN; + } + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief disable RTC alarm + \param[in] rtc_alarm: RTC_ALARM0 or RTC_ALARM1 + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_alarm_disable(uint8_t rtc_alarm) +{ + volatile uint32_t time_index = RTC_ALRMXWF_TIMEOUT; + ErrStatus error_status = ERROR; + uint32_t flag_status = RESET; + + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* clear the state of alarm */ + if(RTC_ALARM0 == rtc_alarm) { + RTC_CTL &= (uint32_t)(~RTC_CTL_ALRM0EN); + /* wait until ALRM0WF flag to be set after the alarm is disabled */ + do { + flag_status = RTC_STAT & RTC_STAT_ALRM0WF; + } while((--time_index > 0U) && ((uint32_t)RESET == flag_status)); + } else { + RTC_CTL &= (uint32_t)(~RTC_CTL_ALRM1EN); + /* wait until ALRM1WF flag to be set after the alarm is disabled */ + do { + flag_status = RTC_STAT & RTC_STAT_ALRM1WF; + } while((--time_index > 0U) && ((uint32_t)RESET == flag_status)); + } + + if((uint32_t)RESET != flag_status) { + error_status = SUCCESS; + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} + +/*! + \brief enable RTC time-stamp + \param[in] edge: specify which edge to detect of time-stamp + \arg RTC_TIMESTAMP_RISING_EDGE: rising edge is valid event edge for timestamp event + \arg RTC_TIMESTAMP_FALLING_EDGE: falling edge is valid event edge for timestamp event + \param[out] none + \retval none +*/ +void rtc_timestamp_enable(uint32_t edge) +{ + uint32_t reg_ctl = 0U; + + /* clear the bits to be configured in RTC_CTL */ + reg_ctl = (uint32_t)(RTC_CTL & (uint32_t)(~(RTC_CTL_TSEG | RTC_CTL_TSEN))); + + /* new configuration */ + reg_ctl |= (uint32_t)(edge | RTC_CTL_TSEN); + + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + RTC_CTL = (uint32_t)reg_ctl; + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief disable RTC time-stamp + \param[in] none + \param[out] none + \retval none +*/ +void rtc_timestamp_disable(void) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* clear the TSEN bit */ + RTC_CTL &= (uint32_t)(~ RTC_CTL_TSEN); + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief get RTC timestamp time and date + \param[in] none + \param[out] rtc_timestamp: pointer to a rtc_timestamp_struct structure which contains + parameters for RTC time-stamp configuration + members of the structure and the member values are shown as below: + timestamp_month: RTC_JAN, RTC_FEB, RTC_MAR, RTC_APR, RTC_MAY, RTC_JUN, + RTC_JUL, RTC_AUG, RTC_SEP, RTC_OCT, RTC_NOV, RTC_DEC + timestamp_date: 0x1 - 0x31(BCD format) + timestamp_day: RTC_MONDAY, RTC_TUESDAY, RTC_WEDSDAY, RTC_THURSDAY, RTC_FRIDAY, + RTC_SATURDAY, RTC_SUNDAY if RTC_ALARM_WEEKDAY_SELECTED is set + timestamp_hour: 0x0 - 0x12(BCD format) or 0x0 - 0x23(BCD format) depending on the rtc_display_format + timestamp_minute: 0x0 - 0x59(BCD format) + timestamp_second: 0x0 - 0x59(BCD format) + am_pm: RTC_AM, RTC_PM + \retval none +*/ +void rtc_timestamp_get(rtc_timestamp_struct *rtc_timestamp) +{ + uint32_t temp_tts = 0U, temp_dts = 0U; + + /* get the value of time_stamp registers */ + temp_tts = (uint32_t)RTC_TTS; + temp_dts = (uint32_t)RTC_DTS; + + /* get timestamp time and construct the rtc_timestamp_struct structure */ + rtc_timestamp->am_pm = (uint32_t)(temp_tts & RTC_TTS_PM); + rtc_timestamp->timestamp_month = (uint8_t)GET_DTS_MON(temp_dts); + rtc_timestamp->timestamp_date = (uint8_t)GET_DTS_DAY(temp_dts); + rtc_timestamp->timestamp_day = (uint8_t)GET_DTS_DOW(temp_dts); + rtc_timestamp->timestamp_hour = (uint8_t)GET_TTS_HR(temp_tts); + rtc_timestamp->timestamp_minute = (uint8_t)GET_TTS_MN(temp_tts); + rtc_timestamp->timestamp_second = (uint8_t)GET_TTS_SC(temp_tts); +} + +/*! + \brief get RTC time-stamp subsecond + \param[in] none + \param[out] none + \retval RTC time-stamp subsecond value +*/ +uint32_t rtc_timestamp_subsecond_get(void) +{ + return ((uint32_t)RTC_SSTS); +} + +/*! + \brief RTC time-stamp mapping + \param[in] rtc_af: + \arg RTC_AF0_TIMESTAMP: RTC_AF0 use for timestamp + \arg RTC_AF1_TIMESTAMP: RTC_AF1 use for timestamp + \param[out] none + \retval none +*/ +void rtc_timestamp_pin_map(uint32_t rtc_af) +{ + RTC_TAMP &= ~RTC_TAMP_TSSEL; + RTC_TAMP |= rtc_af; +} + +/*! + \brief enable RTC tamper + \param[in] rtc_tamper: pointer to a rtc_tamper_struct structure which contains + parameters for RTC tamper configuration + members of the structure and the member values are shown as below: + detecting tamper event can using edge mode or level mode + (1) using edge mode configuration: + tamper_source: RTC_TAMPER0, RTC_TAMPER1 + tamper_trigger: RTC_TAMPER_TRIGGER_EDGE_RISING, RTC_TAMPER_TRIGGER_EDGE_FALLING + tamper_filter: RTC_FLT_EDGE + tamper_with_timestamp: DISABLE, ENABLE + (2) using level mode configuration: + tamper_source: RTC_TAMPER0, RTC_TAMPER1 + tamper_trigger:RTC_TAMPER_TRIGGER_LEVEL_LOW, RTC_TAMPER_TRIGGER_LEVEL_HIGH + tamper_filter: RTC_FLT_2S, RTC_FLT_4S, RTC_FLT_8S + tamper_sample_frequency: RTC_FREQ_DIV32768, RTC_FREQ_DIV16384, RTC_FREQ_DIV8192, + RTC_FREQ_DIV4096, RTC_FREQ_DIV2048, RTC_FREQ_DIV1024, + RTC_FREQ_DIV512, RTC_FREQ_DIV256 + tamper_precharge_enable: DISABLE, ENABLE + tamper_precharge_time: RTC_PRCH_1C, RTC_PRCH_2C, RTC_PRCH_4C, RTC_PRCH_8C + tamper_with_timestamp: DISABLE, ENABLE + \param[out] none + \retval none +*/ +void rtc_tamper_enable(rtc_tamper_struct *rtc_tamper) +{ + /* disable tamper */ + RTC_TAMP &= (uint32_t)~(rtc_tamper->tamper_source); + + /* tamper filter must be used when the tamper source is voltage level detection */ + RTC_TAMP &= (uint32_t)~RTC_TAMP_FLT; + + /* the tamper source is voltage level detection */ + if((uint32_t)(rtc_tamper->tamper_filter) != RTC_FLT_EDGE) { + RTC_TAMP &= (uint32_t)~(RTC_TAMP_DISPU | RTC_TAMP_PRCH | RTC_TAMP_FREQ | RTC_TAMP_FLT); + + /* check if the tamper pin need precharge, if need, then configure the precharge time */ + if(DISABLE == rtc_tamper->tamper_precharge_enable) { + RTC_TAMP |= (uint32_t)RTC_TAMP_DISPU; + } else { + RTC_TAMP |= (uint32_t)(rtc_tamper->tamper_precharge_time); + } + + RTC_TAMP |= (uint32_t)(rtc_tamper->tamper_sample_frequency); + RTC_TAMP |= (uint32_t)(rtc_tamper->tamper_filter); + + /* configure the tamper trigger */ + RTC_TAMP &= ((uint32_t)~((rtc_tamper->tamper_source) << RTC_TAMPER_TRIGGER_POS)); + if(RTC_TAMPER_TRIGGER_LEVEL_LOW != rtc_tamper->tamper_trigger) { + RTC_TAMP |= (uint32_t)((rtc_tamper->tamper_source) << RTC_TAMPER_TRIGGER_POS); + } + } else { + + /* configure the tamper trigger */ + RTC_TAMP &= ((uint32_t)~((rtc_tamper->tamper_source) << RTC_TAMPER_TRIGGER_POS)); + if(RTC_TAMPER_TRIGGER_EDGE_RISING != rtc_tamper->tamper_trigger) { + RTC_TAMP |= (uint32_t)((rtc_tamper->tamper_source) << RTC_TAMPER_TRIGGER_POS); + } + } + + RTC_TAMP &= (uint32_t)~RTC_TAMP_TPTS; + if(DISABLE != rtc_tamper->tamper_with_timestamp) { + /* the tamper event also cause a time-stamp event */ + RTC_TAMP |= (uint32_t)RTC_TAMP_TPTS; + } + /* enable tamper */ + RTC_TAMP |= (uint32_t)(rtc_tamper->tamper_source); +} + +/*! + \brief disable RTC tamper + \param[in] source: specify which tamper source to be disabled + \arg RTC_TAMPER0 + \arg RTC_TAMPER1 + \param[out] none + \retval none +*/ +void rtc_tamper_disable(uint32_t source) +{ + /* disable tamper */ + RTC_TAMP &= (uint32_t)~source; + +} + +/*! + \brief RTC tamper0 mapping + \param[in] rtc_af: + \arg RTC_AF0_TAMPER0: RTC_AF0 use for tamper0 + \arg RTC_AF1_TAMPER0: RTC_AF1 use for tamper0 + \param[out] none + \retval none +*/ +void rtc_tamper0_pin_map(uint32_t rtc_af) +{ + RTC_TAMP &= ~(RTC_TAMP_TP0EN | RTC_TAMP_TP0SEL); + RTC_TAMP |= rtc_af; +} + +/*! + \brief enable specified RTC interrupt + \param[in] interrupt: specify which interrupt source to be enabled + \arg RTC_INT_TIMESTAMP: timestamp interrupt + \arg RTC_INT_ALARM0: alarm0 interrupt + \arg RTC_INT_ALARM1: alarm1 interrupt + \arg RTC_INT_TAMP: tamper detection interrupt + \arg RTC_INT_WAKEUP: wakeup timer interrupt + \param[out] none + \retval none +*/ +void rtc_interrupt_enable(uint32_t interrupt) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* enable the interrupts in RTC_CTL register */ + RTC_CTL |= (uint32_t)(interrupt & (uint32_t)~RTC_TAMP_TPIE); + /* enable the interrupts in RTC_TAMP register */ + RTC_TAMP |= (uint32_t)(interrupt & RTC_TAMP_TPIE); + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief disble specified RTC interrupt + \param[in] interrupt: specify which interrupt source to be disabled + \arg RTC_INT_TIMESTAMP: timestamp interrupt + \arg RTC_INT_ALARM0: alarm interrupt + \arg RTC_INT_ALARM1: alarm interrupt + \arg RTC_INT_TAMP: tamper detection interrupt + \arg RTC_INT_WAKEUP: wakeup timer interrupt + \param[out] none + \retval none +*/ +void rtc_interrupt_disable(uint32_t interrupt) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* disable the interrupts in RTC_CTL register */ + RTC_CTL &= (uint32_t)~(interrupt & (uint32_t)~RTC_TAMP_TPIE); + /* disable the interrupts in RTC_TAMP register */ + RTC_TAMP &= (uint32_t)~(interrupt & RTC_TAMP_TPIE); + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief check specified flag + \param[in] flag: specify which flag to check + \arg RTC_STAT_SCP: smooth calibration pending flag + \arg RTC_FLAG_TP1: RTC tamper 1 detected flag + \arg RTC_FLAG_TP0: RTC tamper 0 detected flag + \arg RTC_FLAG_TSOVR: time-stamp overflow flag + \arg RTC_FLAG_TS: time-stamp flag + \arg RTC_FLAG_ALRM0: alarm0 occurs flag + \arg RTC_FLAG_ALRM1: alarm1 occurs flag + \arg RTC_FLAG_WT: wakeup timer occurs flag + \arg RTC_FLAG_INIT: initialization state flag + \arg RTC_FLAG_RSYN: register synchronization flag + \arg RTC_FLAG_YCM: year configuration mark status flag + \arg RTC_FLAG_SOP: shift function operation pending flag + \arg RTC_FLAG_ALRM0W: alarm0 configuration can be write flag + \arg RTC_FLAG_ALRM1W: alarm1 configuration can be write flag + \arg RTC_FLAG_WTW: wakeup timer can be write flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus rtc_flag_get(uint32_t flag) +{ + FlagStatus flag_state = RESET; + + if((uint32_t)RESET != (RTC_STAT & flag)) { + flag_state = SET; + } + return flag_state; +} + +/*! + \brief clear specified flag + \arg RTC_FLAG_TP1: RTC tamper 1 detected flag + \arg RTC_FLAG_TP0: RTC tamper 0 detected flag + \arg RTC_FLAG_TSOVR: time-stamp overflow flag + \arg RTC_FLAG_TS: time-stamp flag + \arg RTC_FLAG_WT: wakeup timer occurs flag + \arg RTC_FLAG_ALARM0: alarm0 occurs flag + \arg RTC_FLAG_ALARM1: alarm1 occurs flag + \arg RTC_FLAG_RSYN: register synchronization flag + \param[out] none + \retval none +*/ +void rtc_flag_clear(uint32_t flag) +{ + RTC_STAT &= (uint32_t)(~flag); +} + +/*! + \brief configure rtc alarm output source + \param[in] source: specify signal to output + \arg RTC_ALARM0_HIGH: when the alarm0 flag is set, the output pin is high + \arg RTC_ALARM0_LOW: when the alarm0 flag is set, the output pin is low + \arg RTC_ALARM1_HIGH: when the alarm1 flag is set, the output pin is high + \arg RTC_ALARM1_LOW: when the alarm1 flag is set, the output pin is low + \arg RTC_WAKEUP_HIGH: when the wakeup flag is set, the output pin is high + \arg RTC_WAKEUP_LOW: when the wakeup flag is set, the output pin is low + \param[in] mode: specify the output pin mode when output alarm signal + \arg RTC_ALARM_OUTPUT_OD: open drain mode + \arg RTC_ALARM_OUTPUT_PP: push pull mode + \param[out] none + \retval none +*/ +void rtc_alarm_output_config(uint32_t source, uint32_t mode) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + RTC_CTL &= ~(RTC_CTL_OS | RTC_CTL_OPOL); + RTC_TAMP &= ~RTC_TAMP_AOT; + + RTC_CTL |= (uint32_t)(source); + /* alarm output */ + RTC_TAMP |= (uint32_t)(mode); + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief configure rtc calibration output source + \param[in] source: specify signal to output + \arg RTC_CALIBRATION_512HZ: when the LSE freqency is 32768Hz and the RTC_PSC + is the default value, output 512Hz signal + \arg RTC_CALIBRATION_1HZ: when the LSE freqency is 32768Hz and the RTC_PSC + is the default value, output 1Hz signal + \param[out] none + \retval none +*/ +void rtc_calibration_output_config(uint32_t source) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + RTC_CTL &= (uint32_t)~(RTC_CTL_COEN | RTC_CTL_COS); + + RTC_CTL |= (uint32_t)(source); + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief adjust the daylight saving time by adding or substracting one hour from the current time + \param[in] operation: hour adjustment operation + \arg RTC_CTL_A1H: add one hour + \arg RTC_CTL_S1H: substract one hour + \param[out] none + \retval none +*/ +void rtc_hour_adjust(uint32_t operation) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + RTC_CTL |= (uint32_t)(operation); + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief adjust RTC second or subsecond value of current time + \param[in] add: add 1s to current time or not + \arg RTC_SHIFT_ADD1S_RESET: no effect + \arg RTC_SHIFT_ADD1S_SET: add 1s to current time + \param[in] minus: number of subsecond to minus from current time(0x0 - 0x7FFF) + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_second_adjust(uint32_t add, uint32_t minus) +{ + volatile uint32_t time_index = RTC_SHIFTCTL_TIMEOUT; + ErrStatus error_status = ERROR; + uint32_t flag_status = RESET; + uint32_t temp = 0U; + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* check if a shift operation is ongoing */ + do { + flag_status = RTC_STAT & RTC_STAT_SOPF; + } while((--time_index > 0U) && ((uint32_t)RESET != flag_status)); + + /* check if the function of reference clock detection is disabled */ + temp = RTC_CTL & RTC_CTL_REFEN; + if((RESET == flag_status) && (RESET == temp)) { + RTC_SHIFTCTL = (uint32_t)(add | SHIFTCTL_SFS(minus)); + error_status = rtc_register_sync_wait(); + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} + +/*! + \brief enable RTC bypass shadow registers function + \param[in] none + \param[out] none + \retval none +*/ +void rtc_bypass_shadow_enable(void) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + RTC_CTL |= RTC_CTL_BPSHAD; + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief disable RTC bypass shadow registers function + \param[in] none + \param[out] none + \retval none +*/ +void rtc_bypass_shadow_disable(void) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + RTC_CTL &= ~RTC_CTL_BPSHAD; + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief enable RTC reference clock detection function + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_refclock_detection_enable(void) +{ + ErrStatus error_status = ERROR; + + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* enter init mode */ + error_status = rtc_init_mode_enter(); + + if(ERROR != error_status) { + RTC_CTL |= (uint32_t)RTC_CTL_REFEN; + /* exit init mode */ + rtc_init_mode_exit(); + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} + +/*! + \brief disable RTC reference clock detection function + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_refclock_detection_disable(void) +{ + ErrStatus error_status = ERROR; + + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* enter init mode */ + error_status = rtc_init_mode_enter(); + + if(ERROR != error_status) { + RTC_CTL &= (uint32_t)~RTC_CTL_REFEN; + /* exit init mode */ + rtc_init_mode_exit(); + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} + +/*! + \brief enable RTC auto wakeup function + \param[in] none + \param[out] none + \retval none +*/ +void rtc_wakeup_enable(void) +{ + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + RTC_CTL |= RTC_CTL_WTEN; + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; +} + +/*! + \brief disable RTC auto wakeup function + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_wakeup_disable(void) +{ + ErrStatus error_status = ERROR; + volatile uint32_t time_index = RTC_WTWF_TIMEOUT; + uint32_t flag_status = RESET; + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + RTC_CTL &= ~RTC_CTL_WTEN; + /* wait until the WTWF flag to be set */ + do { + flag_status = RTC_STAT & RTC_STAT_WTWF; + } while((--time_index > 0U) && ((uint32_t)RESET == flag_status)); + + if((uint32_t)RESET == flag_status) { + error_status = ERROR; + } else { + error_status = SUCCESS; + } + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + return error_status; +} + +/*! + \brief set RTC auto wakeup timer clock + \param[in] wakeup_clock: + \arg WAKEUP_RTCCK_DIV16: RTC auto wakeup timer clock is RTC clock divided by 16 + \arg WAKEUP_RTCCK_DIV8: RTC auto wakeup timer clock is RTC clock divided by 8 + \arg WAKEUP_RTCCK_DIV4: RTC auto wakeup timer clock is RTC clock divided by 4 + \arg WAKEUP_RTCCK_DIV2: RTC auto wakeup timer clock is RTC clock divided by 2 + \arg WAKEUP_CKSPRE: RTC auto wakeup timer clock is ckspre + \arg WAKEUP_CKSPRE_2EXP16: RTC auto wakeup timer clock is ckspre and wakeup timer add 2exp16 + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_wakeup_clock_set(uint8_t wakeup_clock) +{ + ErrStatus error_status = ERROR; + volatile uint32_t time_index = RTC_WTWF_TIMEOUT; + uint32_t flag_status = RESET; + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + /* only when RTC_CTL_WTEN=0 and RTC_STAT_WTWF=1 can write RTC_CTL[2��0] */ + /* wait until the WTWF flag to be set */ + do { + flag_status = RTC_STAT & RTC_STAT_WTWF; + } while((--time_index > 0U) && ((uint32_t)RESET == flag_status)); + + if((uint32_t)RESET == flag_status) { + error_status = ERROR; + } else { + RTC_CTL &= (uint32_t)~ RTC_CTL_WTCS; + RTC_CTL |= (uint32_t)wakeup_clock; + error_status = SUCCESS; + } + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} + +/*! + \brief set wakeup timer value + \param[in] wakeup_timer: 0x0000-0xffff + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_wakeup_timer_set(uint16_t wakeup_timer) +{ + ErrStatus error_status = ERROR; + volatile uint32_t time_index = RTC_WTWF_TIMEOUT; + uint32_t flag_status = RESET; + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + /* wait until the WTWF flag to be set */ + do { + flag_status = RTC_STAT & RTC_STAT_WTWF; + } while((--time_index > 0U) && ((uint32_t)RESET == flag_status)); + + if((uint32_t)RESET == flag_status) { + error_status = ERROR; + } else { + RTC_WUT = (uint32_t)wakeup_timer; + error_status = SUCCESS; + } + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + return error_status; +} + +/*! + \brief get wakeup timer value + \param[in] none + \param[out] none + \retval wakeup timer value +*/ +uint16_t rtc_wakeup_timer_get(void) +{ + return (uint16_t)RTC_WUT; +} + +/*! + \brief configure RTC smooth calibration + \param[in] window: select calibration window + \arg RTC_CALIBRATION_WINDOW_32S: 2exp20 RTCCLK cycles, 32s if RTCCLK = 32768 Hz + \arg RTC_CALIBRATION_WINDOW_16S: 2exp19 RTCCLK cycles, 16s if RTCCLK = 32768 Hz + \arg RTC_CALIBRATION_WINDOW_8S: 2exp18 RTCCLK cycles, 8s if RTCCLK = 32768 Hz + \param[in] plus: add RTC clock or not + \arg RTC_CALIBRATION_PLUS_SET: add one RTC clock every 2048 rtc clock + \arg RTC_CALIBRATION_PLUS_RESET: no effect + \param[in] minus: the RTC clock to minus during the calibration window(0x0 - 0x1FF) + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_smooth_calibration_config(uint32_t window, uint32_t plus, uint32_t minus) +{ + volatile uint32_t time_index = RTC_HRFC_TIMEOUT; + ErrStatus error_status = ERROR; + uint32_t flag_status = RESET; + + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* check if a smooth calibration operation is ongoing */ + do { + flag_status = RTC_STAT & RTC_STAT_SCPF; + } while((--time_index > 0U) && ((uint32_t)RESET != flag_status)); + + if((uint32_t)RESET == flag_status) { + RTC_HRFC = (uint32_t)(window | plus | HRFC_CMSK(minus)); + error_status = SUCCESS; + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} + +/*! + \brief enable RTC coarse calibration + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_coarse_calibration_enable(void) +{ + ErrStatus error_status = ERROR; + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + /* enter init mode */ + error_status = rtc_init_mode_enter(); + + if(ERROR != error_status) { + RTC_CTL |= (uint32_t)RTC_CTL_CCEN; + /* exit init mode */ + rtc_init_mode_exit(); + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + return error_status; +} + +/*! + \brief disable RTC coarse calibration + \param[in] none + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_coarse_calibration_disable(void) +{ + ErrStatus error_status = ERROR; + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + /* enter init mode */ + error_status = rtc_init_mode_enter(); + + if(ERROR != error_status) { + RTC_CTL &= (uint32_t)~RTC_CTL_CCEN; + /* exit init mode */ + rtc_init_mode_exit(); + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + return error_status; +} + +/*! + \brief config coarse calibration direction and step + \param[in] direction: CALIB_INCREASE or CALIB_DECREASE + \param[in] step: 0x00-0x1F + COSD=0: + 0x00:+0 PPM + 0x01:+4 PPM + 0x02:+8 PPM + .... + 0x1F:+126 PPM + COSD=1: + 0x00:-0 PPM + 0x01:-2 PPM + 0x02:-4 PPM + .... + 0x1F:-63 PPM + \param[out] none + \retval ErrStatus: ERROR or SUCCESS +*/ +ErrStatus rtc_coarse_calibration_config(uint8_t direction, uint8_t step) +{ + ErrStatus error_status = ERROR; + /* disable the write protection */ + RTC_WPK = RTC_UNLOCK_KEY1; + RTC_WPK = RTC_UNLOCK_KEY2; + + /* enter init mode */ + error_status = rtc_init_mode_enter(); + + if(ERROR != error_status) { + if(CALIB_DECREASE == direction) { + RTC_COSC |= (uint32_t)RTC_COSC_COSD; + } else { + RTC_COSC &= (uint32_t)~RTC_COSC_COSD; + } + RTC_COSC &= ~RTC_COSC_COSS; + RTC_COSC |= (uint32_t)((uint32_t)step & 0x1FU); + /* exit init mode */ + rtc_init_mode_exit(); + } + + /* enable the write protection */ + RTC_WPK = RTC_LOCK_KEY; + + return error_status; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_sai.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_sai.c new file mode 100644 index 0000000..4b5cbb8 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_sai.c @@ -0,0 +1,609 @@ +/*! + \file gd32f5xx_sai.c + \brief SAI driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_sai.h" + +/*!< bit offset of MTFCNT in SAI_CFG1 */ +#define CFG1_MTFCNT_OFFSET ((uint32_t)0x00000007U) + +/*! + \brief reset SAI + \param[in] none + \param[out] none + \retval none +*/ +void sai_deinit(void) +{ + /* reset SAI */ + rcu_periph_reset_enable(RCU_SAIRST); + rcu_periph_reset_disable(RCU_SAIRST); +} + +/*! + \brief initialize the parameter of SAI structure with a default value + \param[in] none + \param[out] sai_init_stuct: the initialization data needed to initialize SAI + \retval none +*/ +void sai_struct_para_init(sai_parameter_struct *sai_init_stuct) +{ + /* initialize the initpara struct member with the default value */ + sai_init_stuct->operating_mode = SAI_MASTER_TRANSMITTER; + sai_init_stuct->protocol = SAI_PROTOCOL_POLYMORPHIC; + sai_init_stuct->data_width = SAI_DATAWIDTH_32BIT; + sai_init_stuct->shift_dir = SAI_SHIFT_MSB; + sai_init_stuct->sample_edge = SAI_SAMPEDGE_FALLING; + sai_init_stuct->sync_mode = SAI_SYNCMODE_ASYNC; + sai_init_stuct->output_drive = SAI_OUTPUT_WITH_SAIEN; + sai_init_stuct->clk_div_bypass = SAI_CLKDIV_BYPASS_OFF; + sai_init_stuct->mclk_div = SAI_MCLKDIV_1; + sai_init_stuct->mclk_oversampling = SAI_MCLK_OVERSAMP_256; + sai_init_stuct->mclk_enable = SAI_MCLK_DISABLE; + sai_init_stuct->fifo_threshold = SAI_FIFOTH_EMPTY; +} + +/*! + \brief initialize the parameter of SAI frame structure with a default value + \param[in] none + \param[out] sai_frame_init_struct: the initialization data needed to initialize SAI frame + \retval none +*/ +void sai_frame_struct_para_init(sai_frame_parameter_struct *sai_frame_init_struct) +{ + /* initialize the initpara struct member with the default value */ + sai_frame_init_struct->frame_width = 256U; + sai_frame_init_struct->frame_sync_width = 128U; + sai_frame_init_struct->frame_sync_function = SAI_FS_FUNC_START; + sai_frame_init_struct->frame_sync_polarity = SAI_FS_POLARITY_LOW; + sai_frame_init_struct->frame_sync_offset = SAI_FS_OFFSET_BEGINNING; +} + +/*! + \brief initialize the parameter of SAI slot structure with a default value + \param[in] none + \param[out] sai_slot_init_struct: the initialization data needed to initialize SAI slot + \retval none +*/ +void sai_slot_struct_para_init(sai_slot_parameter_struct *sai_slot_init_struct) +{ + /* initialize the initpara struct member with the default value */ + sai_slot_init_struct->slot_number = 16U; + sai_slot_init_struct->slot_width = SAI_SLOT_WIDTH_DATA; + sai_slot_init_struct->data_offset = 0U; + sai_slot_init_struct->slot_active = SAI_SLOT_ACTIVE_NONE; +} + +/*! + \brief initialize SAI + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x = 0,1) + \param[in] sai_struct: SAI parameter initialization stuct members of the structure + and the member values are shown as below: + operating_mode: SAI_MASTER_TRANSMITTER, SAI_MASTER_RECEIVER, SAI_SLAVE_TRANSMITTER, SAI_SLAVE_RECEIVER; + protocol: SAI_PROTOCOL_POLYMORPHIC, SAI_PROTOCOL_SPDIF, SAI_PROTOCOL_AC97 + data_width: SAI_DATA_WIDTH_xBIT (x = 8, 10, 16, 20, 24, 32) + shift_dir: SAI_SHIFT_MSB, SAI_SHIFT_LSB + sample_edge: SAI_SAMPEDGE_FALLING, SAI_SAMPEDGE_RISING + sync_mode: SAI_SYNCMODE_ASYNC, SAI_SYNCMODE_OTHERBLOCK, SAI_SYNCMODE_EXTERNALSAI + output_drive: SAI_OUTPUT_WITH_SAIEN, SAI_OUTPUT_NOW + clk_div_bypass: SAI_CLKDIV_BYPASS_OFF, SAI_CLKDIV_BYPASS_ON + mck_div: SAI_MCLKDIV_x (x = 1,2,..,63) + mck_oversampling: SAI_MASTERCLK_OVERSAMP_256, SAI_MASTERCLK_OVERSAMP_512 + mck_enable: SAI_MASTERCLK_DISABLE, SAI_MASTERCLK_ENABLE + fifo_threshold: SAI_FIFOTH_EMPTY, SAI_FIFOTH_QUARTER, SAI_FIFOTH_HALF, SAI_FIFOTH_THREE_QUARTER, SAI_FIFOTH_FULL + \param[out] none + \retval none +*/ +void sai_init(uint32_t block, sai_parameter_struct *sai_struct) +{ + uint32_t reg = 0U; + + /* configure the SAI CFGR0 value */ + reg = SAI_CFG0(block); + reg &= ~(SAI_CFG0_OPTMOD | SAI_CFG0_PROT | \ + SAI_CFG0_DATAWD | SAI_CFG0_SHIFTDIR | \ + SAI_CFG0_SAMPEDGE | SAI_CFG0_SYNCMOD | \ + SAI_CFG0_ODRIV | SAI_CFG0_BYPASS | \ + SAI_CFG0_MDIV | SAI_CFG0_MOSPR | \ + SAI_CFG0_MCLKEN | SAI_CFG0_SAIEN); + + reg |= (uint32_t)(sai_struct->operating_mode | sai_struct->protocol | \ + sai_struct->data_width | sai_struct->shift_dir | \ + sai_struct->sample_edge | sai_struct->sync_mode | \ + sai_struct->output_drive | sai_struct->clk_div_bypass | \ + sai_struct->mclk_div | sai_struct->mclk_oversampling | \ + sai_struct->mclk_enable); + SAI_CFG0(block) = reg; + + /* configure the SAI CFGR1 FIFO threshold */ + reg = SAI_CFG1(block); + reg &= ~SAI_CFG1_FFTH; + reg |= (uint32_t)(sai_struct->fifo_threshold); + SAI_CFG1(block) = reg; +} + +/*! + \brief initialize SAI frame + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] sai_frame_struct: SAI frame parameter initialization stuct members of the structure + and the member values are shown as below: + frame_width: 1~256, frame width + frame_sync_width: 1~128, frame synchronization active width + frame_sync_function: SAI_FS_FUNC_START, SAI_FS_FUNC_START_CHANNEL + frame_sync_polarity: SAI_FS_POLARITY_LOW, SAI_FS_POLARITY_HIGH + frame_sync_offset: SAI_FS_OFFSET_BEGINNING, SAI_FS_OFFSET_ONEBITBEFORE + \param[out] none + \retval none +*/ +void sai_frame_init(uint32_t block, sai_frame_parameter_struct *sai_frame_struct) +{ + uint32_t reg = 0U; + reg = SAI_FCFG(block); + reg &= ~(SAI_FCFG_FWD | SAI_FCFG_FSAWD | SAI_FCFG_FSFUNC | \ + SAI_FCFG_FSPL | SAI_FCFG_FSOST); + reg |= (uint32_t)(sai_frame_struct->frame_sync_offset | \ + sai_frame_struct->frame_sync_polarity | \ + sai_frame_struct->frame_sync_function | \ + ((sai_frame_struct->frame_sync_width - 1U) << 8U) | \ + (sai_frame_struct->frame_width - 1U)); + /* configure the SAI frame */ + SAI_FCFG(block) = reg; +} + +/*! + \brief initialize SAI slot + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] sai_slot_struct: SAI slot parameter initialization stuct members of the structure + and the member values are shown as below: + slot_number: 1~16, slot number + slot_width: SAI_SLOTWIDTH_DATA, SAI_SLOTWIDTH_16BIT, SAI_SLOTWIDTH_32BIT + data_offset: 0~31, data offset + slot_active: one or more parameters can be selected, SAI_SLOT_ACTIVE_NONE, SAI_SLOT_ACTIVE_x(x=0..15), SAI_SLOT_ACTIVE_ALL + \param[out] none + \retval none +*/ +void sai_slot_init(uint32_t block, sai_slot_parameter_struct *sai_slot_struct) +{ + uint32_t reg = 0U; + reg = SAI_SCFG(block); + reg &= ~(SAI_SCFG_DATAOST | SAI_SCFG_SLOTWD | SAI_SCFG_SLOTNUM | SAI_SCFG_SLOTAV); + reg = (uint32_t)(((sai_slot_struct->slot_number - 1U) << 8U) | \ + sai_slot_struct->slot_width | \ + sai_slot_struct->data_offset | \ + sai_slot_struct->slot_active); + /* configure the SAI slot */ + SAI_SCFG(block) = reg; +} + +/*! + \brief SAI enable + + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[out] none + \retval none +*/ +void sai_enable(uint32_t block) +{ + SAI_CFG0(block) |= SAI_CFG0_SAIEN; +} + +/*! + \brief SAI disable + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[out] none + \retval none +*/ +void sai_disable(uint32_t block) +{ + SAI_CFG0(block) &= ~SAI_CFG0_SAIEN; +} + +/*! + \brief SAI serial data near inactive slot output management + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] sdout: serial data output management + only one parameter can be selected which is shown as below: + \arg SAI_SDLINE_DRIVE: SD line output is driven entirely during the audio frame + \arg SAI_SDLINE_RELEASE: SD line output is released near inactive slots + \param[out] none + \retval none +*/ +void sai_sdoutput_config(uint32_t block, uint32_t sdout) +{ + SAI_CFG1(block) &= ~SAI_CFG1_SDOM; + SAI_CFG1(block) |= sdout; +} + +/*! + \brief configure SAI mono mode + + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[in] mono: stereo and mono mode selection + only one parameter can be selected which is shown as below: + \arg SAI_STEREO_MODE: stereo mode + \arg SAI_MONO_MODE: mono mode + \param[out] none + \retval none +*/ +void sai_monomode_config(uint32_t block, uint32_t mono) +{ + SAI_CFG0(block) &= ~SAI_CFG0_MONO; + SAI_CFG0(block) |= mono; +} + +/*! + \brief configure SAI companding mode + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[in] compander: compander mode + only one parameter can be selected which is shown as below: + \arg SAI_COMPANDER_OFF: no compansion applies + \arg SAI_COMPANDER_ULAW: u-law algorithm + \arg SAI_COMPANDER_ALAW: A-law algorithm + \param[in] complement:complement mode + only one parameter can be selected which is shown as below: + \arg SAI_COMPLEMENT_1S: data represented in 1's complement form + \arg SAI_COMPLEMENT_2S: data represented in 2's complement form + \param[out] none + \retval none +*/ +void sai_companding_config(uint32_t block, uint32_t compander, uint32_t complement) +{ + uint32_t reg = 0U; + reg = SAI_CFG1(block); + reg &= ~(SAI_CFG1_CPLMOD | SAI_CFG1_CPAMOD); + reg |= (compander | complement); + SAI_CFG1(block) = reg; +} + +/*! + \brief SAI mute detected enable or mute send enable + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[out] none + \retval none +*/ +void sai_mute_enable(uint32_t block) +{ + SAI_CFG1(block) |= SAI_CFG1_MT; +} + +/*! + \brief SAI mute detected disable or mute send disable + + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[out] none + \retval none +*/ +void sai_mute_disable(uint32_t block) +{ + SAI_CFG1(block) &= ~SAI_CFG1_MT; +} + +/*! + \brief configure SAI mute value + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[in] value: mute value + only one parameter can be selected which are shown as below: + \arg SAI_MUTESENT_0: 0 is sent via the serial data line when mute is on + \arg SAI_MUTESENT_LASTFREAM: If SLOTNUM is less or equals to two, last frame is sent via the serial data line + \param[out] none + \retval none +*/ +void sai_mute_value_config(uint32_t block, uint32_t value) +{ + SAI_CFG1(block) &= ~SAI_CFG1_MTVAL; + SAI_CFG1(block) |= value; +} + +/*! + \brief configure SAI mute frame count + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[in] count: 0~63, mute frame count + \param[out] none + \retval none +*/ +void sai_mute_count_config(uint32_t block, uint32_t count) +{ + uint32_t reg = 0U; + reg = SAI_CFG1(block); + reg &= ~SAI_CFG1_MTFCNT; + reg |= count << CFG1_MTFCNT_OFFSET; + SAI_CFG1(block) = reg; +} + +/*! + \brief SAI transmit data + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[in] data: 32-bit data + \param[out] none + \retval none +*/ +void sai_data_transmit(uint32_t block, uint32_t data) +{ + SAI_DATA(block) = data; +} + +/*! + \brief SAI receive data + + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[out] none + \retval received data +*/ +uint32_t sai_data_receive(uint32_t block) +{ + return SAI_DATA(block); +} + +/*! + \brief get SAI fifo status + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[out] none + \retval state of fifo + \arg FIFO_EMPTY: empty + \arg FIFO_EMPTY_TO_1_4_FULL: empty < fifo_level <= 1/4_full + \arg FIFO_1_4_FULL_TO_1_2_FULL: 1/4_full < fifo_level <= 1/2_full + \arg FIFO_1_2_FULL_TO_3_4_FULL: 1/2_full < fifo_level <= 3/4_full + \arg FIFO_3_4_FULL_TO_FULL: 3/4_full < fifo_level < full + \arg FIFO_FULL: full +*/ +sai_fifo_state_enum sai_fifo_status_get(uint32_t block) +{ + sai_fifo_state_enum sai_fifo_state = FIFO_EMPTY; + + if(SAI_FIFO_STAT_EMPTY == (SAI_STAT(block) & SAI_STAT_FFSTAT)) { + sai_fifo_state = FIFO_EMPTY; + } else if(SAI_FIFO_STAT_QUARTER == (SAI_STAT(block) & SAI_STAT_FFSTAT)) { + sai_fifo_state = FIFO_EMPTY_TO_1_4_FULL; + } else if(SAI_FIFO_STAT_HALF == (SAI_STAT(block) & SAI_STAT_FFSTAT)) { + sai_fifo_state = FIFO_1_4_FULL_TO_1_2_FULL; + } else if(SAI_FIFO_STAT_THREE_QUARTER == (SAI_STAT(block) & SAI_STAT_FFSTAT)) { + sai_fifo_state = FIFO_1_2_FULL_TO_3_4_FULL; + } else if(SAI_FIFO_STAT_NEARFULL == (SAI_STAT(block) & SAI_STAT_FFSTAT)) { + sai_fifo_state = FIFO_3_4_FULL_TO_FULL; + } else { + sai_fifo_state = FIFO_FULL; + } + + return sai_fifo_state; +} + +/*! + \brief SAI fifo flush + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[out] none + \retval none +*/ +void sai_fifo_flush(uint32_t block) +{ + SAI_CFG1(block) = SAI_CFG1_FLUSH; +} + +/*! + \brief enable SAI dma + + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[out] none + \retval none +*/ +void sai_dma_enable(uint32_t block) +{ + SAI_CFG0(block) |= SAI_CFG0_DMAEN; +} + +/*! + \brief disable SAI dma + + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx (x=0,1) + \param[out] none + \retval none +*/ +void sai_dma_disable(uint32_t block) +{ + SAI_CFG0(block) &= ~SAI_CFG0_DMAEN; +} + +/*! + \brief enable the SAI interrupt + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] interrupt: specify which interrupt to enable + one or more parameters can be selected which are shown as below: + \arg SAI_INT_OUERR: FIFO overrun or underrun interrupt enable + \arg SAI_INT_MTDET: mute detection interrupt enable + \arg SAI_INT_ERRCK: error clock interrupt enable + \arg SAI_INT_FFREQ: FIFO request interrupt enable + \arg SAI_INT_ACNRDY: audio codec not ready interrupt enable + \arg SAI_INT_FSADET: frame synchronization advanced detection interrupt enable + \arg SAI_INT_FSPDET: frame synchronization postpone detection interrupt enable + \param[out] none + \retval none +*/ +void sai_interrupt_enable(uint32_t block, uint32_t interrupt) +{ + SAI_INTEN(block) |= interrupt; +} + +/*! + \brief disable the SAI interrupt + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] interrupt: specify which interrupt to disable + one or more parameters can be selected which are shown as below: + \arg SAI_INT_OUERR: FIFO overrun or underrun interrupt + \arg SAI_INT_MTDET: mute detection interrupt + \arg SAI_INT_ERRCK: error clock interrupt + \arg SAI_INT_FFREQ: FIFO request interrupt + \arg SAI_INT_ACNRDY: audio codec not ready interrupt + \arg SAI_INT_FSADET: frame synchronization advanced detection interrupt + \arg SAI_INT_FSPDET: frame synchronization postpone detection interrupt + \param[out] none + \retval none +*/ +void sai_interrupt_disable(uint32_t block, uint32_t interrupt) +{ + SAI_INTEN(block) &= ~interrupt; +} + +/*! + \brief get the SAI interrupt flag + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] interrupt: specify which interrupt flag to get + only one parameter can be selected which are shown as below: + \arg SAI_FLAG_OUERR: FIFO overrun or underrun interrupt flag + \arg SAI_FLAG_MTDET: mute detection interrupt flag + \arg SAI_FLAG_ERRCK: error clock interrupt flag + \arg SAI_FLAG_FFREQ: FIFO request interrupt flag + \arg SAI_FLAG_ACNRDY: audio codec not ready interrupt flag + \arg SAI_FLAG_FSADET: frame synchronization advanced detection interrupt flag + \arg SAI_FLAG_FSPDET: frame synchronization postpone detection interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus sai_interrupt_flag_get(uint32_t block, uint32_t interrupt) +{ + uint32_t inten = 0U; + inten = SAI_INTEN(block) & interrupt; + if((RESET != (SAI_STAT(block) & interrupt)) && (RESET != inten)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear the SAI interrupt flag + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] interrupt: specify which interrupt flag to clear + one or more parameters can be selected which are shown as below: + \arg SAI_FLAG_OUERR: FIFO overrun or underrun interrupt flag + \arg SAI_FLAG_MTDET: mute detection interrupt flag + \arg SAI_FLAG_ERRCK: error clock interrupt flag + \arg SAI_FLAG_ACNRDY: audio codec not ready interrupt flag + \arg SAI_FLAG_FSADET: frame synchronization advanced detection interrupt flag + \arg SAI_FLAG_FSPDET: frame synchronization postpone detection interrupt flag + \param[out] none + \retval none +*/ +void sai_interrupt_flag_clear(uint32_t block, uint32_t interrupt) +{ + SAI_INTC(block) = interrupt; +} + +/*! + \brief get the SAI flag + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] flag: specify which flag to get + only one parameter can be selected which are shown as below: + \arg SAI_FLAG_OUERR: FIFO overrun or underrun flag + \arg SAI_FLAG_MTDET: mute detection flag + \arg SAI_FLAG_ERRCK: error clock flag + \arg SAI_FLAG_FFREQ: FIFO request flag + \arg SAI_FLAG_ACNRDY: audio codec not ready flag + \arg SAI_FLAG_FSADET: frame synchronization advanced detection flag + \arg SAI_FLAG_FSPDET: frame synchronization postpone detection flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus sai_flag_get(uint32_t block, uint32_t flag) +{ + if(RESET != (SAI_STAT(block) & flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear the SAI flag + \param[in] block: specify which bolck is initialized + only one parameter can be selected which is shown as below: + \arg SAI_BLOCKx(x=0,1) + \param[in] flag: specify which flag to clear + one or more parameters can be selected which are shown as below: + \arg SAI_FLAG_OUERR: FIFO overrun or underrun flag + \arg SAI_FLAG_MTDET: mute detection flag + \arg SAI_FLAG_ERRCK: error clock flag + \arg SAI_FLAG_ACNRDY: audio codec not ready flag + \arg SAI_FLAG_FSADET: frame synchronization advanced detection flag + \arg SAI_FLAG_FSPDET: frame synchronization postpone detection flag + \param[out] none + \retval none +*/ +void sai_flag_clear(uint32_t block, uint32_t flag) +{ + SAI_INTC(block) = flag; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_sdio.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_sdio.c new file mode 100644 index 0000000..b548c9e --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_sdio.c @@ -0,0 +1,801 @@ +/*! + \file gd32f5xx_sdio.c + \brief SDIO driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_sdio.h" + +/*! + \brief deinitialize the SDIO + \param[in] none + \param[out] none + \retval none +*/ +void sdio_deinit(void) +{ + rcu_periph_reset_enable(RCU_SDIORST); + rcu_periph_reset_disable(RCU_SDIORST); +} + +/*! + \brief configure the SDIO clock + \param[in] clock_edge: SDIO_CLK clock edge + only one parameter can be selected which is shown as below: + \arg SDIO_SDIOCLKEDGE_RISING: select the rising edge of the SDIOCLK to generate SDIO_CLK + \arg SDIO_SDIOCLKEDGE_FALLING: select the falling edge of the SDIOCLK to generate SDIO_CLK + \param[in] clock_bypass: clock bypass + only one parameter can be selected which is shown as below: + \arg SDIO_CLOCKBYPASS_ENABLE: clock bypass + \arg SDIO_CLOCKBYPASS_DISABLE: no bypass + \param[in] clock_powersave: SDIO_CLK clock dynamic switch on/off for power saving + only one parameter can be selected which is shown as below: + \arg SDIO_CLOCKPWRSAVE_ENABLE: SDIO_CLK closed when bus is idle + \arg SDIO_CLOCKPWRSAVE_DISABLE: SDIO_CLK clock is always on + \param[in] clock_division: clock division, less than 512 + \param[out] none + \retval none +*/ +void sdio_clock_config(uint32_t clock_edge, uint32_t clock_bypass, uint32_t clock_powersave, uint16_t clock_division) +{ + uint32_t clock_config = 0U; + clock_config = SDIO_CLKCTL; + /* reset the CLKEDGE, CLKBYP, CLKPWRSAV, DIV */ + clock_config &= ~(SDIO_CLKCTL_CLKEDGE | SDIO_CLKCTL_CLKBYP | SDIO_CLKCTL_CLKPWRSAV | SDIO_CLKCTL_DIV8 | SDIO_CLKCTL_DIV); + /* if the clock division is greater or equal to 256, set the DIV[8] */ + if(clock_division >= 256U) { + clock_config |= SDIO_CLKCTL_DIV8; + clock_division -= 256U; + } + /* configure the SDIO_CLKCTL according to the parameters */ + clock_config |= (clock_edge | clock_bypass | clock_powersave | clock_division); + SDIO_CLKCTL = clock_config; +} + +/*! + \brief enable hardware clock control + \param[in] none + \param[out] none + \retval none +*/ +void sdio_hardware_clock_enable(void) +{ + SDIO_CLKCTL |= SDIO_CLKCTL_HWCLKEN; +} + +/*! + \brief disable hardware clock control + \param[in] none + \param[out] none + \retval none +*/ +void sdio_hardware_clock_disable(void) +{ + SDIO_CLKCTL &= ~SDIO_CLKCTL_HWCLKEN; +} + +/*! + \brief set different SDIO card bus mode + \param[in] bus_mode: SDIO card bus mode + only one parameter can be selected which is shown as below: + \arg SDIO_BUSMODE_1BIT: 1-bit SDIO card bus mode + \arg SDIO_BUSMODE_4BIT: 4-bit SDIO card bus mode + \arg SDIO_BUSMODE_8BIT: 8-bit SDIO card bus mode + \param[out] none + \retval none +*/ +void sdio_bus_mode_set(uint32_t bus_mode) +{ + /* reset the SDIO card bus mode bits and set according to bus_mode */ + SDIO_CLKCTL &= ~SDIO_CLKCTL_BUSMODE; + SDIO_CLKCTL |= bus_mode; +} + +/*! + \brief set the SDIO power state + \param[in] power_state: SDIO power state + only one parameter can be selected which is shown as below: + \arg SDIO_POWER_ON: SDIO power on + \arg SDIO_POWER_OFF: SDIO power off + \param[out] none + \retval none +*/ +void sdio_power_state_set(uint32_t power_state) +{ + SDIO_PWRCTL = power_state; +} + +/*! + \brief get the SDIO power state + \param[in] none + \param[out] none + \retval SDIO power state + \arg SDIO_POWER_ON: SDIO power on + \arg SDIO_POWER_OFF: SDIO power off +*/ +uint32_t sdio_power_state_get(void) +{ + return SDIO_PWRCTL; +} + +/*! + \brief enable SDIO_CLK clock output + \param[in] none + \param[out] none + \retval none +*/ +void sdio_clock_enable(void) +{ + SDIO_CLKCTL |= SDIO_CLKCTL_CLKEN; +} + +/*! + \brief disable SDIO_CLK clock output + \param[in] none + \param[out] none + \retval none +*/ +void sdio_clock_disable(void) +{ + SDIO_CLKCTL &= ~SDIO_CLKCTL_CLKEN; +} + +/*! + \brief configure the command and response + \param[in] cmd_index: command index, refer to the related specifications + \param[in] cmd_argument: command argument, refer to the related specifications + \param[in] response_type: response type + only one parameter can be selected which is shown as below: + \arg SDIO_RESPONSETYPE_NO: no response + \arg SDIO_RESPONSETYPE_SHORT: short response + \arg SDIO_RESPONSETYPE_LONG: long response + \param[out] none + \retval none +*/ +void sdio_command_response_config(uint32_t cmd_index, uint32_t cmd_argument, uint32_t response_type) +{ + uint32_t cmd_config = 0U; + /* disable the CSM */ + SDIO_CMDCTL &= ~SDIO_CMDCTL_CSMEN; + /* reset the command index, command argument and response type */ + SDIO_CMDAGMT &= ~SDIO_CMDAGMT_CMDAGMT; + SDIO_CMDAGMT = cmd_argument; + cmd_config = SDIO_CMDCTL; + cmd_config &= ~(SDIO_CMDCTL_CMDIDX | SDIO_CMDCTL_CMDRESP); + /* configure SDIO_CMDCTL and SDIO_CMDAGMT according to the parameters */ + cmd_config |= (cmd_index | response_type); + SDIO_CMDCTL = cmd_config; +} + +/*! + \brief set the command state machine wait type + \param[in] wait_type: wait type + only one parameter can be selected which is shown as below: + \arg SDIO_WAITTYPE_NO: not wait interrupt + \arg SDIO_WAITTYPE_INTERRUPT: wait interrupt + \arg SDIO_WAITTYPE_DATAEND: wait the end of data transfer + \param[out] none + \retval none +*/ +void sdio_wait_type_set(uint32_t wait_type) +{ + /* reset INTWAIT and WAITDEND */ + SDIO_CMDCTL &= ~(SDIO_CMDCTL_INTWAIT | SDIO_CMDCTL_WAITDEND); + /* set the wait type according to wait_type */ + SDIO_CMDCTL |= wait_type; +} + +/*! + \brief enable the CSM(command state machine) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_csm_enable(void) +{ + SDIO_CMDCTL |= SDIO_CMDCTL_CSMEN; +} + +/*! + \brief disable the CSM(command state machine) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_csm_disable(void) +{ + SDIO_CMDCTL &= ~SDIO_CMDCTL_CSMEN; +} + +/*! + \brief get the last response command index + \param[in] none + \param[out] none + \retval last response command index +*/ +uint8_t sdio_command_index_get(void) +{ + return (uint8_t)SDIO_RSPCMDIDX; +} + +/*! + \brief get the response for the last received command + \param[in] sdio_responsex: SDIO response + only one parameter can be selected which is shown as below: + \arg SDIO_RESPONSE0: card response[31:0]/card response[127:96] + \arg SDIO_RESPONSE1: card response[95:64] + \arg SDIO_RESPONSE2: card response[63:32] + \arg SDIO_RESPONSE3: card response[31:1], plus bit 0 + \param[out] none + \retval response for the last received command +*/ +uint32_t sdio_response_get(uint32_t sdio_responsex) +{ + uint32_t resp_content = 0U; + switch(sdio_responsex) { + case SDIO_RESPONSE0: + resp_content = SDIO_RESP0; + break; + case SDIO_RESPONSE1: + resp_content = SDIO_RESP1; + break; + case SDIO_RESPONSE2: + resp_content = SDIO_RESP2; + break; + case SDIO_RESPONSE3: + resp_content = SDIO_RESP3; + break; + default: + break; + } + return resp_content; +} + +/*! + \brief configure the data timeout, data length and data block size + \param[in] data_timeout: data timeout period in card bus clock periods + \param[in] data_length: number of data bytes to be transferred + \param[in] data_blocksize: size of data block for block transfer + only one parameter can be selected which is shown as below: + \arg SDIO_DATABLOCKSIZE_1BYTE: block size = 1 byte + \arg SDIO_DATABLOCKSIZE_2BYTES: block size = 2 bytes + \arg SDIO_DATABLOCKSIZE_4BYTES: block size = 4 bytes + \arg SDIO_DATABLOCKSIZE_8BYTES: block size = 8 bytes + \arg SDIO_DATABLOCKSIZE_16BYTES: block size = 16 bytes + \arg SDIO_DATABLOCKSIZE_32BYTES: block size = 32 bytes + \arg SDIO_DATABLOCKSIZE_64BYTES: block size = 64 bytes + \arg SDIO_DATABLOCKSIZE_128BYTES: block size = 128 bytes + \arg SDIO_DATABLOCKSIZE_256BYTES: block size = 256 bytes + \arg SDIO_DATABLOCKSIZE_512BYTES: block size = 512 bytes + \arg SDIO_DATABLOCKSIZE_1024BYTES: block size = 1024 bytes + \arg SDIO_DATABLOCKSIZE_2048BYTES: block size = 2048 bytes + \arg SDIO_DATABLOCKSIZE_4096BYTES: block size = 4096 bytes + \arg SDIO_DATABLOCKSIZE_8192BYTES: block size = 8192 bytes + \arg SDIO_DATABLOCKSIZE_16384BYTES: block size = 16384 bytes + \param[out] none + \retval none +*/ +void sdio_data_config(uint32_t data_timeout, uint32_t data_length, uint32_t data_blocksize) +{ + /* reset data timeout, data length and data block size */ + SDIO_DATATO &= ~SDIO_DATATO_DATATO; + SDIO_DATALEN &= ~SDIO_DATALEN_DATALEN; + SDIO_DATACTL &= ~SDIO_DATACTL_BLKSZ; + /* configure the related parameters of data */ + SDIO_DATATO = data_timeout; + SDIO_DATALEN = data_length; + SDIO_DATACTL |= data_blocksize; +} + +/*! + \brief configure the data transfer mode and direction + \param[in] transfer_mode: mode of data transfer + only one parameter can be selected which is shown as below: + \arg SDIO_TRANSMODE_BLOCK: block transfer + \arg SDIO_TRANSMODE_STREAM: stream transfer or SDIO multibyte transfer + \param[in] transfer_direction: data transfer direction, read or write + only one parameter can be selected which is shown as below: + \arg SDIO_TRANSDIRECTION_TOCARD: write data to card + \arg SDIO_TRANSDIRECTION_TOSDIO: read data from card + \param[out] none + \retval none +*/ +void sdio_data_transfer_config(uint32_t transfer_mode, uint32_t transfer_direction) +{ + uint32_t data_trans = 0U; + /* reset the data transfer mode, transfer direction and set according to the parameters */ + data_trans = SDIO_DATACTL; + data_trans &= ~(SDIO_DATACTL_TRANSMOD | SDIO_DATACTL_DATADIR); + data_trans |= (transfer_mode | transfer_direction); + SDIO_DATACTL = data_trans; +} + +/*! + \brief enable the DSM(data state machine) for data transfer + \param[in] none + \param[out] none + \retval none +*/ +void sdio_dsm_enable(void) +{ + SDIO_DATACTL |= SDIO_DATACTL_DATAEN; +} + +/*! + \brief disable the DSM(data state machine) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_dsm_disable(void) +{ + SDIO_DATACTL &= ~SDIO_DATACTL_DATAEN; +} + +/*! + \brief write data(one word) to the transmit FIFO + \param[in] data: 32-bit data write to card + \param[out] none + \retval none +*/ +void sdio_data_write(uint32_t data) +{ + SDIO_FIFO = data; +} + +/*! + \brief read data(one word) from the receive FIFO + \param[in] none + \param[out] none + \retval received data +*/ +uint32_t sdio_data_read(void) +{ + return SDIO_FIFO; +} + +/*! + \brief get the number of remaining data bytes to be transferred to card + \param[in] none + \param[out] none + \retval number of remaining data bytes to be transferred +*/ +uint32_t sdio_data_counter_get(void) +{ + return SDIO_DATACNT; +} + +/*! + \brief get the number of words remaining to be written or read from FIFO + \param[in] none + \param[out] none + \retval remaining number of words +*/ +uint32_t sdio_fifo_counter_get(void) +{ + return SDIO_FIFOCNT; +} + +/*! + \brief enable the DMA request for SDIO + \param[in] none + \param[out] none + \retval none +*/ +void sdio_dma_enable(void) +{ + SDIO_DATACTL |= SDIO_DATACTL_DMAEN; +} + +/*! + \brief disable the DMA request for SDIO + \param[in] none + \param[out] none + \retval none +*/ +void sdio_dma_disable(void) +{ + SDIO_DATACTL &= ~SDIO_DATACTL_DMAEN; +} + +/*! + \brief get the flags state of SDIO + \param[in] flag: flags state of SDIO + one or more parameters can be selected which are shown as below: + \arg SDIO_FLAG_CCRCERR: command response received (CRC check failed) flag + \arg SDIO_FLAG_DTCRCERR: data block sent/received (CRC check failed) flag + \arg SDIO_FLAG_CMDTMOUT: command response timeout flag + \arg SDIO_FLAG_DTTMOUT: data timeout flag + \arg SDIO_FLAG_TXURE: transmit FIFO underrun error occurs flag + \arg SDIO_FLAG_RXORE: received FIFO overrun error occurs flag + \arg SDIO_FLAG_CMDRECV: command response received (CRC check passed) flag + \arg SDIO_FLAG_CMDSEND: command sent (no response required) flag + \arg SDIO_FLAG_DTEND: data end (data counter, SDIO_DATACNT, is zero) flag + \arg SDIO_FLAG_STBITE: start bit error in the bus flag + \arg SDIO_FLAG_DTBLKEND: data block sent/received (CRC check passed) flag + \arg SDIO_FLAG_CMDRUN: command transmission in progress flag + \arg SDIO_FLAG_TXRUN: data transmission in progress flag + \arg SDIO_FLAG_RXRUN: data reception in progress flag + \arg SDIO_FLAG_TFH: transmit FIFO is half empty flag: at least 8 words can be written into the FIFO + \arg SDIO_FLAG_RFH: receive FIFO is half full flag: at least 8 words can be read in the FIFO + \arg SDIO_FLAG_TFF: transmit FIFO is full flag + \arg SDIO_FLAG_RFF: receive FIFO is full flag + \arg SDIO_FLAG_TFE: transmit FIFO is empty flag + \arg SDIO_FLAG_RFE: receive FIFO is empty flag + \arg SDIO_FLAG_TXDTVAL: data is valid in transmit FIFO flag + \arg SDIO_FLAG_RXDTVAL: data is valid in receive FIFO flag + \arg SDIO_FLAG_SDIOINT: SD I/O interrupt received flag + \arg SDIO_FLAG_ATAEND: CE-ATA command completion signal received (only for CMD61) flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus sdio_flag_get(uint32_t flag) +{ + FlagStatus temp_flag = RESET; + if(RESET != (SDIO_STAT & flag)) { + temp_flag = SET; + } + return temp_flag; +} + +/*! + \brief clear the pending flags of SDIO + \param[in] flag: flags state of SDIO + one or more parameters can be selected which are shown as below: + \arg SDIO_FLAG_CCRCERR: command response received (CRC check failed) flag + \arg SDIO_FLAG_DTCRCERR: data block sent/received (CRC check failed) flag + \arg SDIO_FLAG_CMDTMOUT: command response timeout flag + \arg SDIO_FLAG_DTTMOUT: data timeout flag + \arg SDIO_FLAG_TXURE: transmit FIFO underrun error occurs flag + \arg SDIO_FLAG_RXORE: received FIFO overrun error occurs flag + \arg SDIO_FLAG_CMDRECV: command response received (CRC check passed) flag + \arg SDIO_FLAG_CMDSEND: command sent (no response required) flag + \arg SDIO_FLAG_DTEND: data end (data counter, SDIO_DATACNT, is zero) flag + \arg SDIO_FLAG_STBITE: start bit error in the bus flag + \arg SDIO_FLAG_DTBLKEND: data block sent/received (CRC check passed) flag + \arg SDIO_FLAG_SDIOINT: SD I/O interrupt received flag + \arg SDIO_FLAG_ATAEND: CE-ATA command completion signal received (only for CMD61) flag + \param[out] none + \retval none +*/ +void sdio_flag_clear(uint32_t flag) +{ + SDIO_INTC = flag; +} + +/*! + \brief enable the SDIO interrupt + \param[in] int_flag: interrupt flags state of SDIO + one or more parameters can be selected which are shown as below: + \arg SDIO_INT_CCRCERR: SDIO CCRCERR interrupt + \arg SDIO_INT_DTCRCERR: SDIO DTCRCERR interrupt + \arg SDIO_INT_CMDTMOUT: SDIO CMDTMOUT interrupt + \arg SDIO_INT_DTTMOUT: SDIO DTTMOUT interrupt + \arg SDIO_INT_TXURE: SDIO TXURE interrupt + \arg SDIO_INT_RXORE: SDIO RXORE interrupt + \arg SDIO_INT_CMDRECV: SDIO CMDRECV interrupt + \arg SDIO_INT_CMDSEND: SDIO CMDSEND interrupt + \arg SDIO_INT_DTEND: SDIO DTEND interrupt + \arg SDIO_INT_STBITE: SDIO STBITE interrupt + \arg SDIO_INT_DTBLKEND: SDIO DTBLKEND interrupt + \arg SDIO_INT_CMDRUN: SDIO CMDRUN interrupt + \arg SDIO_INT_TXRUN: SDIO TXRUN interrupt + \arg SDIO_INT_RXRUN: SDIO RXRUN interrupt + \arg SDIO_INT_TFH: SDIO TFH interrupt + \arg SDIO_INT_RFH: SDIO RFH interrupt + \arg SDIO_INT_TFF: SDIO TFF interrupt + \arg SDIO_INT_RFF: SDIO RFF interrupt + \arg SDIO_INT_TFE: SDIO TFE interrupt + \arg SDIO_INT_RFE: SDIO RFE interrupt + \arg SDIO_INT_TXDTVAL: SDIO TXDTVAL interrupt + \arg SDIO_INT_RXDTVAL: SDIO RXDTVAL interrupt + \arg SDIO_INT_SDIOINT: SDIO SDIOINT interrupt + \arg SDIO_INT_ATAEND: SDIO ATAEND interrupt + \param[out] none + \retval none +*/ +void sdio_interrupt_enable(uint32_t int_flag) +{ + SDIO_INTEN |= int_flag; +} + +/*! + \brief disable the SDIO interrupt + \param[in] int_flag: interrupt flags state of SDIO + one or more parameters can be selected which are shown as below: + \arg SDIO_INT_CCRCERR: SDIO CCRCERR interrupt + \arg SDIO_INT_DTCRCERR: SDIO DTCRCERR interrupt + \arg SDIO_INT_CMDTMOUT: SDIO CMDTMOUT interrupt + \arg SDIO_INT_DTTMOUT: SDIO DTTMOUT interrupt + \arg SDIO_INT_TXURE: SDIO TXURE interrupt + \arg SDIO_INT_RXORE: SDIO RXORE interrupt + \arg SDIO_INT_CMDRECV: SDIO CMDRECV interrupt + \arg SDIO_INT_CMDSEND: SDIO CMDSEND interrupt + \arg SDIO_INT_DTEND: SDIO DTEND interrupt + \arg SDIO_INT_STBITE: SDIO STBITE interrupt + \arg SDIO_INT_DTBLKEND: SDIO DTBLKEND interrupt + \arg SDIO_INT_CMDRUN: SDIO CMDRUN interrupt + \arg SDIO_INT_TXRUN: SDIO TXRUN interrupt + \arg SDIO_INT_RXRUN: SDIO RXRUN interrupt + \arg SDIO_INT_TFH: SDIO TFH interrupt + \arg SDIO_INT_RFH: SDIO RFH interrupt + \arg SDIO_INT_TFF: SDIO TFF interrupt + \arg SDIO_INT_RFF: SDIO RFF interrupt + \arg SDIO_INT_TFE: SDIO TFE interrupt + \arg SDIO_INT_RFE: SDIO RFE interrupt + \arg SDIO_INT_TXDTVAL: SDIO TXDTVAL interrupt + \arg SDIO_INT_RXDTVAL: SDIO RXDTVAL interrupt + \arg SDIO_INT_SDIOINT: SDIO SDIOINT interrupt + \arg SDIO_INT_ATAEND: SDIO ATAEND interrupt + \param[out] none + \retval none +*/ +void sdio_interrupt_disable(uint32_t int_flag) +{ + SDIO_INTEN &= ~int_flag; +} + +/*! + \brief get the interrupt flags state of SDIO + \param[in] int_flag: interrupt flags state of SDIO + one or more parameters can be selected which are shown as below: + \arg SDIO_INT_FLAG_CCRCERR: SDIO CCRCERR interrupt flag + \arg SDIO_INT_FLAG_DTCRCERR: SDIO DTCRCERR interrupt flag + \arg SDIO_INT_FLAG_CMDTMOUT: SDIO CMDTMOUT interrupt flag + \arg SDIO_INT_FLAG_DTTMOUT: SDIO DTTMOUT interrupt flag + \arg SDIO_INT_FLAG_TXURE: SDIO TXURE interrupt flag + \arg SDIO_INT_FLAG_RXORE: SDIO RXORE interrupt flag + \arg SDIO_INT_FLAG_CMDRECV: SDIO CMDRECV interrupt flag + \arg SDIO_INT_FLAG_CMDSEND: SDIO CMDSEND interrupt flag + \arg SDIO_INT_FLAG_DTEND: SDIO DTEND interrupt flag + \arg SDIO_INT_FLAG_STBITE: SDIO STBITE interrupt flag + \arg SDIO_INT_FLAG_DTBLKEND: SDIO DTBLKEND interrupt flag + \arg SDIO_INT_FLAG_CMDRUN: SDIO CMDRUN interrupt flag + \arg SDIO_INT_FLAG_TXRUN: SDIO TXRUN interrupt flag + \arg SDIO_INT_FLAG_RXRUN: SDIO RXRUN interrupt flag + \arg SDIO_INT_FLAG_TFH: SDIO TFH interrupt flag + \arg SDIO_INT_FLAG_RFH: SDIO RFH interrupt flag + \arg SDIO_INT_FLAG_TFF: SDIO TFF interrupt flag + \arg SDIO_INT_FLAG_RFF: SDIO RFF interrupt flag + \arg SDIO_INT_FLAG_TFE: SDIO TFE interrupt flag + \arg SDIO_INT_FLAG_RFE: SDIO RFE interrupt flag + \arg SDIO_INT_FLAG_TXDTVAL: SDIO TXDTVAL interrupt flag + \arg SDIO_INT_FLAG_RXDTVAL: SDIO RXDTVAL interrupt flag + \arg SDIO_INT_FLAG_SDIOINT: SDIO SDIOINT interrupt flag + \arg SDIO_INT_FLAG_ATAEND: SDIO ATAEND interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus sdio_interrupt_flag_get(uint32_t int_flag) +{ + FlagStatus temp_flag = RESET; + if(RESET != (SDIO_STAT & int_flag)) { + temp_flag = SET; + } + return temp_flag; +} + +/*! + \brief clear the interrupt pending flags of SDIO + \param[in] int_flag: interrupt flags state of SDIO + one or more parameters can be selected which are shown as below: + \arg SDIO_INT_FLAG_CCRCERR: command response received (CRC check failed) flag + \arg SDIO_INT_FLAG_DTCRCERR: data block sent/received (CRC check failed) flag + \arg SDIO_INT_FLAG_CMDTMOUT: command response timeout flag + \arg SDIO_INT_FLAG_DTTMOUT: data timeout flag + \arg SDIO_INT_FLAG_TXURE: transmit FIFO underrun error occurs flag + \arg SDIO_INT_FLAG_RXORE: received FIFO overrun error occurs flag + \arg SDIO_INT_FLAG_CMDRECV: command response received (CRC check passed) flag + \arg SDIO_INT_FLAG_CMDSEND: command sent (no response required) flag + \arg SDIO_INT_FLAG_DTEND: data end (data counter, SDIO_DATACNT, is zero) flag + \arg SDIO_INT_FLAG_STBITE: start bit error in the bus flag + \arg SDIO_INT_FLAG_DTBLKEND: data block sent/received (CRC check passed) flag + \arg SDIO_INT_FLAG_SDIOINT: SD I/O interrupt received flag + \arg SDIO_INT_FLAG_ATAEND: CE-ATA command completion signal received (only for CMD61) flag + \param[out] none + \retval none +*/ +void sdio_interrupt_flag_clear(uint32_t int_flag) +{ + SDIO_INTC = int_flag; +} + +/*! + \brief enable the read wait mode(SD I/O only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_readwait_enable(void) +{ + SDIO_DATACTL |= SDIO_DATACTL_RWEN; +} + +/*! + \brief disable the read wait mode(SD I/O only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_readwait_disable(void) +{ + SDIO_DATACTL &= ~SDIO_DATACTL_RWEN; +} + +/*! + \brief enable the function that stop the read wait process(SD I/O only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_stop_readwait_enable(void) +{ + SDIO_DATACTL |= SDIO_DATACTL_RWSTOP; +} + +/*! + \brief disable the function that stop the read wait process(SD I/O only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_stop_readwait_disable(void) +{ + SDIO_DATACTL &= ~SDIO_DATACTL_RWSTOP; +} + +/*! + \brief set the read wait type(SD I/O only) + \param[in] readwait_type: SD I/O read wait type + only one parameter can be selected which is shown as below: + \arg SDIO_READWAITTYPE_CLK: read wait control by stopping SDIO_CLK + \arg SDIO_READWAITTYPE_DAT2: read wait control using SDIO_DAT[2] + \param[out] none + \retval none +*/ +void sdio_readwait_type_set(uint32_t readwait_type) +{ + if(SDIO_READWAITTYPE_CLK == readwait_type) { + SDIO_DATACTL |= SDIO_DATACTL_RWTYPE; + } else { + SDIO_DATACTL &= ~SDIO_DATACTL_RWTYPE; + } +} + +/*! + \brief enable the SD I/O mode specific operation(SD I/O only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_operation_enable(void) +{ + SDIO_DATACTL |= SDIO_DATACTL_IOEN; +} + +/*! + \brief disable the SD I/O mode specific operation(SD I/O only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_operation_disable(void) +{ + SDIO_DATACTL &= ~SDIO_DATACTL_IOEN; +} + +/*! + \brief enable the SD I/O suspend operation(SD I/O only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_suspend_enable(void) +{ + SDIO_CMDCTL |= SDIO_CMDCTL_SUSPEND; +} + +/*! + \brief disable the SD I/O suspend operation(SD I/O only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_suspend_disable(void) +{ + SDIO_CMDCTL &= ~SDIO_CMDCTL_SUSPEND; +} + +/*! + \brief enable the CE-ATA command(CE-ATA only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_ceata_command_enable(void) +{ + SDIO_CMDCTL |= SDIO_CMDCTL_ATAEN; +} + +/*! + \brief disable the CE-ATA command(CE-ATA only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_ceata_command_disable(void) +{ + SDIO_CMDCTL &= ~SDIO_CMDCTL_ATAEN; +} + +/*! + \brief enable the CE-ATA interrupt(CE-ATA only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_ceata_interrupt_enable(void) +{ + SDIO_CMDCTL &= ~SDIO_CMDCTL_NINTEN; +} + +/*! + \brief disable the CE-ATA interrupt(CE-ATA only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_ceata_interrupt_disable(void) +{ + SDIO_CMDCTL |= SDIO_CMDCTL_NINTEN; +} + +/*! + \brief enable the CE-ATA command completion signal(CE-ATA only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_ceata_command_completion_enable(void) +{ + SDIO_CMDCTL |= SDIO_CMDCTL_ENCMDC; +} + +/*! + \brief disable the CE-ATA command completion signal(CE-ATA only) + \param[in] none + \param[out] none + \retval none +*/ +void sdio_ceata_command_completion_disable(void) +{ + SDIO_CMDCTL &= ~SDIO_CMDCTL_ENCMDC; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_spi.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_spi.c new file mode 100644 index 0000000..bef7f6e --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_spi.c @@ -0,0 +1,877 @@ +/*! + \file gd32f5xx_spi.c + \brief SPI driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_spi.h" +#include "gd32f5xx_rcu.h" + +/* SPI/I2S parameter initialization mask */ +#define SPI_INIT_MASK ((uint32_t)0x00003040U) /*!< SPI parameter initialization mask */ +#define I2S_INIT_MASK ((uint32_t)0x0000F047U) /*!< I2S parameter initialization mask */ +#define I2S_FULL_DUPLEX_MASK ((uint32_t)0x00000480U) /*!< I2S full duples mode configure parameter initialization mask */ + +/* default value */ +#define SPI_I2SPSC_DEFAULT_VALUE ((uint32_t)0x00000002U) /*!< default value of SPI_I2SPSC register */ + +/*! + \brief deinitialize SPI and I2S + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5),include I2S1_ADD and I2S2_ADD + \param[out] none + \retval none +*/ +void spi_i2s_deinit(uint32_t spi_periph) +{ + switch(spi_periph) { + case SPI0: + /* reset SPI0 */ + rcu_periph_reset_enable(RCU_SPI0RST); + rcu_periph_reset_disable(RCU_SPI0RST); + break; + case SPI1: + /* reset SPI1,I2S1 and I2S1_ADD */ + rcu_periph_reset_enable(RCU_SPI1RST); + rcu_periph_reset_disable(RCU_SPI1RST); + break; + case SPI2: + /* reset SPI2,I2S2 and I2S2_ADD */ + rcu_periph_reset_enable(RCU_SPI2RST); + rcu_periph_reset_disable(RCU_SPI2RST); + break; + case SPI3: + /* reset SPI3 */ + rcu_periph_reset_enable(RCU_SPI3RST); + rcu_periph_reset_disable(RCU_SPI3RST); + break; + case SPI4: + /* reset SPI4 */ + rcu_periph_reset_enable(RCU_SPI4RST); + rcu_periph_reset_disable(RCU_SPI4RST); + break; + case SPI5: + /* reset SPI5 */ + rcu_periph_reset_enable(RCU_SPI5RST); + rcu_periph_reset_disable(RCU_SPI5RST); + break; + default : + break; + } +} + +/*! + \brief initialize the parameters of SPI struct with default values + \param[in] none + \param[out] spi_parameter_struct: the initialized struct spi_parameter_struct pointer + \retval none +*/ +void spi_struct_para_init(spi_parameter_struct *spi_struct) +{ + /* configure the structure with default value */ + spi_struct->device_mode = SPI_SLAVE; + spi_struct->trans_mode = SPI_TRANSMODE_FULLDUPLEX; + spi_struct->frame_size = SPI_FRAMESIZE_8BIT; + spi_struct->nss = SPI_NSS_HARD; + spi_struct->clock_polarity_phase = SPI_CK_PL_LOW_PH_1EDGE; + spi_struct->prescale = SPI_PSC_2; + spi_struct->endian = SPI_ENDIAN_MSB; +} +/*! + \brief initialize SPI parameter + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] spi_struct: SPI parameter initialization stuct members of the structure + and the member values are shown as below: + device_mode: SPI_MASTER, SPI_SLAVE. + trans_mode: SPI_TRANSMODE_FULLDUPLEX, SPI_TRANSMODE_RECEIVEONLY, + SPI_TRANSMODE_BDRECEIVE, SPI_TRANSMODE_BDTRANSMIT + frame_size: SPI_FRAMESIZE_16BIT, SPI_FRAMESIZE_8BIT + nss: SPI_NSS_SOFT, SPI_NSS_HARD + endian: SPI_ENDIAN_MSB, SPI_ENDIAN_LSB + clock_polarity_phase: SPI_CK_PL_LOW_PH_1EDGE, SPI_CK_PL_HIGH_PH_1EDGE + SPI_CK_PL_LOW_PH_2EDGE, SPI_CK_PL_HIGH_PH_2EDGE + prescale: SPI_PSC_n (n=2,4,8,16,32,64,128,256) + \param[out] none + \retval none +*/ +void spi_init(uint32_t spi_periph, spi_parameter_struct *spi_struct) +{ + uint32_t reg = 0U; + reg = SPI_CTL0(spi_periph); + reg &= SPI_INIT_MASK; + + /* select SPI as master or slave */ + reg |= spi_struct->device_mode; + /* select SPI transfer mode */ + reg |= spi_struct->trans_mode; + /* select SPI frame size */ + reg |= spi_struct->frame_size; + /* select SPI nss use hardware or software */ + reg |= spi_struct->nss; + /* select SPI LSB or MSB */ + reg |= spi_struct->endian; + /* select SPI polarity and phase */ + reg |= spi_struct->clock_polarity_phase; + /* select SPI prescale to adjust transmit speed */ + reg |= spi_struct->prescale; + + /* write to SPI_CTL0 register */ + SPI_CTL0(spi_periph) = (uint32_t)reg; + + SPI_I2SCTL(spi_periph) &= (uint32_t)(~SPI_I2SCTL_I2SSEL); +} + +/*! + \brief enable SPI + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_enable(uint32_t spi_periph) +{ + SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_SPIEN; +} + +/*! + \brief disable SPI + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_disable(uint32_t spi_periph) +{ + SPI_CTL0(spi_periph) &= (uint32_t)(~SPI_CTL0_SPIEN); +} + +/*! + \brief initialize I2S parameter + \param[in] spi_periph: SPIx(x=1,2) + \param[in] i2s_mode: I2S operation mode + only one parameter can be selected which is shown as below: + \arg I2S_MODE_SLAVETX : I2S slave transmit mode + \arg I2S_MODE_SLAVERX : I2S slave receive mode + \arg I2S_MODE_MASTERTX : I2S master transmit mode + \arg I2S_MODE_MASTERRX : I2S master receive mode + \param[in] i2s_standard: I2S standard + only one parameter can be selected which is shown as below: + \arg I2S_STD_PHILLIPS : I2S phillips standard + \arg I2S_STD_MSB : I2S MSB standard + \arg I2S_STD_LSB : I2S LSB standard + \arg I2S_STD_PCMSHORT : I2S PCM short standard + \arg I2S_STD_PCMLONG : I2S PCM long standard + \param[in] i2s_ckpl: I2S idle state clock polarity + only one parameter can be selected which is shown as below: + \arg I2S_CKPL_LOW : I2S clock polarity low level + \arg I2S_CKPL_HIGH : I2S clock polarity high level + \param[out] none + \retval none +*/ +void i2s_init(uint32_t spi_periph, uint32_t i2s_mode, uint32_t i2s_standard, uint32_t i2s_ckpl) +{ + uint32_t reg = 0U; + reg = SPI_I2SCTL(spi_periph); + reg &= I2S_INIT_MASK; + + /* enable I2S mode */ + reg |= (uint32_t)SPI_I2SCTL_I2SSEL; + /* select I2S mode */ + reg |= (uint32_t)i2s_mode; + /* select I2S standard */ + reg |= (uint32_t)i2s_standard; + /* select I2S polarity */ + reg |= (uint32_t)i2s_ckpl; + + /* write to SPI_I2SCTL register */ + SPI_I2SCTL(spi_periph) = (uint32_t)reg; +} + +/*! + \brief configure I2S prescale + \param[in] spi_periph: SPIx(x=1,2) + \param[in] i2s_audiosample: I2S audio sample rate + only one parameter can be selected which is shown as below: + \arg I2S_AUDIOSAMPLE_8K: audio sample rate is 8KHz + \arg I2S_AUDIOSAMPLE_11K: audio sample rate is 11KHz + \arg I2S_AUDIOSAMPLE_16K: audio sample rate is 16KHz + \arg I2S_AUDIOSAMPLE_22K: audio sample rate is 22KHz + \arg I2S_AUDIOSAMPLE_32K: audio sample rate is 32KHz + \arg I2S_AUDIOSAMPLE_44K: audio sample rate is 44KHz + \arg I2S_AUDIOSAMPLE_48K: audio sample rate is 48KHz + \arg I2S_AUDIOSAMPLE_96K: audio sample rate is 96KHz + \arg I2S_AUDIOSAMPLE_192K: audio sample rate is 192KHz + \param[in] i2s_frameformat: I2S data length and channel length + only one parameter can be selected which is shown as below: + \arg I2S_FRAMEFORMAT_DT16B_CH16B: I2S data length is 16 bit and channel length is 16 bit + \arg I2S_FRAMEFORMAT_DT16B_CH32B: I2S data length is 16 bit and channel length is 32 bit + \arg I2S_FRAMEFORMAT_DT24B_CH32B: I2S data length is 24 bit and channel length is 32 bit + \arg I2S_FRAMEFORMAT_DT32B_CH32B: I2S data length is 32 bit and channel length is 32 bit + \param[in] i2s_mckout: I2S master clock output + only one parameter can be selected which is shown as below: + \arg I2S_MCKOUT_ENABLE: I2S master clock output enable + \arg I2S_MCKOUT_DISABLE: I2S master clock output disable + \param[out] none + \retval none +*/ +void i2s_psc_config(uint32_t spi_periph, uint32_t i2s_audiosample, uint32_t i2s_frameformat, uint32_t i2s_mckout) +{ + uint32_t i2sdiv = 2U, i2sof = 0U; + uint32_t clks = 0U; + uint32_t i2sclock = 0U; + +#ifndef I2S_EXTERNAL_CLOCK_IN + uint32_t plli2sm = 0U, plli2sn = 0U, plli2sr = 0U; +#endif /* I2S_EXTERNAL_CLOCK_IN */ + + /* deinit SPI_I2SPSC register */ + SPI_I2SPSC(spi_periph) = SPI_I2SPSC_DEFAULT_VALUE; + +#ifdef I2S_EXTERNAL_CLOCK_IN + rcu_i2s_clock_config(RCU_I2SSRC_I2S_CKIN); + + /* set the I2S clock to the external clock input value */ + i2sclock = I2S_EXTERNAL_CLOCK_IN; +#else + + /* turn on the oscillator HXTAL */ + rcu_osci_on(RCU_HXTAL); + /* wait for oscillator stabilization flags is SET */ + rcu_osci_stab_wait(RCU_HXTAL); + /* turn on the PLLI2S */ + rcu_osci_on(RCU_PLLI2S_CK); + /* wait for PLLI2S flags is SET */ + rcu_osci_stab_wait(RCU_PLLI2S_CK); + /* configure the I2S clock source selection */ + rcu_i2s_clock_config(RCU_I2SSRC_PLLI2S); + + /* get the RCU_PLL_PLLPSC value */ + plli2sm = (uint32_t)(RCU_PLL & RCU_PLL_PLLPSC); + /* get the RCU_PLLI2S_PLLI2SN value */ + plli2sn = (uint32_t)((RCU_PLLI2S & RCU_PLLI2S_PLLI2SN) >> 6); + /* get the RCU_PLLI2S_PLLI2SR value */ + plli2sr = (uint32_t)((RCU_PLLI2S & RCU_PLLI2S_PLLI2SR) >> 28); + + if((RCU_PLL & RCU_PLL_PLLSEL) == RCU_PLLSRC_HXTAL) { + /* get the I2S source clock value */ + i2sclock = (uint32_t)(((HXTAL_VALUE / plli2sm) * plli2sn) / plli2sr); + } else { + /* get the I2S source clock value */ + i2sclock = (uint32_t)(((IRC16M_VALUE / plli2sm) * plli2sn) / plli2sr); + } +#endif /* I2S_EXTERNAL_CLOCK_IN */ + + /* config the prescaler depending on the mclk output state, the frame format and audio sample rate */ + if(I2S_MCKOUT_ENABLE == i2s_mckout) { + clks = (uint32_t)(((i2sclock / 256U) * 10U) / i2s_audiosample); + } else { + if(I2S_FRAMEFORMAT_DT16B_CH16B == i2s_frameformat) { + clks = (uint32_t)(((i2sclock / 32U) * 10U) / i2s_audiosample); + } else { + clks = (uint32_t)(((i2sclock / 64U) * 10U) / i2s_audiosample); + } + } + /* remove the floating point */ + clks = (clks + 5U) / 10U; + i2sof = (clks & 0x00000001U); + i2sdiv = ((clks - i2sof) / 2U); + i2sof = (i2sof << 8U); + + /* set the default values */ + if((i2sdiv < 2U) || (i2sdiv > 255U)) { + i2sdiv = 2U; + i2sof = 0U; + } + + /* configure SPI_I2SPSC */ + SPI_I2SPSC(spi_periph) = (uint32_t)(i2sdiv | i2sof | i2s_mckout); + + /* clear SPI_I2SCTL_DTLEN and SPI_I2SCTL_CHLEN bits */ + SPI_I2SCTL(spi_periph) &= (uint32_t)(~(SPI_I2SCTL_DTLEN | SPI_I2SCTL_CHLEN)); + /* configure data frame format */ + SPI_I2SCTL(spi_periph) |= (uint32_t)i2s_frameformat; +} + +/*! + \brief enable I2S + \param[in] spi_periph: SPIx(x=1,2) + \param[out] none + \retval none +*/ +void i2s_enable(uint32_t spi_periph) +{ + SPI_I2SCTL(spi_periph) |= (uint32_t)SPI_I2SCTL_I2SEN; +} + +/*! + \brief disable I2S + \param[in] spi_periph: SPIx(x=1,2) + \param[out] none + \retval none +*/ +void i2s_disable(uint32_t spi_periph) +{ + SPI_I2SCTL(spi_periph) &= (uint32_t)(~SPI_I2SCTL_I2SEN); +} + +/*! + \brief enable SPI nss output + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_nss_output_enable(uint32_t spi_periph) +{ + SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_NSSDRV; +} + +/*! + \brief disable SPI nss output + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_nss_output_disable(uint32_t spi_periph) +{ + SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_NSSDRV); +} + +/*! + \brief SPI nss pin high level in software mode + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_nss_internal_high(uint32_t spi_periph) +{ + SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_SWNSS; +} + +/*! + \brief SPI nss pin low level in software mode + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_nss_internal_low(uint32_t spi_periph) +{ + SPI_CTL0(spi_periph) &= (uint32_t)(~SPI_CTL0_SWNSS); +} + +/*! + \brief enable SPI DMA send or receive + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] spi_dma: SPI DMA mode + only one parameter can be selected which is shown as below: + \arg SPI_DMA_TRANSMIT: SPI transmit data use DMA + \arg SPI_DMA_RECEIVE: SPI receive data use DMA + \param[out] none + \retval none +*/ +void spi_dma_enable(uint32_t spi_periph, uint8_t spi_dma) +{ + if(SPI_DMA_TRANSMIT == spi_dma) { + SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_DMATEN; + } else { + SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_DMAREN; + } +} + +/*! + \brief diable SPI DMA send or receive + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] spi_dma: SPI DMA mode + only one parameter can be selected which is shown as below: + \arg SPI_DMA_TRANSMIT: SPI transmit data use DMA + \arg SPI_DMA_RECEIVE: SPI receive data use DMA + \param[out] none + \retval none +*/ +void spi_dma_disable(uint32_t spi_periph, uint8_t spi_dma) +{ + if(SPI_DMA_TRANSMIT == spi_dma) { + SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_DMATEN); + } else { + SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_DMAREN); + } +} + +/*! + \brief configure SPI/I2S data frame format + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] frame_format: SPI frame size + only one parameter can be selected which is shown as below: + \arg SPI_FRAMESIZE_16BIT: SPI frame size is 16 bits + \arg SPI_FRAMESIZE_8BIT: SPI frame size is 8 bits + \param[out] none + \retval none +*/ +void spi_i2s_data_frame_format_config(uint32_t spi_periph, uint16_t frame_format) +{ + /* clear SPI_CTL0_FF16 bit */ + SPI_CTL0(spi_periph) &= (uint32_t)(~SPI_CTL0_FF16); + /* configure SPI_CTL0_FF16 bit */ + SPI_CTL0(spi_periph) |= (uint32_t)frame_format; +} + +/*! + \brief SPI transmit data + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] data: 16-bit data + \param[out] none + \retval none +*/ +void spi_i2s_data_transmit(uint32_t spi_periph, uint16_t data) +{ + SPI_DATA(spi_periph) = (uint32_t)data; +} + +/*! + \brief SPI receive data + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval 16-bit data +*/ +uint16_t spi_i2s_data_receive(uint32_t spi_periph) +{ + return ((uint16_t)SPI_DATA(spi_periph)); +} + +/*! + \brief configure SPI bidirectional transfer direction + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] transfer_direction: SPI transfer direction + only one parameter can be selected which is shown as below: + \arg SPI_BIDIRECTIONAL_TRANSMIT: SPI work in transmit-only mode + \arg SPI_BIDIRECTIONAL_RECEIVE: SPI work in receive-only mode + \retval none +*/ +void spi_bidirectional_transfer_config(uint32_t spi_periph, uint32_t transfer_direction) +{ + if(SPI_BIDIRECTIONAL_TRANSMIT == transfer_direction) { + /* set the transmit only mode */ + SPI_CTL0(spi_periph) |= (uint32_t)SPI_BIDIRECTIONAL_TRANSMIT; + } else { + /* set the receive only mode */ + SPI_CTL0(spi_periph) &= SPI_BIDIRECTIONAL_RECEIVE; + } +} + +/*! + \brief set SPI CRC polynomial + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] crc_poly: CRC polynomial value + \param[out] none + \retval none +*/ +void spi_crc_polynomial_set(uint32_t spi_periph, uint16_t crc_poly) +{ + /* set SPI CRC polynomial */ + SPI_CRCPOLY(spi_periph) = (uint32_t)crc_poly; +} + +/*! + \brief get SPI CRC polynomial + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval 16-bit CRC polynomial +*/ +uint16_t spi_crc_polynomial_get(uint32_t spi_periph) +{ + return ((uint16_t)SPI_CRCPOLY(spi_periph)); +} + +/*! + \brief turn on SPI CRC function + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_crc_on(uint32_t spi_periph) +{ + SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_CRCEN; +} + +/*! + \brief turn off SPI CRC function + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_crc_off(uint32_t spi_periph) +{ + SPI_CTL0(spi_periph) &= (uint32_t)(~SPI_CTL0_CRCEN); +} + +/*! + \brief SPI next data is CRC value + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_crc_next(uint32_t spi_periph) +{ + SPI_CTL0(spi_periph) |= (uint32_t)SPI_CTL0_CRCNT; +} + +/*! + \brief get SPI CRC send value or receive value + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] spi_crc: SPI crc value + only one parameter can be selected which is shown as below: + \arg SPI_CRC_TX: get transmit crc value + \arg SPI_CRC_RX: get receive crc value + \param[out] none + \retval 16-bit CRC value +*/ +uint16_t spi_crc_get(uint32_t spi_periph, uint8_t spi_crc) +{ + if(SPI_CRC_TX == spi_crc) { + return ((uint16_t)(SPI_TCRC(spi_periph))); + } else { + return ((uint16_t)(SPI_RCRC(spi_periph))); + } +} + +/*! + \brief enable SPI TI mode + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_ti_mode_enable(uint32_t spi_periph) +{ + SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_TMOD; +} + +/*! + \brief disable SPI TI mode + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_ti_mode_disable(uint32_t spi_periph) +{ + SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_TMOD); +} + +/*! + \brief configure i2s full duplex mode + \param[in] i2s_add_periph: I2Sx_ADD(x=1,2) + \param[in] i2s_mode: + \arg I2S_MODE_SLAVETX : I2S slave transmit mode + \arg I2S_MODE_SLAVERX : I2S slave receive mode + \arg I2S_MODE_MASTERTX : I2S master transmit mode + \arg I2S_MODE_MASTERRX : I2S master receive mode + \param[in] i2s_standard: + \arg I2S_STD_PHILLIPS : I2S phillips standard + \arg I2S_STD_MSB : I2S MSB standard + \arg I2S_STD_LSB : I2S LSB standard + \arg I2S_STD_PCMSHORT : I2S PCM short standard + \arg I2S_STD_PCMLONG : I2S PCM long standard + \param[in] i2s_ckpl: + \arg I2S_CKPL_LOW : I2S clock polarity low level + \arg I2S_CKPL_HIGH : I2S clock polarity high level + \param[in] i2s_frameformat: + \arg I2S_FRAMEFORMAT_DT16B_CH16B: I2S data length is 16 bit and channel length is 16 bit + \arg I2S_FRAMEFORMAT_DT16B_CH32B: I2S data length is 16 bit and channel length is 32 bit + \arg I2S_FRAMEFORMAT_DT24B_CH32B: I2S data length is 24 bit and channel length is 32 bit + \arg I2S_FRAMEFORMAT_DT32B_CH32B: I2S data length is 32 bit and channel length is 32 bit + \param[out] none + \retval none +*/ +void i2s_full_duplex_mode_config(uint32_t i2s_add_periph, uint32_t i2s_mode, uint32_t i2s_standard, + uint32_t i2s_ckpl, uint32_t i2s_frameformat) +{ + uint32_t reg = 0U, tmp = 0U; + + reg = I2S_ADD_I2SCTL(i2s_add_periph); + reg &= I2S_FULL_DUPLEX_MASK; + + /* get the mode of the extra I2S module I2Sx_ADD */ + if((I2S_MODE_MASTERTX == i2s_mode) || (I2S_MODE_SLAVETX == i2s_mode)) { + tmp = I2S_MODE_SLAVERX; + } else { + tmp = I2S_MODE_SLAVETX; + } + + /* enable I2S mode */ + reg |= (uint32_t)SPI_I2SCTL_I2SSEL; + /* select I2S mode */ + reg |= (uint32_t)tmp; + /* select I2S standard */ + reg |= (uint32_t)i2s_standard; + /* select I2S polarity */ + reg |= (uint32_t)i2s_ckpl; + /* configure data frame format */ + reg |= (uint32_t)i2s_frameformat; + + /* write to SPI_I2SCTL register */ + I2S_ADD_I2SCTL(i2s_add_periph) = (uint32_t)reg; +} + +/*! + \brief enable quad wire SPI + \param[in] spi_periph: SPIx(only x=5) + \param[out] none + \retval none +*/ +void spi_quad_enable(uint32_t spi_periph) +{ + SPI_QCTL(spi_periph) |= (uint32_t)SPI_QCTL_QMOD; +} + +/*! + \brief disable quad wire SPI + \param[in] spi_periph: SPIx(only x=5) + \param[out] none + \retval none +*/ +void spi_quad_disable(uint32_t spi_periph) +{ + SPI_QCTL(spi_periph) &= (uint32_t)(~SPI_QCTL_QMOD); +} + +/*! + \brief enable quad wire SPI write + \param[in] spi_periph: SPIx(only x=5) + \param[out] none + \retval none +*/ +void spi_quad_write_enable(uint32_t spi_periph) +{ + SPI_QCTL(spi_periph) &= (uint32_t)(~SPI_QCTL_QRD); +} + +/*! + \brief enable quad wire SPI read + \param[in] spi_periph: SPIx(only x=5) + \param[out] none + \retval none +*/ +void spi_quad_read_enable(uint32_t spi_periph) +{ + SPI_QCTL(spi_periph) |= (uint32_t)SPI_QCTL_QRD; +} + +/*! + \brief enable SPI_IO2 and SPI_IO3 pin output + \param[in] spi_periph: SPIx(only x=5) + \param[out] none + \retval none +*/ +void spi_quad_io23_output_enable(uint32_t spi_periph) +{ + SPI_QCTL(spi_periph) |= (uint32_t)SPI_QCTL_IO23_DRV; +} + +/*! + \brief disable SPI_IO2 and SPI_IO3 pin output + \param[in] spi_periph: SPIx(only x=5) + \param[out] none + \retval none +*/ +void spi_quad_io23_output_disable(uint32_t spi_periph) +{ + SPI_QCTL(spi_periph) &= (uint32_t)(~SPI_QCTL_IO23_DRV); +} + +/*! + \brief enable SPI and I2S interrupt + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] spi_i2s_int: SPI/I2S interrupt + only one parameter can be selected which is shown as below: + \arg SPI_I2S_INT_TBE: transmit buffer empty interrupt + \arg SPI_I2S_INT_RBNE: receive buffer not empty interrupt + \arg SPI_I2S_INT_ERR: CRC error,configuration error,reception overrun error, + transmission underrun error and format error interrupt + \param[out] none + \retval none +*/ +void spi_i2s_interrupt_enable(uint32_t spi_periph, uint8_t spi_i2s_int) +{ + switch(spi_i2s_int) { + /* SPI/I2S transmit buffer empty interrupt */ + case SPI_I2S_INT_TBE: + SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_TBEIE; + break; + /* SPI/I2S receive buffer not empty interrupt */ + case SPI_I2S_INT_RBNE: + SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_RBNEIE; + break; + /* SPI/I2S error */ + case SPI_I2S_INT_ERR: + SPI_CTL1(spi_periph) |= (uint32_t)SPI_CTL1_ERRIE; + break; + default: + break; + } +} + +/*! + \brief disable SPI and I2S interrupt + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] spi_i2s_int: SPI/I2S interrupt + only one parameter can be selected which is shown as below: + \arg SPI_I2S_INT_TBE: transmit buffer empty interrupt + \arg SPI_I2S_INT_RBNE: receive buffer not empty interrupt + \arg SPI_I2S_INT_ERR: CRC error,configuration error,reception overrun error, + transmission underrun error and format error interrupt + \param[out] none + \retval none +*/ +void spi_i2s_interrupt_disable(uint32_t spi_periph, uint8_t spi_i2s_int) +{ + switch(spi_i2s_int) { + /* SPI/I2S transmit buffer empty interrupt */ + case SPI_I2S_INT_TBE : + SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_TBEIE); + break; + /* SPI/I2S receive buffer not empty interrupt */ + case SPI_I2S_INT_RBNE : + SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_RBNEIE); + break; + /* SPI/I2S error */ + case SPI_I2S_INT_ERR : + SPI_CTL1(spi_periph) &= (uint32_t)(~SPI_CTL1_ERRIE); + break; + default : + break; + } +} + +/*! + \brief get SPI and I2S interrupt flag status + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] spi_i2s_int: SPI/I2S interrupt flag status + only one parameter can be selected which are shown as below: + \arg SPI_I2S_INT_FLAG_TBE: transmit buffer empty interrupt flag + \arg SPI_I2S_INT_FLAG_RBNE: receive buffer not empty interrupt flag + \arg SPI_I2S_INT_FLAG_RXORERR: overrun interrupt flag + \arg SPI_INT_FLAG_CONFERR: config error interrupt flag + \arg SPI_INT_FLAG_CRCERR: CRC error interrupt flag + \arg I2S_INT_FLAG_TXURERR: underrun error interrupt flag + \arg SPI_I2S_INT_FLAG_FERR: format error interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus spi_i2s_interrupt_flag_get(uint32_t spi_periph, uint8_t spi_i2s_int) +{ + uint32_t reg1 = SPI_STAT(spi_periph); + uint32_t reg2 = SPI_CTL1(spi_periph); + + switch(spi_i2s_int) { + /* SPI/I2S transmit buffer empty interrupt */ + case SPI_I2S_INT_FLAG_TBE : + reg1 = reg1 & SPI_STAT_TBE; + reg2 = reg2 & SPI_CTL1_TBEIE; + break; + /* SPI/I2S receive buffer not empty interrupt */ + case SPI_I2S_INT_FLAG_RBNE : + reg1 = reg1 & SPI_STAT_RBNE; + reg2 = reg2 & SPI_CTL1_RBNEIE; + break; + /* SPI/I2S overrun interrupt */ + case SPI_I2S_INT_FLAG_RXORERR : + reg1 = reg1 & SPI_STAT_RXORERR; + reg2 = reg2 & SPI_CTL1_ERRIE; + break; + /* SPI config error interrupt */ + case SPI_INT_FLAG_CONFERR : + reg1 = reg1 & SPI_STAT_CONFERR; + reg2 = reg2 & SPI_CTL1_ERRIE; + break; + /* SPI CRC error interrupt */ + case SPI_INT_FLAG_CRCERR : + reg1 = reg1 & SPI_STAT_CRCERR; + reg2 = reg2 & SPI_CTL1_ERRIE; + break; + /* I2S underrun error interrupt */ + case I2S_INT_FLAG_TXURERR : + reg1 = reg1 & SPI_STAT_TXURERR; + reg2 = reg2 & SPI_CTL1_ERRIE; + break; + /* SPI/I2S format error interrupt */ + case SPI_I2S_INT_FLAG_FERR : + reg1 = reg1 & SPI_STAT_FERR; + reg2 = reg2 & SPI_CTL1_ERRIE; + break; + default : + break; + } + /*get SPI/I2S interrupt flag status */ + if(reg1 && reg2) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief get SPI and I2S flag status + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[in] spi_i2s_flag: SPI/I2S flag status + only one parameter can be selected which are shown as below: + \arg SPI_FLAG_TBE: transmit buffer empty flag + \arg SPI_FLAG_RBNE: receive buffer not empty flag + \arg SPI_FLAG_TRANS: transmit on-going flag + \arg SPI_FLAG_RXORERR: receive overrun error flag + \arg SPI_FLAG_CONFERR: mode config error flag + \arg SPI_FLAG_CRCERR: CRC error flag + \arg SPI_FLAG_FERR: format error flag + \arg I2S_FLAG_TBE: transmit buffer empty flag + \arg I2S_FLAG_RBNE: receive buffer not empty flag + \arg I2S_FLAG_TRANS: transmit on-going flag + \arg I2S_FLAG_RXORERR: overrun error flag + \arg I2S_FLAG_TXURERR: underrun error flag + \arg I2S_FLAG_CH: channel side flag + \arg I2S_FLAG_FERR: format error flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus spi_i2s_flag_get(uint32_t spi_periph, uint32_t spi_i2s_flag) +{ + if(SPI_STAT(spi_periph) & spi_i2s_flag) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear SPI CRC error flag status + \param[in] spi_periph: SPIx(x=0,1,2,3,4,5) + \param[out] none + \retval none +*/ +void spi_crc_error_clear(uint32_t spi_periph) +{ + SPI_STAT(spi_periph) &= (uint32_t)(~SPI_FLAG_CRCERR); +} + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_syscfg.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_syscfg.c new file mode 100644 index 0000000..7407be3 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_syscfg.c @@ -0,0 +1,472 @@ +/*! + \file gd32f5xx_syscfg.c + \brief SYSCFG driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_syscfg.h" + +/*! + \brief reset the SYSCFG registers + \param[in] none + \param[out] none + \retval none +*/ +void syscfg_deinit(void) +{ + rcu_periph_reset_enable(RCU_SYSCFGRST); + rcu_periph_reset_disable(RCU_SYSCFGRST); +} + +/*! + \brief configure the boot mode + \param[in] syscfg_bootmode: selects the memory remapping + only one parameter can be selected which is shown as below: + \arg SYSCFG_BOOTMODE_FLASH: main flash memory (0x08000000~0x083BFFFF) is mapped at address 0x00000000 + \arg SYSCFG_BOOTMODE_BOOTLOADER: boot loader (0x1FFF0000 - 0x1FFF77FF) is mapped at address 0x00000000 + \arg SYSCFG_BOOTMODE_EXMC_SRAM: SRAM/NOR 0 and 1 of EXMC (0x60000000~0x67FFFFFF) is mapped at address 0x00000000 + \arg SYSCFG_BOOTMODE_SRAM: SRAM0 of on-chip SRAM (0x20000000~0x2001BFFF) is mapped at address 0x00000000 + \arg SYSCFG_BOOTMODE_EXMC_SDRAM: SDRAM bank0 of EXMC (0xC0000000~0xC7FFFFFF) is mapped at address 0x00000000 + \param[out] none + \retval none +*/ +void syscfg_bootmode_config(uint8_t syscfg_bootmode) +{ + /* reset the SYSCFG_CFG0_BOOT_MODE bit and set according to syscfg_bootmode */ + SYSCFG_CFG0 &= ~SYSCFG_CFG0_BOOT_MODE; + SYSCFG_CFG0 |= (uint32_t)syscfg_bootmode; +} + +/*! + \brief FMC memory mapping swap + \param[in] syscfg_fmc_swap: selects the interal flash bank swapping + only one parameter can be selected which is shown as below: + \arg SYSCFG_FMC_SWP_BANK0: bank 0 is mapped at address 0x08000000 and bank 1 is mapped at address 0x08100000 + \arg SYSCFG_FMC_SWP_BANK1: bank 1 is mapped at address 0x08000000 and bank 0 is mapped at address 0x08100000 + \param[out] none + \retval none +*/ +void syscfg_fmc_swap_config(uint32_t syscfg_fmc_swap) +{ + uint32_t reg; + reg = SYSCFG_CFG0; + /* reset the FMC_SWP bit and set according to syscfg_fmc_swap */ + reg &= ~SYSCFG_CFG0_FMC_SWP; + SYSCFG_CFG0 = (reg | syscfg_fmc_swap); +} + +/*! + \brief EXMC memory mapping swap + \param[in] syscfg_exmc_swap: selects the memories in EXMC swapping + only one parameter can be selected which is shown as below: + \arg SYSCFG_EXMC_SWP_ENABLE: SDRAM bank 0 and bank 1 are swapped with NAND bank 1 and PC card + \arg SYSCFG_EXMC_SWP_DISABLE: no memory mapping swap + \param[out] none + \retval none +*/ +void syscfg_exmc_swap_config(uint32_t syscfg_exmc_swap) +{ + uint32_t reg; + + reg = SYSCFG_CFG0; + /* reset the SYSCFG_CFG0_EXMC_SWP bits and set according to syscfg_exmc_swap */ + reg &= ~SYSCFG_CFG0_EXMC_SWP; + SYSCFG_CFG0 = (reg | syscfg_exmc_swap); +} + +/*! + \brief configure the GPIO pin as EXTI Line + \param[in] exti_port: specify the GPIO port used in EXTI + only one parameter can be selected which is shown as below: + \arg EXTI_SOURCE_GPIOx(x = A,B,C,D,E,F,G,H,I): EXTI GPIO port + \param[in] exti_pin: specify the EXTI line + only one parameter can be selected which is shown as below: + \arg EXTI_SOURCE_PINx(x = 0..15): EXTI GPIO pin + \param[out] none + \retval none +*/ +void syscfg_exti_line_config(uint8_t exti_port, uint8_t exti_pin) +{ + uint32_t clear_exti_mask = ~((uint32_t)EXTI_SS_MASK << (EXTI_SS_MSTEP(exti_pin))); + uint32_t config_exti_mask = ((uint32_t)exti_port) << (EXTI_SS_MSTEP(exti_pin)); + + switch(exti_pin / EXTI_SS_JSTEP) { + case EXTISS0: + /* clear EXTI source line(0..3) */ + SYSCFG_EXTISS0 &= clear_exti_mask; + /* configure EXTI soure line(0..3) */ + SYSCFG_EXTISS0 |= config_exti_mask; + break; + case EXTISS1: + /* clear EXTI soure line(4..7) */ + SYSCFG_EXTISS1 &= clear_exti_mask; + /* configure EXTI soure line(4..7) */ + SYSCFG_EXTISS1 |= config_exti_mask; + break; + case EXTISS2: + /* clear EXTI soure line(8..11) */ + SYSCFG_EXTISS2 &= clear_exti_mask; + /* configure EXTI soure line(8..11) */ + SYSCFG_EXTISS2 |= config_exti_mask; + break; + case EXTISS3: + /* clear EXTI soure line(12..15) */ + SYSCFG_EXTISS3 &= clear_exti_mask; + /* configure EXTI soure line(12..15) */ + SYSCFG_EXTISS3 |= config_exti_mask; + break; + default: + break; + } +} + +/*! + \brief configure the PHY interface for the ethernet MAC + \param[in] syscfg_enet_phy_interface: specifies the media interface mode. + only one parameter can be selected which is shown as below: + \arg SYSCFG_ENET_PHY_MII: MII mode is selected + \arg SYSCFG_ENET_PHY_RMII: RMII mode is selected + \param[out] none + \retval none +*/ +void syscfg_enet_phy_interface_config(uint32_t syscfg_enet_phy_interface) +{ + uint32_t reg; + + reg = SYSCFG_CFG1; + /* reset the ENET_PHY_SEL bit and set according to syscfg_enet_phy_interface */ + reg &= ~SYSCFG_CFG1_ENET_PHY_SEL; + SYSCFG_CFG1 = (reg | syscfg_enet_phy_interface); +} + +/*! + \brief configure the I/O compensation cell + \param[in] syscfg_compensation: specifies the I/O compensation cell mode + only one parameter can be selected which is shown as below: + \arg SYSCFG_COMPENSATION_ENABLE: I/O compensation cell is enabled + \arg SYSCFG_COMPENSATION_DISABLE: I/O compensation cell is disabled + \param[out] none + \retval none +*/ +void syscfg_compensation_config(uint32_t syscfg_compensation) +{ + uint32_t reg; + + reg = SYSCFG_CPSCTL; + /* reset the SYSCFG_CPSCTL_CPS_EN bit and set according to syscfg_compensation */ + reg &= ~SYSCFG_CPSCTL_CPS_EN; + SYSCFG_CPSCTL = (reg | syscfg_compensation); +} + +/*! + \brief get Compensation cell ready flag + \param[in] none + \param[out] FlagStatus: the status of vref + \arg SET: the VREF output is ready + \arg RESET: the VREF output is not ready + \retval none +*/ +FlagStatus syscfg_cps_cell_ready_get(void) +{ + if(SYSCFG_CPSCTL & SYSCFG_CPSCTL_CPS_RDY){ + return SET; + }else{ + return RESET; + } +} + +/*! + \brief get ECC event error bits + \param[in] ecc_type: ECC event type, refer to syscfg_ecc_enum + only one parameter can be selected which is shown as below: + \arg SYSCFG_SRAM0_ECC: SRAM0 ECC event + \arg SYSCFG_SRAM1_ECC: SRAM1 ECC event + \arg SYSCFG_SRAM2_ECC: SRAM2 ECC event + \arg SYSCFG_ADDSRAM_ECC: ADDSRAM ECC event + \arg SYSCFG_TCMSRAM_ECC: TCMSRAM ECC event + \arg SYSCFG_BKPSRAM_ECC: BKPSRAM ECC event + \arg SYSCFG_FLASH_ECC: FLASH ECC event + \param[out] none + \retval error bits +*/ +uint32_t syscfg_ecc_err_bits_get(syscfg_ecc_enum ecc_type) +{ + uint32_t err_bits = 0U; + + switch(ecc_type){ + case SYSCFG_SRAM0_ECC: + err_bits = (uint32_t)((SYSCFG_SRAM0ECC & SYSCFG_SRAM0ECC_ECCSERRBITS0) >> 10U); + break; + case SYSCFG_SRAM1_ECC: + err_bits = (uint32_t)((SYSCFG_SRAM1ECC & SYSCFG_SRAM1ECC_ECCSERRBITS1) >> 12U); + break; + case SYSCFG_SRAM2_ECC: + err_bits = (uint32_t)((SYSCFG_SRAM2ECC & SYSCFG_SRAM2ECC_ECCSERRBITS2) >> 10U); + break; + case SYSCFG_ADDSRAM_ECC: + err_bits = (uint32_t)((SYSCFG_ADDSRAMECC & SYSCFG_ADDSRAMECC_ECCSERRBITS3) >> 8U); + break; + case SYSCFG_TCMSRAM_ECC: + err_bits = (uint32_t)((SYSCFG_TCMSRAMECC & SYSCFG_TCMSRAMECC_ECCSERRBITS4) >> 12U); + break; + case SYSCFG_BKPSRAM_ECC: + err_bits = (uint32_t)((SYSCFG_BKPSRAMECC & SYSCFG_BKPSRAMECC_ECCSERRBITS5) >> 16U); + break; + case SYSCFG_FLASH_ECC: + err_bits = (uint32_t)((SYSCFG_FLASHECC & SYSCFG_FLASHECC_ECCSERRBITS6) >> 2U); + break; + default: + /* should not jump to here */ + break; + } + + return err_bits; +} + +/*! + \brief get last address of ECC event + \param[in] ecc_type: ECC event type, refer to syscfg_ecc_enum + only one parameter can be selected which is shown as below: + \arg SYSCFG_SRAM0_ECC: SRAM0 ECC event + \arg SYSCFG_SRAM1_ECC: SRAM1 ECC event + \arg SYSCFG_SRAM2_ECC: SRAM2 ECC event + \arg SYSCFG_ADDSRAM_ECC: ADDSRAM ECC event + \arg SYSCFG_TCMSRAM_ECC: TCMSRAM ECC event + \arg SYSCFG_BKPSRAM_ECC: BKPSRAM ECC event + \arg SYSCFG_FLASH_ECC: FLASH ECC event + \param[out] none + \retval error address +*/ +uint32_t syscfg_ecc_address_get(syscfg_ecc_enum ecc_type) +{ + uint32_t err_addr = 0U; + + switch(ecc_type){ + case SYSCFG_SRAM0_ECC: + err_addr = (uint32_t)((SYSCFG_SRAM0ECC & SYSCFG_SRAM0ECC_ECCEADDR0) >> 16U); + break; + case SYSCFG_SRAM1_ECC: + err_addr = (uint32_t)((SYSCFG_SRAM1ECC & SYSCFG_SRAM1ECC_ECCEADDR1) >> 18U); + break; + case SYSCFG_SRAM2_ECC: + err_addr = (uint32_t)((SYSCFG_SRAM2ECC & SYSCFG_SRAM2ECC_ECCEADDR2) >> 16U); + break; + case SYSCFG_ADDSRAM_ECC: + err_addr = (uint32_t)((SYSCFG_ADDSRAMECC & SYSCFG_ADDSRAMECC_ECCEADDR3) >> 14U); + break; + case SYSCFG_TCMSRAM_ECC: + err_addr = (uint32_t)((SYSCFG_TCMSRAMECC & SYSCFG_TCMSRAMECC_ECCEADDR4) >> 18U); + break; + case SYSCFG_BKPSRAM_ECC: + err_addr = (uint32_t)((SYSCFG_BKPSRAMECC & SYSCFG_BKPSRAMECC_ECCEADDR5) >> 22U); + break; + case SYSCFG_FLASH_ECC: + err_addr = (uint32_t)(SYSCFG_FLASHECC_ADDR); + break; + default: + /* should not jump to here */ + break; + } + + return err_addr; +} + +/*! + \brief get SYSCFG flag state + \param[in] flag: SYSCFG flags, refer to syscfg_flag_enum + only one parameter can be selected which is shown as below: + \arg SYSCFG_FLAG_ECCME0: SRAM0 two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE0: SRAM0 single bit correction event flag + \arg SYSCFG_FLAG_ECCME1: SRAM1 two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE1: SRAM1 single bit correction event flag + \arg SYSCFG_FLAG_ECCME2: SRAM2 two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE2: SRAM2 single bit correction event flag + \arg SYSCFG_FLAG_ECCME3: ADDSRAM two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE3: ADDSRAM single bit correction event flag + \arg SYSCFG_FLAG_ECCME4: TCMSRAM two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE4: TCMSRAM single bit correction event flag + \arg SYSCFG_FLAG_ECCME5: BKPSRAM two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE5: BKPSRAM single bit correction event flag + \arg SYSCFG_FLAG_ECCME6: FLASH two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE6: FLASH single bit correction event flag + \arg SYSCFG_FLAG_CKMNMI: HXTAL clock moniotor NMI flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus syscfg_flag_get(syscfg_flag_enum flag) +{ + /* get flag and interrupt enable state */ + if(RESET != (SYSCFG_STAT & (uint32_t)flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear SYSCFG flag state + \param[in] flag: SYSCFG flags, refer to syscfg_flag_enum + only one parameter can be selected which is shown as below: + \arg SYSCFG_FLAG_ECCME0: SRAM0 two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE0: SRAM0 single bit correction event flag + \arg SYSCFG_FLAG_ECCME1: SRAM1 two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE1: SRAM1 single bit correction event flag + \arg SYSCFG_FLAG_ECCME2: SRAM2 two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE2: SRAM2 single bit correction event flag + \arg SYSCFG_FLAG_ECCME3: ADDSRAM two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE3: ADDSRAM single bit correction event flag + \arg SYSCFG_FLAG_ECCME4: TCMSRAM two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE4: TCMSRAM single bit correction event flag + \arg SYSCFG_FLAG_ECCME5: BKPSRAM two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE5: BKPSRAM single bit correction event flag + \arg SYSCFG_FLAG_ECCME6: FLASH two bits non-correction event flag + \arg SYSCFG_FLAG_ECCSE6: FLASH single bit correction event flag + \arg SYSCFG_FLAG_CKMNMI: HXTAL clock moniotor NMI flag + \param[out] none + \retval none +*/ +void syscfg_flag_clear(syscfg_flag_enum flag) +{ + SYSCFG_STAT = (uint32_t)flag; +} + +/*! + \brief enable SYSCFG interrupt + \param[in] interrupt: SYSCFG interrupt, refer to syscfg_interrupt_enum + only one parameter can be selected which is shown as below: + \arg SYSCFG_INT_ECCME0: SRAM0 two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE0: SRAM0 single bit correction interrupt + \arg SYSCFG_INT_CKMNMI: HXTAL clock moniotor NMI interrupt + \arg SYSCFG_INT_ECCME1: SRAM1 two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE1: SRAM1 single bit correction interrupt + \arg SYSCFG_INT_ECCME2: SRAM2 two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE2: SRAM2 single bit correction interrupt + \arg SYSCFG_INT_ECCME3: ADDSRAM two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE3: ADDSRAM single bit correction interrupt + \arg SYSCFG_INT_ECCME4: TCMSRAM two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE4: TCMSRAM single bit correction interrupt + \arg SYSCFG_INT_ECCME5: BKPSRAM two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE5: BKPSRAM single bit correction interrupt + \arg SYSCFG_INT_ECCME6: FLASH two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE6: FLASH single bit correction interrupt + \param[out] none + \retval none +*/ +void syscfg_interrupt_enable(syscfg_interrupt_enum interrupt) +{ + SYSCFG_REG_VAL(interrupt) |= BIT(SYSCFG_BIT_POS(interrupt)); +} + +/*! + \brief disable SYSCFG interrupt + \param[in] interrupt: SYSCFG interrupt, refer to syscfg_interrupt_enum + only one parameter can be selected which is shown as below: + \arg SYSCFG_INT_ECCME0: SRAM0 two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE0: SRAM0 single bit correction interrupt + \arg SYSCFG_INT_CKMNMI: HXTAL clock moniotor NMI interrupt + \arg SYSCFG_INT_ECCME1: SRAM1 two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE1: SRAM1 single bit correction interrupt + \arg SYSCFG_INT_ECCME2: SRAM2 two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE2: SRAM2 single bit correction interrupt + \arg SYSCFG_INT_ECCME3: ADDSRAM two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE3: ADDSRAM single bit correction interrupt + \arg SYSCFG_INT_ECCME4: TCMSRAM two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE4: TCMSRAM single bit correction interrupt + \arg SYSCFG_INT_ECCME5: BKPSRAM two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE5: BKPSRAM single bit correction interrupt + \arg SYSCFG_INT_ECCME6: FLASH two bits non-correction interrupt + \arg SYSCFG_INT_ECCSE6: FLASH single bit correction interrupt + \param[out] none + \retval none +*/ +void syscfg_interrupt_disable(syscfg_interrupt_enum interrupt) +{ + SYSCFG_REG_VAL(interrupt) &= ~BIT(SYSCFG_BIT_POS(interrupt)); +} + +/*! + \brief get SYSCFG interrupt flag state + \param[in] flag: SYSCFG interrupt flags, refer to syscfg_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg SYSCFG_INT_FLAG_ECCME0: SRAM0 two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE0: SRAM0 single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME1: SRAM1 two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE1: SRAM1 single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME2: SRAM2 two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE2: SRAM2 single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME3: ADDSRAM two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE3: ADDSRAM single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME4: TCMSRAM two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE4: TCMSRAM single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME5: BKPSRAM two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE5: BKPSRAM single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME6: FLASH two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE6: FLASH single bit correction event flag + \arg SYSCFG_INT_FLAG_CKMNMI: HXTAL clock moniotor NMI flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus syscfg_interrupt_flag_get(syscfg_interrupt_flag_enum flag) +{ + /* get flag and interrupt enable state */ + if(RESET != (SYSCFG_STAT & (uint32_t)flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear SYSCFG interrupt flag state + \param[in] flag: SYSCFG interrupt flags, refer to syscfg_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg SYSCFG_INT_FLAG_ECCME0: SRAM0 two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE0: SRAM0 single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME1: SRAM1 two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE1: SRAM1 single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME2: SRAM2 two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE2: SRAM2 single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME3: ADDSRAM two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE3: ADDSRAM single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME4: TCMSRAM two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE4: TCMSRAM single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME5: BKPSRAM two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE5: BKPSRAM single bit correction event flag + \arg SYSCFG_INT_FLAG_ECCME6: FLASH two bits non-correction event flag + \arg SYSCFG_INT_FLAG_ECCSE6: FLASH single bit correction event flag + \arg SYSCFG_INT_FLAG_CKMNMI: HXTAL clock moniotor NMI flag + \param[out] none + \retval none +*/ +void syscfg_interrupt_flag_clear(syscfg_interrupt_flag_enum flag) +{ + SYSCFG_STAT = (uint32_t)flag; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_timer.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_timer.c new file mode 100644 index 0000000..4077a5b --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_timer.c @@ -0,0 +1,2282 @@ +/*! + \file gd32f5xx_timer.c + \brief TIMER driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_timer.h" + +/*! + \brief deinit a TIMER + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval none +*/ +void timer_deinit(uint32_t timer_periph) +{ + switch(timer_periph) { + case TIMER0: + /* reset TIMER0 */ + rcu_periph_reset_enable(RCU_TIMER0RST); + rcu_periph_reset_disable(RCU_TIMER0RST); + break; + case TIMER1: + /* reset TIMER1 */ + rcu_periph_reset_enable(RCU_TIMER1RST); + rcu_periph_reset_disable(RCU_TIMER1RST); + break; + case TIMER2: + /* reset TIMER2 */ + rcu_periph_reset_enable(RCU_TIMER2RST); + rcu_periph_reset_disable(RCU_TIMER2RST); + break; + case TIMER3: + /* reset TIMER3 */ + rcu_periph_reset_enable(RCU_TIMER3RST); + rcu_periph_reset_disable(RCU_TIMER3RST); + break; + case TIMER4: + /* reset TIMER4 */ + rcu_periph_reset_enable(RCU_TIMER4RST); + rcu_periph_reset_disable(RCU_TIMER4RST); + break; + case TIMER5: + /* reset TIMER5 */ + rcu_periph_reset_enable(RCU_TIMER5RST); + rcu_periph_reset_disable(RCU_TIMER5RST); + break; + case TIMER6: + /* reset TIMER6 */ + rcu_periph_reset_enable(RCU_TIMER6RST); + rcu_periph_reset_disable(RCU_TIMER6RST); + break; + case TIMER7: + /* reset TIMER7 */ + rcu_periph_reset_enable(RCU_TIMER7RST); + rcu_periph_reset_disable(RCU_TIMER7RST); + break; + case TIMER8: + /* reset TIMER8 */ + rcu_periph_reset_enable(RCU_TIMER8RST); + rcu_periph_reset_disable(RCU_TIMER8RST); + break; + case TIMER9: + /* reset TIMER9 */ + rcu_periph_reset_enable(RCU_TIMER9RST); + rcu_periph_reset_disable(RCU_TIMER9RST); + break; + case TIMER10: + /* reset TIMER10 */ + rcu_periph_reset_enable(RCU_TIMER10RST); + rcu_periph_reset_disable(RCU_TIMER10RST); + break; + case TIMER11: + /* reset TIMER11 */ + rcu_periph_reset_enable(RCU_TIMER11RST); + rcu_periph_reset_disable(RCU_TIMER11RST); + break; + case TIMER12: + /* reset TIMER12 */ + rcu_periph_reset_enable(RCU_TIMER12RST); + rcu_periph_reset_disable(RCU_TIMER12RST); + break; + case TIMER13: + /* reset TIMER13 */ + rcu_periph_reset_enable(RCU_TIMER13RST); + rcu_periph_reset_disable(RCU_TIMER13RST); + break; + default: + break; + } +} + +/*! + \brief initialize TIMER init parameter struct with a default value + \param[in] initpara: init parameter struct + \param[out] none + \retval none +*/ +void timer_struct_para_init(timer_parameter_struct *initpara) +{ + /* initialize the init parameter struct member with the default value */ + initpara->prescaler = 0U; + initpara->alignedmode = TIMER_COUNTER_EDGE; + initpara->counterdirection = TIMER_COUNTER_UP; + initpara->period = 65535U; + initpara->clockdivision = TIMER_CKDIV_DIV1; + initpara->repetitioncounter = 0U; +} + +/*! + \brief initialize TIMER counter + \param[in] timer_periph: TIMERx(x=0..13) + \param[in] initpara: init parameter struct + prescaler: prescaler value of the counter clock,0~65535 + alignedmode: TIMER_COUNTER_EDGE,TIMER_COUNTER_CENTER_DOWN,TIMER_COUNTER_CENTER_UP,TIMER_COUNTER_CENTER_BOTH + counterdirection: TIMER_COUNTER_UP,TIMER_COUNTER_DOWN + period: counter auto reload value,(TIMER1,TIMER4,32 bit) + clockdivision: TIMER_CKDIV_DIV1,TIMER_CKDIV_DIV2,TIMER_CKDIV_DIV4 + repetitioncounter: counter repetition value,0~255 + \param[out] none + \retval none +*/ +void timer_init(uint32_t timer_periph, timer_parameter_struct *initpara) +{ + /* configure the counter prescaler value */ + TIMER_PSC(timer_periph) = (uint16_t)initpara->prescaler; + + /* configure the counter direction and aligned mode */ + if((TIMER0 == timer_periph) || (TIMER1 == timer_periph) || (TIMER2 == timer_periph) + || (TIMER3 == timer_periph) || (TIMER4 == timer_periph) || (TIMER7 == timer_periph)) { + TIMER_CTL0(timer_periph) &= ~(uint32_t)(TIMER_CTL0_DIR | TIMER_CTL0_CAM); + TIMER_CTL0(timer_periph) |= (uint32_t)initpara->alignedmode; + TIMER_CTL0(timer_periph) |= (uint32_t)initpara->counterdirection; + } + + /* configure the autoreload value */ + TIMER_CAR(timer_periph) = (uint32_t)initpara->period; + + if((TIMER5 != timer_periph) && (TIMER6 != timer_periph)) { + /* reset the CKDIV bit */ + TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_CKDIV; + TIMER_CTL0(timer_periph) |= (uint32_t)initpara->clockdivision; + } + + if((TIMER0 == timer_periph) || (TIMER7 == timer_periph)) { + /* configure the repetition counter value */ + TIMER_CREP(timer_periph) = (uint32_t)initpara->repetitioncounter; + } + + /* generate an update event */ + TIMER_SWEVG(timer_periph) |= (uint32_t)TIMER_SWEVG_UPG; +} + +/*! + \brief enable a TIMER + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval none +*/ +void timer_enable(uint32_t timer_periph) +{ + TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_CEN; +} + +/*! + \brief disable a TIMER + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval none +*/ +void timer_disable(uint32_t timer_periph) +{ + TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_CEN; +} + +/*! + \brief enable the auto reload shadow function + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval none +*/ +void timer_auto_reload_shadow_enable(uint32_t timer_periph) +{ + TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_ARSE; +} + +/*! + \brief disable the auto reload shadow function + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval none +*/ +void timer_auto_reload_shadow_disable(uint32_t timer_periph) +{ + TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_ARSE; +} + +/*! + \brief enable the update event + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval none +*/ +void timer_update_event_enable(uint32_t timer_periph) +{ + TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_UPDIS; +} + +/*! + \brief disable the update event + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval none +*/ +void timer_update_event_disable(uint32_t timer_periph) +{ + TIMER_CTL0(timer_periph) |= (uint32_t) TIMER_CTL0_UPDIS; +} + +/*! + \brief set TIMER counter alignment mode + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[in] aligned: + only one parameter can be selected which is shown as below: + \arg TIMER_COUNTER_EDGE: edge-aligned mode + \arg TIMER_COUNTER_CENTER_DOWN: center-aligned and counting down assert mode + \arg TIMER_COUNTER_CENTER_UP: center-aligned and counting up assert mode + \arg TIMER_COUNTER_CENTER_BOTH: center-aligned and counting up/down assert mode + \param[out] none + \retval none +*/ +void timer_counter_alignment(uint32_t timer_periph, uint16_t aligned) +{ + TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_CAM; + TIMER_CTL0(timer_periph) |= (uint32_t)aligned; +} + +/*! + \brief set TIMER counter up direction + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[out] none + \retval none +*/ +void timer_counter_up_direction(uint32_t timer_periph) +{ + TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_DIR; +} + +/*! + \brief set TIMER counter down direction + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[out] none + \retval none +*/ +void timer_counter_down_direction(uint32_t timer_periph) +{ + TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_DIR; +} + +/*! + \brief configure TIMER prescaler + \param[in] timer_periph: TIMERx(x=0..13) + \param[in] prescaler: prescaler value,0~65535 + \param[in] pscreload: prescaler reload mode + only one parameter can be selected which is shown as below: + \arg TIMER_PSC_RELOAD_NOW: the prescaler is loaded right now + \arg TIMER_PSC_RELOAD_UPDATE: the prescaler is loaded at the next update event + \param[out] none + \retval none +*/ +void timer_prescaler_config(uint32_t timer_periph, uint16_t prescaler, uint8_t pscreload) +{ + TIMER_PSC(timer_periph) = (uint32_t)prescaler; + + if(TIMER_PSC_RELOAD_NOW == pscreload) { + TIMER_SWEVG(timer_periph) |= (uint32_t)TIMER_SWEVG_UPG; + } +} + +/*! + \brief configure TIMER repetition register value + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] repetition: the counter repetition value,0~255 + \param[out] none + \retval none +*/ +void timer_repetition_value_config(uint32_t timer_periph, uint16_t repetition) +{ + TIMER_CREP(timer_periph) = (uint32_t)repetition; +} + +/*! + \brief configure TIMER autoreload register value + \param[in] timer_periph: TIMERx(x=0..13) + \param[in] autoreload: the counter auto-reload value + \param[out] none + \retval none +*/ +void timer_autoreload_value_config(uint32_t timer_periph, uint32_t autoreload) +{ + TIMER_CAR(timer_periph) = (uint32_t)autoreload; +} + +/*! + \brief configure TIMER counter register value + \param[in] timer_periph: TIMERx(x=0..13) + \param[in] counter: the counter value,0~65535 + \param[out] none + \retval none +*/ +void timer_counter_value_config(uint32_t timer_periph, uint32_t counter) +{ + TIMER_CNT(timer_periph) = (uint32_t)counter; +} + +/*! + \brief read TIMER counter value + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval counter value +*/ +uint32_t timer_counter_read(uint32_t timer_periph) +{ + uint32_t count_value = 0U; + count_value = TIMER_CNT(timer_periph); + return (count_value); +} + +/*! + \brief read TIMER prescaler value + \param[in] timer_periph: TIMERx(x=0..13) + \param[out] none + \retval prescaler register value +*/ +uint16_t timer_prescaler_read(uint32_t timer_periph) +{ + uint16_t prescaler_value = 0U; + prescaler_value = (uint16_t)(TIMER_PSC(timer_periph)); + return (prescaler_value); +} + +/*! + \brief configure TIMER single pulse mode + \param[in] timer_periph: TIMERx(x=0..8,11) + \param[in] spmode: + only one parameter can be selected which is shown as below: + \arg TIMER_SP_MODE_SINGLE: single pulse mode + \arg TIMER_SP_MODE_REPETITIVE: repetitive pulse mode + \param[out] none + \retval none +*/ +void timer_single_pulse_mode_config(uint32_t timer_periph, uint32_t spmode) +{ + if(TIMER_SP_MODE_SINGLE == spmode) { + TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_SPM; + } else if(TIMER_SP_MODE_REPETITIVE == spmode) { + TIMER_CTL0(timer_periph) &= ~((uint32_t)TIMER_CTL0_SPM); + } else { + /* illegal parameters */ + } +} + +/*! + \brief configure TIMER update source + \param[in] timer_periph: TIMERx(x=0..13) + \param[in] update: + only one parameter can be selected which is shown as below: + \arg TIMER_UPDATE_SRC_GLOBAL: update generate by setting of UPG bit or the counter overflow/underflow,or the slave mode controller trigger + \arg TIMER_UPDATE_SRC_REGULAR: update generate only by counter overflow/underflow + \param[out] none + \retval none +*/ +void timer_update_source_config(uint32_t timer_periph, uint32_t update) +{ + if(TIMER_UPDATE_SRC_REGULAR == update) { + TIMER_CTL0(timer_periph) |= (uint32_t)TIMER_CTL0_UPS; + } else if(TIMER_UPDATE_SRC_GLOBAL == update) { + TIMER_CTL0(timer_periph) &= ~(uint32_t)TIMER_CTL0_UPS; + } else { + /* illegal parameters */ + } +} + +/*! + \brief enable the TIMER DMA + \param[in] timer_periph: please refer to the following parameters + \param[in] dma: specify which DMA to enable + one or more parameters can be selected which is shown as below: + \arg TIMER_DMA_UPD: update DMA,TIMERx(x=0..7) + \arg TIMER_DMA_CH0D: channel 0 DMA request,TIMERx(x=0..4,7) + \arg TIMER_DMA_CH1D: channel 1 DMA request,TIMERx(x=0..4,7) + \arg TIMER_DMA_CH2D: channel 2 DMA request,TIMERx(x=0..4,7) + \arg TIMER_DMA_CH3D: channel 3 DMA request,TIMERx(x=0..4,7) + \arg TIMER_DMA_CMTD: commutation DMA request,TIMERx(x=0,7) + \arg TIMER_DMA_TRGD: trigger DMA request,TIMERx(x=0..4,7) + \param[out] none + \retval none +*/ +void timer_dma_enable(uint32_t timer_periph, uint16_t dma) +{ + TIMER_DMAINTEN(timer_periph) |= (uint32_t) dma; +} + +/*! + \brief disable the TIMER DMA + \param[in] timer_periph: please refer to the following parameters + \param[in] dma: specify which DMA to disable + one or more parameters can be selected which are shown as below: + \arg TIMER_DMA_UPD: update DMA,TIMERx(x=0..7) + \arg TIMER_DMA_CH0D: channel 0 DMA request,TIMERx(x=0..4,7) + \arg TIMER_DMA_CH1D: channel 1 DMA request,TIMERx(x=0..4,7) + \arg TIMER_DMA_CH2D: channel 2 DMA request,TIMERx(x=0..4,7) + \arg TIMER_DMA_CH3D: channel 3 DMA request,TIMERx(x=0..4,7) + \arg TIMER_DMA_CMTD: commutation DMA request ,TIMERx(x=0,7) + \arg TIMER_DMA_TRGD: trigger DMA request,TIMERx(x=0..4,7) + \param[out] none + \retval none +*/ +void timer_dma_disable(uint32_t timer_periph, uint16_t dma) +{ + TIMER_DMAINTEN(timer_periph) &= (~(uint32_t)(dma)); +} + +/*! + \brief channel DMA request source selection + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[in] dma_request: channel DMA request source selection + only one parameter can be selected which is shown as below: + \arg TIMER_DMAREQUEST_CHANNELEVENT: DMA request of channel y is sent when channel y event occurs + \arg TIMER_DMAREQUEST_UPDATEEVENT: DMA request of channel y is sent when update event occurs + \param[out] none + \retval none +*/ +void timer_channel_dma_request_source_select(uint32_t timer_periph, uint8_t dma_request) +{ + if(TIMER_DMAREQUEST_UPDATEEVENT == dma_request) { + TIMER_CTL1(timer_periph) |= (uint32_t)TIMER_CTL1_DMAS; + } else if(TIMER_DMAREQUEST_CHANNELEVENT == dma_request) { + TIMER_CTL1(timer_periph) &= ~(uint32_t)TIMER_CTL1_DMAS; + } else { + /* illegal parameters */ + } +} + +/*! + \brief configure the TIMER DMA transfer + \param[in] timer_periph: please refer to the following parameters + \param[in] dma_baseaddr: + only one parameter can be selected which is shown as below: + \arg TIMER_DMACFG_DMATA_CTL0: DMA transfer address is TIMER_CTL0,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CTL1: DMA transfer address is TIMER_CTL1,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_SMCFG: DMA transfer address is TIMER_SMCFG,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_DMAINTEN: DMA transfer address is TIMER_DMAINTEN,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_INTF: DMA transfer address is TIMER_INTF,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_SWEVG: DMA transfer address is TIMER_SWEVG,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CHCTL0: DMA transfer address is TIMER_CHCTL0,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CHCTL1: DMA transfer address is TIMER_CHCTL1,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CHCTL2: DMA transfer address is TIMER_CHCTL2,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CNT: DMA transfer address is TIMER_CNT,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_PSC: DMA transfer address is TIMER_PSC,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CAR: DMA transfer address is TIMER_CAR,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CREP: DMA transfer address is TIMER_CREP,TIMERx(x=0,7) + \arg TIMER_DMACFG_DMATA_CH0CV: DMA transfer address is TIMER_CH0CV,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CH1CV: DMA transfer address is TIMER_CH1CV,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CH2CV: DMA transfer address is TIMER_CH2CV,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CH3CV: DMA transfer address is TIMER_CH3CV,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_CCHP: DMA transfer address is TIMER_CCHP,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_DMACFG: DMA transfer address is TIMER_DMACFG,TIMERx(x=0..4,7) + \arg TIMER_DMACFG_DMATA_DMATB: DMA transfer address is TIMER_DMATB,TIMERx(x=0..4,7) + \param[in] dma_lenth: + only one parameter can be selected which is shown as below: + \arg TIMER_DMACFG_DMATC_xTRANSFER(x=1..18): DMA transfer x time + \param[out] none + \retval none +*/ +void timer_dma_transfer_config(uint32_t timer_periph, uint32_t dma_baseaddr, uint32_t dma_lenth) +{ + TIMER_DMACFG(timer_periph) &= (~(uint32_t)(TIMER_DMACFG_DMATA | TIMER_DMACFG_DMATC)); + TIMER_DMACFG(timer_periph) |= (uint32_t)(dma_baseaddr | dma_lenth); +} + +/*! + \brief software generate events + \param[in] timer_periph: please refer to the following parameters + \param[in] event: the timer software event generation sources + one or more parameters can be selected which are shown as below: + \arg TIMER_EVENT_SRC_UPG: update event,TIMERx(x=0..13) + \arg TIMER_EVENT_SRC_CH0G: channel 0 capture or compare event generation,TIMERx(x=0..4,7..13) + \arg TIMER_EVENT_SRC_CH1G: channel 1 capture or compare event generation,TIMERx(x=0..4,7,8,11) + \arg TIMER_EVENT_SRC_CH2G: channel 2 capture or compare event generation,TIMERx(x=0..4,7) + \arg TIMER_EVENT_SRC_CH3G: channel 3 capture or compare event generation,TIMERx(x=0..4,7) + \arg TIMER_EVENT_SRC_CMTG: channel commutation event generation,TIMERx(x=0,7) + \arg TIMER_EVENT_SRC_TRGG: trigger event generation,TIMERx(x=0..4,7,8,11) + \arg TIMER_EVENT_SRC_BRKG: break event generation,TIMERx(x=0,7) + \arg TIMER_EVENT_SRC_CH0COMADDG: Channel 0 additional compare event generation, TIMERx(x=0,7) + \arg TIMER_EVENT_SRC_CH1COMADDG: Channel 1 additional compare event generation, TIMERx(x=0,7) + \arg TIMER_EVENT_SRC_CH2COMADDG: Channel 2 additional compare event generation, TIMERx(x=0,7) + \arg TIMER_EVENT_SRC_CH3COMADDG: Channel 3 additional compare event generation, TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_event_software_generate(uint32_t timer_periph, uint16_t event) +{ + TIMER_SWEVG(timer_periph) |= (uint32_t)event; +} + +/*! + \brief initialize TIMER break parameter struct + \param[in] breakpara: TIMER break parameter struct + \param[out] none + \retval none +*/ +void timer_break_struct_para_init(timer_break_parameter_struct *breakpara) +{ + /* initialize the break parameter struct member with the default value */ + breakpara->runoffstate = TIMER_ROS_STATE_DISABLE; + breakpara->ideloffstate = TIMER_IOS_STATE_DISABLE; + breakpara->deadtime = 0U; + breakpara->breakpolarity = TIMER_BREAK_POLARITY_LOW; + breakpara->outputautostate = TIMER_OUTAUTO_DISABLE; + breakpara->protectmode = TIMER_CCHP_PROT_OFF; + breakpara->breakstate = TIMER_BREAK_DISABLE; +} + +/*! + \brief configure TIMER break function + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] breakpara: TIMER break parameter struct + runoffstate: TIMER_ROS_STATE_ENABLE,TIMER_ROS_STATE_DISABLE + ideloffstate: TIMER_IOS_STATE_ENABLE,TIMER_IOS_STATE_DISABLE + deadtime: 0~255 + breakpolarity: TIMER_BREAK_POLARITY_LOW,TIMER_BREAK_POLARITY_HIGH + outputautostate: TIMER_OUTAUTO_ENABLE,TIMER_OUTAUTO_DISABLE + protectmode: TIMER_CCHP_PROT_OFF,TIMER_CCHP_PROT_0,TIMER_CCHP_PROT_1,TIMER_CCHP_PROT_2 + breakstate: TIMER_BREAK_ENABLE,TIMER_BREAK_DISABLE + \param[out] none + \retval none +*/ +void timer_break_config(uint32_t timer_periph, timer_break_parameter_struct *breakpara) +{ + TIMER_CCHP(timer_periph) = (uint32_t)(((uint32_t)(breakpara->runoffstate)) | + ((uint32_t)(breakpara->ideloffstate)) | + ((uint32_t)(breakpara->deadtime)) | + ((uint32_t)(breakpara->breakpolarity)) | + ((uint32_t)(breakpara->outputautostate)) | + ((uint32_t)(breakpara->protectmode)) | + ((uint32_t)(breakpara->breakstate))) ; +} + +/*! + \brief enable TIMER break function + \param[in] timer_periph: TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_break_enable(uint32_t timer_periph) +{ + TIMER_CCHP(timer_periph) |= (uint32_t)TIMER_CCHP_BRKEN; +} + +/*! + \brief disable TIMER break function + \param[in] timer_periph: TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_break_disable(uint32_t timer_periph) +{ + TIMER_CCHP(timer_periph) &= ~(uint32_t)TIMER_CCHP_BRKEN; +} + +/*! + \brief enable TIMER output automatic function + \param[in] timer_periph: TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_automatic_output_enable(uint32_t timer_periph) +{ + TIMER_CCHP(timer_periph) |= (uint32_t)TIMER_CCHP_OAEN; +} + +/*! + \brief disable TIMER output automatic function + \param[in] timer_periph: TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_automatic_output_disable(uint32_t timer_periph) +{ + TIMER_CCHP(timer_periph) &= ~(uint32_t)TIMER_CCHP_OAEN; +} + +/*! + \brief configure TIMER primary output function + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] newvalue: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void timer_primary_output_config(uint32_t timer_periph, ControlStatus newvalue) +{ + if(ENABLE == newvalue) { + TIMER_CCHP(timer_periph) |= (uint32_t)TIMER_CCHP_POEN; + } else { + TIMER_CCHP(timer_periph) &= (~(uint32_t)TIMER_CCHP_POEN); + } +} + +/*! + \brief enable or disable channel capture/compare control shadow register + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] newvalue: ENABLE or DISABLE + \param[out] none + \retval none +*/ +void timer_channel_control_shadow_config(uint32_t timer_periph, ControlStatus newvalue) +{ + if(ENABLE == newvalue) { + TIMER_CTL1(timer_periph) |= (uint32_t)TIMER_CTL1_CCSE; + } else { + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_CCSE); + } +} + +/*! + \brief configure TIMER channel control shadow register update control + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] ccuctl: channel control shadow register update control + only one parameter can be selected which is shown as below: + \arg TIMER_UPDATECTL_CCU: the shadow registers update by when CMTG bit is set + \arg TIMER_UPDATECTL_CCUTRI: the shadow registers update by when CMTG bit is set or an rising edge of TRGI occurs + \param[out] none + \retval none +*/ +void timer_channel_control_shadow_update_config(uint32_t timer_periph, uint8_t ccuctl) +{ + if(TIMER_UPDATECTL_CCU == ccuctl) { + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_CCUC); + } else if(TIMER_UPDATECTL_CCUTRI == ccuctl) { + TIMER_CTL1(timer_periph) |= (uint32_t)TIMER_CTL1_CCUC; + } else { + /* illegal parameters */ + } +} + +/*! + \brief initialize TIMER channel output parameter struct with a default value + \param[in] ocpara: TIMER channel n output parameter struct + \param[out] none + \retval none +*/ +void timer_channel_output_struct_para_init(timer_oc_parameter_struct *ocpara) +{ + /* initialize the channel output parameter struct member with the default value */ + ocpara->outputstate = (uint16_t)TIMER_CCX_DISABLE; + ocpara->outputnstate = TIMER_CCXN_DISABLE; + ocpara->ocpolarity = TIMER_OC_POLARITY_HIGH; + ocpara->ocnpolarity = TIMER_OCN_POLARITY_HIGH; + ocpara->ocidlestate = TIMER_OC_IDLE_STATE_LOW; + ocpara->ocnidlestate = TIMER_OCN_IDLE_STATE_LOW; +} + +/*! + \brief configure TIMER channel output function + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel 0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel 1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel 2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel 3(TIMERx(x=0..4,7)) + \param[in] ocpara: TIMER channeln output parameter struct + outputstate: TIMER_CCX_ENABLE,TIMER_CCX_DISABLE + outputnstate: TIMER_CCXN_ENABLE,TIMER_CCXN_DISABLE + ocpolarity: TIMER_OC_POLARITY_HIGH,TIMER_OC_POLARITY_LOW + ocnpolarity: TIMER_OCN_POLARITY_HIGH,TIMER_OCN_POLARITY_LOW + ocidlestate: TIMER_OC_IDLE_STATE_LOW,TIMER_OC_IDLE_STATE_HIGH + ocnidlestate: TIMER_OCN_IDLE_STATE_LOW,TIMER_OCN_IDLE_STATE_HIGH + \param[out] none + \retval none +*/ +void timer_channel_output_config(uint32_t timer_periph, uint16_t channel, + timer_oc_parameter_struct *ocpara) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + /* reset the CH0EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN); + TIMER_CHCTL0(timer_periph) &= ~(uint32_t)TIMER_CHCTL0_CH0MS; + /* set the CH0EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpara->outputstate; + /* reset the CH0P bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0P); + /* set the CH0P bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpara->ocpolarity; + + if((TIMER0 == timer_periph) || (TIMER7 == timer_periph)) { + /* reset the CH0NEN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0NEN); + /* set the CH0NEN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpara->outputnstate; + /* reset the CH0NP bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0NP); + /* set the CH0NP bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpara->ocnpolarity; + /* reset the ISO0 bit */ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO0); + /* set the ISO0 bit */ + TIMER_CTL1(timer_periph) |= (uint32_t)ocpara->ocidlestate; + /* reset the ISO0N bit */ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO0N); + /* set the ISO0N bit */ + TIMER_CTL1(timer_periph) |= (uint32_t)ocpara->ocnidlestate; + } + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + /* reset the CH1EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN); + TIMER_CHCTL0(timer_periph) &= ~(uint32_t)TIMER_CHCTL0_CH1MS; + /* set the CH1EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpara->outputstate << 4U); + /* reset the CH1P bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1P); + /* set the CH1P bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocpolarity) << 4U); + + if((TIMER0 == timer_periph) || (TIMER7 == timer_periph)) { + /* reset the CH1NEN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1NEN); + /* set the CH1NEN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->outputnstate) << 4U); + /* reset the CH1NP bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1NP); + /* set the CH1NP bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnpolarity) << 4U); + /* reset the ISO1 bit */ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO1); + /* set the ISO1 bit */ + TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocidlestate) << 2U); + /* reset the ISO1N bit */ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO1N); + /* set the ISO1N bit */ + TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnidlestate) << 2U); + } + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + /* reset the CH2EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2EN); + TIMER_CHCTL1(timer_periph) &= ~(uint32_t)TIMER_CHCTL1_CH2MS; + /* set the CH2EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpara->outputstate << 8U); + /* reset the CH2P bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2P); + /* set the CH2P bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocpolarity) << 8U); + + if((TIMER0 == timer_periph) || (TIMER7 == timer_periph)) { + /* reset the CH2NEN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2NEN); + /* set the CH2NEN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->outputnstate) << 8U); + /* reset the CH2NP bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2NP); + /* set the CH2NP bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnpolarity) << 8U); + /* reset the ISO2 bit */ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO2); + /* set the ISO2 bit */ + TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocidlestate) << 4U); + /* reset the ISO2N bit */ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO2N); + /* set the ISO2N bit */ + TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnidlestate) << 4U); + } + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + /* reset the CH3EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3EN); + TIMER_CHCTL1(timer_periph) &= ~(uint32_t)TIMER_CHCTL1_CH3MS; + /* set the CH3EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpara->outputstate << 12U); + /* reset the CH3P bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3P); + /* set the CH3P bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocpolarity) << 12U); + + if((TIMER0 == timer_periph) || (TIMER7 == timer_periph)) { + /* reset the CH3NEN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3NEN); + /* set the CH3NEN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->outputnstate) << 12U); + /* reset the CH3NP bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3NP); + /* set the CH3NP bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnpolarity) << 12U); + /* reset the ISO3 bit */ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO3); + /* set the ISO3 bit */ + TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocidlestate) << 6U); + /* reset the ISO3N bit */ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_ISO3N); + /* set the ISO3N bit */ + TIMER_CTL1(timer_periph) |= (uint32_t)((uint32_t)(ocpara->ocnidlestate) << 6U); + } + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel output compare mode + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] ocmode: channel output compare mode + only one parameter can be selected which is shown as below: + \arg TIMER_OC_MODE_TIMING: timing mode + \arg TIMER_OC_MODE_ACTIVE: active mode + \arg TIMER_OC_MODE_INACTIVE: inactive mode + \arg TIMER_OC_MODE_TOGGLE: toggle mode + \arg TIMER_OC_MODE_LOW: force low mode + \arg TIMER_OC_MODE_HIGH: force high mode + \arg TIMER_OC_MODE_PWM0: PWM0 mode + \arg TIMER_OC_MODE_PWM1: PWM1 mode + \param[out] none + \retval none +*/ +void timer_channel_output_mode_config(uint32_t timer_periph, uint16_t channel, uint16_t ocmode) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMCTL); + TIMER_CHCTL0(timer_periph) |= (uint32_t)ocmode; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMCTL); + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(ocmode) << 8U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMCTL); + TIMER_CHCTL1(timer_periph) |= (uint32_t)ocmode; + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMCTL); + TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(ocmode) << 8U); + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel output pulse value + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] pulse: channel output pulse value,0~65535 + \param[out] none + \retval none +*/ +void timer_channel_output_pulse_value_config(uint32_t timer_periph, uint16_t channel, + uint32_t pulse) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CH0CV(timer_periph) = (uint32_t)pulse; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CH1CV(timer_periph) = (uint32_t)pulse; + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CH2CV(timer_periph) = (uint32_t)pulse; + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CH3CV(timer_periph) = (uint32_t)pulse; + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel output shadow function + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] ocshadow: channel output shadow state + only one parameter can be selected which is shown as below: + \arg TIMER_OC_SHADOW_ENABLE: channel output shadow state enable + \arg TIMER_OC_SHADOW_DISABLE: channel output shadow state disable + \param[out] none + \retval none +*/ +void timer_channel_output_shadow_config(uint32_t timer_periph, uint16_t channel, uint16_t ocshadow) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMSEN); + TIMER_CHCTL0(timer_periph) |= (uint32_t)ocshadow; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMSEN); + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(ocshadow) << 8U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMSEN); + TIMER_CHCTL1(timer_periph) |= (uint32_t)ocshadow; + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMSEN); + TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(ocshadow) << 8U); + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel output fast function + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] ocfast: channel output fast function + only one parameter can be selected which is shown as below: + \arg TIMER_OC_FAST_ENABLE: channel output fast function enable + \arg TIMER_OC_FAST_DISABLE: channel output fast function disable + \param[out] none + \retval none +*/ +void timer_channel_output_fast_config(uint32_t timer_periph, uint16_t channel, uint16_t ocfast) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMFEN); + TIMER_CHCTL0(timer_periph) |= (uint32_t)ocfast; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMFEN); + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)ocfast << 8U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMFEN); + TIMER_CHCTL1(timer_periph) |= (uint32_t)ocfast; + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMFEN); + TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)ocfast << 8U); + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel output clear function + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] occlear: channel output clear function + only one parameter can be selected which is shown as below: + \arg TIMER_OC_CLEAR_ENABLE: channel output clear function enable + \arg TIMER_OC_CLEAR_DISABLE: channel output clear function disable + \param[out] none + \retval none +*/ +void timer_channel_output_clear_config(uint32_t timer_periph, uint16_t channel, uint16_t occlear) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMCEN); + TIMER_CHCTL0(timer_periph) |= (uint32_t)occlear; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMCEN); + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)occlear << 8U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMCEN); + TIMER_CHCTL1(timer_periph) |= (uint32_t)occlear; + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMCEN); + TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)occlear << 8U); + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel output polarity + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] ocpolarity: channel output polarity + only one parameter can be selected which is shown as below: + \arg TIMER_OC_POLARITY_HIGH: channel output polarity is high + \arg TIMER_OC_POLARITY_LOW: channel output polarity is low + \param[out] none + \retval none +*/ +void timer_channel_output_polarity_config(uint32_t timer_periph, uint16_t channel, + uint16_t ocpolarity) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0P); + TIMER_CHCTL2(timer_periph) |= (uint32_t)ocpolarity; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1P); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpolarity << 4U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2P); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpolarity << 8U); + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3P); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocpolarity << 12U); + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel complementary output polarity + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0,7)) + \param[in] ocnpolarity: channel complementary output polarity + only one parameter can be selected which is shown as below: + \arg TIMER_OCN_POLARITY_HIGH: channel complementary output polarity is high + \arg TIMER_OCN_POLARITY_LOW: channel complementary output polarity is low + \param[out] none + \retval none +*/ +void timer_channel_complementary_output_polarity_config(uint32_t timer_periph, uint16_t channel, + uint16_t ocnpolarity) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0NP); + TIMER_CHCTL2(timer_periph) |= (uint32_t)ocnpolarity; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1NP); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnpolarity << 4U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2NP); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnpolarity << 8U); + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3NP); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnpolarity << 12U); + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel enable state + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] state: TIMER channel enable state + only one parameter can be selected which is shown as below: + \arg TIMER_CCX_ENABLE: channel enable + \arg TIMER_CCX_DISABLE: channel disable + \param[out] none + \retval none +*/ +void timer_channel_output_state_config(uint32_t timer_periph, uint16_t channel, uint32_t state) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN); + TIMER_CHCTL2(timer_periph) |= (uint32_t)state; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)state << 4U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2EN); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)state << 8U); + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3EN); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)state << 12U); + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel complementary output enable state + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0 + \arg TIMER_CH_1: TIMER channel1 + \arg TIMER_CH_2: TIMER channel2 + \arg TIMER_CH_3: TIMER channel3 + \param[in] ocnstate: TIMER channel complementary output enable state + only one parameter can be selected which is shown as below: + \arg TIMER_CCXN_ENABLE: channel complementary enable + \arg TIMER_CCXN_DISABLE: channel complementary disable + \param[out] none + \retval none +*/ +void timer_channel_complementary_output_state_config(uint32_t timer_periph, uint16_t channel, + uint16_t ocnstate) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0NEN); + TIMER_CHCTL2(timer_periph) |= (uint32_t)ocnstate; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1NEN); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnstate << 4U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2NEN); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnstate << 8U); + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3NEN); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)ocnstate << 12U); + break; + default: + break; + } +} + +/*! + \brief initialize TIMER channel input parameter struct + \param[in] icpara: TIMER channel intput parameter struct + \param[out] none + \retval none +*/ +void timer_channel_input_struct_para_init(timer_ic_parameter_struct *icpara) +{ + /* initialize the channel input parameter struct member with the default value */ + icpara->icpolarity = TIMER_IC_POLARITY_RISING; + icpara->icselection = TIMER_IC_SELECTION_DIRECTTI; + icpara->icprescaler = TIMER_IC_PSC_DIV1; + icpara->icfilter = 0U; +} + +/*! + \brief configure TIMER input capture parameter + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] icpara: TIMER channel intput parameter struct + icpolarity: TIMER_IC_POLARITY_RISING,TIMER_IC_POLARITY_FALLING,TIMER_IC_POLARITY_BOTH_EDGE + icselection: TIMER_IC_SELECTION_DIRECTTI,TIMER_IC_SELECTION_INDIRECTTI,TIMER_IC_SELECTION_ITS + icprescaler: TIMER_IC_PSC_DIV1,TIMER_IC_PSC_DIV2,TIMER_IC_PSC_DIV4,TIMER_IC_PSC_DIV8 + icfilter: 0~15 + \param[out] none + \retval none +*/ +void timer_input_capture_config(uint32_t timer_periph, uint16_t channel, + timer_ic_parameter_struct *icpara) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + /* reset the CH0EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN); + + /* reset the CH0P and CH0NP bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP)); + TIMER_CHCTL2(timer_periph) |= (uint32_t)(icpara->icpolarity); + /* reset the CH0MS bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0MS); + TIMER_CHCTL0(timer_periph) |= (uint32_t)(icpara->icselection); + /* reset the CH0CAPFLT bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPFLT); + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpara->icfilter) << 4U); + + /* set the CH0EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH0EN; + break; + + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + /* reset the CH1EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN); + + /* reset the CH1P and CH1NP bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP)); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(icpara->icpolarity) << 4U); + /* reset the CH1MS bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1MS); + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpara->icselection) << 8U); + /* reset the CH1CAPFLT bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPFLT); + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpara->icfilter) << 12U); + + /* set the CH1EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH1EN; + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + /* reset the CH2EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH2EN); + + /* reset the CH2P and CH2NP bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH2P | TIMER_CHCTL2_CH2NP)); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(icpara->icpolarity) << 8U); + + /* reset the CH2MS bit */ + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2MS); + TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(icpara->icselection)); + + /* reset the CH2CAPFLT bit */ + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2CAPFLT); + TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(icpara->icfilter) << 4U); + + /* set the CH2EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH2EN; + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + /* reset the CH3EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH3EN); + + /* reset the CH3P bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH3P)); + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(icpara->icpolarity) << 12U); + + /* reset the CH3MS bit */ + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3MS); + TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(icpara->icselection) << 8U); + + /* reset the CH3CAPFLT bit */ + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3CAPFLT); + TIMER_CHCTL1(timer_periph) |= (uint32_t)((uint32_t)(icpara->icfilter) << 12U); + + /* set the CH3EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH3EN; + break; + default: + break; + } + /* configure TIMER channel input capture prescaler value */ + timer_channel_input_capture_prescaler_config(timer_periph, channel, + (uint16_t)(icpara->icprescaler)); +} + +/*! + \brief configure TIMER channel input capture prescaler value + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[in] prescaler: channel input capture prescaler value + only one parameter can be selected which is shown as below: + \arg TIMER_IC_PSC_DIV1: no prescaler + \arg TIMER_IC_PSC_DIV2: divided by 2 + \arg TIMER_IC_PSC_DIV4: divided by 4 + \arg TIMER_IC_PSC_DIV8: divided by 8 + \param[out] none + \retval none +*/ +void timer_channel_input_capture_prescaler_config(uint32_t timer_periph, uint16_t channel, + uint16_t prescaler) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPPSC); + TIMER_CHCTL0(timer_periph) |= (uint32_t)prescaler; + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPPSC); + TIMER_CHCTL0(timer_periph) |= ((uint32_t)prescaler << 8U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2CAPPSC); + TIMER_CHCTL1(timer_periph) |= (uint32_t)prescaler; + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3CAPPSC); + TIMER_CHCTL1(timer_periph) |= ((uint32_t)prescaler << 8U); + break; + default: + break; + } +} + +/*! + \brief read TIMER channel capture compare register value + \param[in] timer_periph: please refer to the following parameters + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0(TIMERx(x=0..4,7..13)) + \arg TIMER_CH_1: TIMER channel1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_CH_2: TIMER channel2(TIMERx(x=0..4,7)) + \arg TIMER_CH_3: TIMER channel3(TIMERx(x=0..4,7)) + \param[out] none + \retval channel capture compare register value +*/ +uint32_t timer_channel_capture_value_register_read(uint32_t timer_periph, uint16_t channel) +{ + uint32_t count_value = 0U; + + switch(channel) { + /* read TIMER channel 0 capture compare register value */ + case TIMER_CH_0: + count_value = TIMER_CH0CV(timer_periph); + break; + /* read TIMER channel 1 capture compare register value */ + case TIMER_CH_1: + count_value = TIMER_CH1CV(timer_periph); + break; + /* read TIMER channel 2 capture compare register value */ + case TIMER_CH_2: + count_value = TIMER_CH2CV(timer_periph); + break; + /* read TIMER channel 3 capture compare register value */ + case TIMER_CH_3: + count_value = TIMER_CH3CV(timer_periph); + break; + default: + break; + } + return (count_value); +} + +/*! + \brief configure TIMER input pwm capture function + \param[in] timer_periph: TIMERx(x=0..4,7,8,11) + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel0 + \arg TIMER_CH_1: TIMER channel1 + \param[in] icpwm:TIMER channel intput pwm parameter struct + icpolarity: TIMER_IC_POLARITY_RISING,TIMER_IC_POLARITY_FALLING + icselection: TIMER_IC_SELECTION_DIRECTTI,TIMER_IC_SELECTION_INDIRECTTI + icprescaler: TIMER_IC_PSC_DIV1,TIMER_IC_PSC_DIV2,TIMER_IC_PSC_DIV4,TIMER_IC_PSC_DIV8 + icfilter: 0~15 + \param[out] none + \retval none +*/ +void timer_input_pwm_capture_config(uint32_t timer_periph, uint16_t channel, + timer_ic_parameter_struct *icpwm) +{ + uint16_t icpolarity = 0x0U; + uint16_t icselection = 0x0U; + + /* Set channel input polarity */ + if(TIMER_IC_POLARITY_RISING == icpwm->icpolarity) { + icpolarity = TIMER_IC_POLARITY_FALLING; + } else { + icpolarity = TIMER_IC_POLARITY_RISING; + } + + /* Set channel input mode selection */ + if(TIMER_IC_SELECTION_DIRECTTI == icpwm->icselection) { + icselection = TIMER_IC_SELECTION_INDIRECTTI; + } else { + icselection = TIMER_IC_SELECTION_DIRECTTI; + } + + if(TIMER_CH_0 == channel) { + /* reset the CH0EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN); + /* reset the CH0P and CH0NP bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP)); + /* set the CH0P and CH0NP bits */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)(icpwm->icpolarity); + /* reset the CH0MS bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0MS); + /* set the CH0MS bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)(icpwm->icselection); + /* reset the CH0CAPFLT bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPFLT); + /* set the CH0CAPFLT bit */ + TIMER_CHCTL0(timer_periph) |= ((uint32_t)(icpwm->icfilter) << 4U); + /* set the CH0EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH0EN; + /* configure TIMER channel input capture prescaler value */ + timer_channel_input_capture_prescaler_config(timer_periph, TIMER_CH_0, + (uint16_t)(icpwm->icprescaler)); + + /* reset the CH1EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN); + /* reset the CH1P and CH1NP bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP)); + /* set the CH1P and CH1NP bits */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)icpolarity << 4U); + /* reset the CH1MS bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1MS); + /* set the CH1MS bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)icselection << 8U); + /* reset the CH1CAPFLT bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPFLT); + /* set the CH1CAPFLT bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpwm->icfilter) << 12U); + /* set the CH1EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH1EN; + /* configure TIMER channel input capture prescaler value */ + timer_channel_input_capture_prescaler_config(timer_periph, TIMER_CH_1, + (uint16_t)(icpwm->icprescaler)); + } else { + /* reset the CH1EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN); + /* reset the CH1P and CH1NP bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP)); + /* set the CH1P and CH1NP bits */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)(icpwm->icpolarity) << 4U); + /* reset the CH1MS bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1MS); + /* set the CH1MS bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpwm->icselection) << 8U); + /* reset the CH1CAPFLT bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPFLT); + /* set the CH1CAPFLT bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)(icpwm->icfilter) << 12U); + /* set the CH1EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH1EN; + /* configure TIMER channel input capture prescaler value */ + timer_channel_input_capture_prescaler_config(timer_periph, TIMER_CH_1, + (uint16_t)(icpwm->icprescaler)); + + /* reset the CH0EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN); + /* reset the CH0P and CH0NP bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP)); + /* set the CH0P and CH0NP bits */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)icpolarity; + /* reset the CH0MS bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0MS); + /* set the CH0MS bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)icselection; + /* reset the CH0CAPFLT bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPFLT); + /* set the CH0CAPFLT bit */ + TIMER_CHCTL0(timer_periph) |= ((uint32_t)(icpwm->icfilter) << 4U); + /* set the CH0EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH0EN; + /* configure TIMER channel input capture prescaler value */ + timer_channel_input_capture_prescaler_config(timer_periph, TIMER_CH_0, + (uint16_t)(icpwm->icprescaler)); + } +} + +/*! + \brief configure TIMER hall sensor mode + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[in] hallmode: + only one parameter can be selected which is shown as below: + \arg TIMER_HALLINTERFACE_ENABLE: TIMER hall sensor mode enable + \arg TIMER_HALLINTERFACE_DISABLE: TIMER hall sensor mode disable + \param[out] none + \retval none +*/ +void timer_hall_mode_config(uint32_t timer_periph, uint32_t hallmode) +{ + if(TIMER_HALLINTERFACE_ENABLE == hallmode) { + TIMER_CTL1(timer_periph) |= (uint32_t)TIMER_CTL1_TI0S; + } else if(TIMER_HALLINTERFACE_DISABLE == hallmode) { + TIMER_CTL1(timer_periph) &= ~(uint32_t)TIMER_CTL1_TI0S; + } else { + /* illegal parameters */ + } +} + +/*! + \brief select TIMER input trigger source + \param[in] timer_periph: please refer to the following parameters + \param[in] intrigger: + only one parameter can be selected which is shown as below: + \arg TIMER_SMCFG_TRGSEL_ITI0: internal trigger 0(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SMCFG_TRGSEL_ITI1: internal trigger 1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SMCFG_TRGSEL_ITI2: internal trigger 2(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SMCFG_TRGSEL_ITI3: internal trigger 3(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SMCFG_TRGSEL_CI0F_ED: TI0 edge detector(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SMCFG_TRGSEL_CI0FE0: filtered TIMER input 0(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SMCFG_TRGSEL_CI1FE1: filtered TIMER input 1(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SMCFG_TRGSEL_ETIFP: external trigger(TIMERx(x=0..4,7,8,11)) + \param[out] none + \retval none +*/ +void timer_input_trigger_source_select(uint32_t timer_periph, uint32_t intrigger) +{ + TIMER_SMCFG(timer_periph) &= (~(uint32_t)TIMER_SMCFG_TRGS); + TIMER_SMCFG(timer_periph) |= (uint32_t)intrigger; +} + +/*! + \brief select TIMER master mode output trigger source + \param[in] timer_periph: TIMERx(x=0..7) + \param[in] outrigger: + only one parameter can be selected which is shown as below: + \arg TIMER_TRI_OUT_SRC_RESET: the UPG bit as trigger output(TIMERx(x=0..7,9,10,12,13)) + \arg TIMER_TRI_OUT_SRC_ENABLE: the counter enable signal TIMER_CTL0_CEN as trigger output(TIMERx(x=0..7,9,10,12,13)) + \arg TIMER_TRI_OUT_SRC_UPDATE: update event as trigger output(TIMERx(x=0..7,9,10,12,13)) + \arg TIMER_TRI_OUT_SRC_CH0: a capture or a compare match occurred in channal0 as trigger output TRGO(TIMERx(x=0..4,7,9,10,12,13)) + \arg TIMER_TRI_OUT_SRC_O0CPRE: O0CPRE as trigger output(TIMERx(x=0..4,7,9,10,12,13)) + \arg TIMER_TRI_OUT_SRC_O1CPRE: O1CPRE as trigger output(TIMERx(x=0..4,7)) + \arg TIMER_TRI_OUT_SRC_O2CPRE: O2CPRE as trigger output(TIMERx(x=0..4,7)) + \arg TIMER_TRI_OUT_SRC_O3CPRE: O3CPRE as trigger output(TIMERx(x=0..4,7)) + \param[out] none + \retval none +*/ +void timer_master_output_trigger_source_select(uint32_t timer_periph, uint32_t outrigger) +{ + TIMER_CTL1(timer_periph) &= (~(uint32_t)TIMER_CTL1_MMC); + TIMER_CTL1(timer_periph) |= (uint32_t)outrigger; +} + +/*! + \brief select TIMER slave mode + \param[in] timer_periph: TIMERx(x=0..4,7,8,11) + \param[in] slavemode: + only one parameter can be selected which is shown as below: + \arg TIMER_SLAVE_MODE_DISABLE: slave mode disable(TIMERx(x=0..4,7,8,11)) + \arg TIMER_ENCODER_MODE0: encoder mode 0(TIMERx(x=0..4,7)) + \arg TIMER_ENCODER_MODE1: encoder mode 1(TIMERx(x=0..4,7)) + \arg TIMER_ENCODER_MODE2: encoder mode 2(TIMERx(x=0..4,7)) + \arg TIMER_SLAVE_MODE_RESTART: restart mode(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SLAVE_MODE_PAUSE: pause mode(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SLAVE_MODE_EVENT: event mode(TIMERx(x=0..4,7,8,11)) + \arg TIMER_SLAVE_MODE_EXTERNAL0: external clock mode 0.(TIMERx(x=0..4,7,8,11)) + \param[out] none + \retval none +*/ + +void timer_slave_mode_select(uint32_t timer_periph, uint32_t slavemode) +{ + TIMER_SMCFG(timer_periph) &= (~(uint32_t)TIMER_SMCFG_SMC); + + TIMER_SMCFG(timer_periph) |= (uint32_t)slavemode; +} + +/*! + \brief configure TIMER master slave mode + \param[in] timer_periph: TIMERx(x=0..4,7,8,11) + \param[in] masterslave: + only one parameter can be selected which is shown as below: + \arg TIMER_MASTER_SLAVE_MODE_ENABLE: master slave mode enable + \arg TIMER_MASTER_SLAVE_MODE_DISABLE: master slave mode disable + \param[out] none + \retval none +*/ +void timer_master_slave_mode_config(uint32_t timer_periph, uint32_t masterslave) +{ + if(TIMER_MASTER_SLAVE_MODE_ENABLE == masterslave) { + TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SMCFG_MSM; + } else if(TIMER_MASTER_SLAVE_MODE_DISABLE == masterslave) { + TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_MSM; + } else { + /* illegal parameters */ + } +} + +/*! + \brief configure TIMER external trigger input + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[in] extprescaler: + only one parameter can be selected which is shown as below: + \arg TIMER_EXT_TRI_PSC_OFF: no divided + \arg TIMER_EXT_TRI_PSC_DIV2: divided by 2 + \arg TIMER_EXT_TRI_PSC_DIV4: divided by 4 + \arg TIMER_EXT_TRI_PSC_DIV8: divided by 8 + \param[in] extpolarity: + only one parameter can be selected which is shown as below: + \arg TIMER_ETP_FALLING: active low or falling edge active + \arg TIMER_ETP_RISING: active high or rising edge active + \param[in] extfilter: a value between 0 and 15 + \param[out] none + \retval none +*/ +void timer_external_trigger_config(uint32_t timer_periph, uint32_t extprescaler, + uint32_t extpolarity, uint32_t extfilter) +{ + TIMER_SMCFG(timer_periph) &= (~(uint32_t)(TIMER_SMCFG_ETP | TIMER_SMCFG_ETPSC | TIMER_SMCFG_ETFC)); + TIMER_SMCFG(timer_periph) |= (uint32_t)(extprescaler | extpolarity); + TIMER_SMCFG(timer_periph) |= (uint32_t)(extfilter << 8U); +} + +/*! + \brief configure TIMER quadrature decoder mode + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[in] decomode: + only one parameter can be selected which is shown as below: + \arg TIMER_ENCODER_MODE0: counter counts on CI0FE0 edge depending on CI1FE1 level + \arg TIMER_ENCODER_MODE1: counter counts on CI1FE1 edge depending on CI0FE0 level + \arg TIMER_ENCODER_MODE2: counter counts on both CI0FE0 and CI1FE1 edges depending on the level of the other input + \param[in] ic0polarity: + only one parameter can be selected which is shown as below: + \arg TIMER_IC_POLARITY_RISING: capture rising edge + \arg TIMER_IC_POLARITY_FALLING: capture falling edge + \param[in] ic1polarity: + only one parameter can be selected which is shown as below: + \arg TIMER_IC_POLARITY_RISING: capture rising edge + \arg TIMER_IC_POLARITY_FALLING: capture falling edge + \param[out] none + \retval none +*/ +void timer_quadrature_decoder_mode_config(uint32_t timer_periph, uint32_t decomode, + uint16_t ic0polarity, uint16_t ic1polarity) +{ + TIMER_SMCFG(timer_periph) &= (~(uint32_t)TIMER_SMCFG_SMC); + TIMER_SMCFG(timer_periph) |= (uint32_t)decomode; + + TIMER_CHCTL0(timer_periph) &= (uint32_t)(((~(uint32_t)TIMER_CHCTL0_CH0MS)) & ((~ + (uint32_t)TIMER_CHCTL0_CH1MS))); + TIMER_CHCTL0(timer_periph) |= (uint32_t)(TIMER_IC_SELECTION_DIRECTTI | (( + uint32_t)TIMER_IC_SELECTION_DIRECTTI << 8U)); + + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP)); + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP)); + TIMER_CHCTL2(timer_periph) |= ((uint32_t)ic0polarity | ((uint32_t)ic1polarity << 4U)); +} + +/*! + \brief configure TIMER internal clock mode + \param[in] timer_periph: TIMERx(x=0..4,7,8,11) + \param[out] none + \retval none +*/ +void timer_internal_clock_config(uint32_t timer_periph) +{ + TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_SMC; +} + +/*! + \brief configure TIMER the internal trigger as external clock input + \param[in] timer_periph: TIMERx(x=0..4,7,8,11) + \param[in] intrigger: + only one parameter can be selected which is shown as below: + \arg TIMER_SMCFG_TRGSEL_ITI0: internal trigger 0 + \arg TIMER_SMCFG_TRGSEL_ITI1: internal trigger 1 + \arg TIMER_SMCFG_TRGSEL_ITI2: internal trigger 2 + \arg TIMER_SMCFG_TRGSEL_ITI3: internal trigger 3 + \param[out] none + \retval none +*/ +void timer_internal_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t intrigger) +{ + timer_input_trigger_source_select(timer_periph, intrigger); + TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_SMC; + TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SLAVE_MODE_EXTERNAL0; +} + +/*! + \brief configure TIMER the external trigger as external clock input + \param[in] timer_periph: TIMERx(x=0..4,7,8,11) + \param[in] extrigger: + only one parameter can be selected which is shown as below: + \arg TIMER_SMCFG_TRGSEL_CI0F_ED: TI0 edge detector + \arg TIMER_SMCFG_TRGSEL_CI0FE0: filtered TIMER input 0 + \arg TIMER_SMCFG_TRGSEL_CI1FE1: filtered TIMER input 1 + \param[in] extpolarity: + only one parameter can be selected which is shown as below: + \arg TIMER_IC_POLARITY_RISING: active high or rising edge active + \arg TIMER_IC_POLARITY_FALLING: active low or falling edge active + \param[in] extfilter: a value between 0 and 15 + \param[out] none + \retval none +*/ +void timer_external_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t extrigger, + uint16_t extpolarity, uint32_t extfilter) +{ + if(TIMER_SMCFG_TRGSEL_CI1FE1 == extrigger) { + /* reset the CH1EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH1EN); + /* reset the CH1NP bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH1P | TIMER_CHCTL2_CH1NP)); + /* set the CH1NP bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)((uint32_t)extpolarity << 4U); + /* reset the CH1MS bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1MS); + /* set the CH1MS bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)((uint32_t)TIMER_IC_SELECTION_DIRECTTI << 8U); + /* reset the CH1CAPFLT bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1CAPFLT); + /* set the CH1CAPFLT bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)(extfilter << 12U); + /* set the CH1EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH1EN; + } else { + /* reset the CH0EN bit */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)TIMER_CHCTL2_CH0EN); + /* reset the CH0P and CH0NP bits */ + TIMER_CHCTL2(timer_periph) &= (~(uint32_t)(TIMER_CHCTL2_CH0P | TIMER_CHCTL2_CH0NP)); + /* set the CH0P and CH0NP bits */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)extpolarity; + /* reset the CH0MS bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0MS); + /* set the CH0MS bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)TIMER_IC_SELECTION_DIRECTTI; + /* reset the CH0CAPFLT bit */ + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0CAPFLT); + /* reset the CH0CAPFLT bit */ + TIMER_CHCTL0(timer_periph) |= (uint32_t)(extfilter << 4U); + /* set the CH0EN bit */ + TIMER_CHCTL2(timer_periph) |= (uint32_t)TIMER_CHCTL2_CH0EN; + } + /* select TIMER input trigger source */ + timer_input_trigger_source_select(timer_periph, extrigger); + /* reset the SMC bit */ + TIMER_SMCFG(timer_periph) &= (~(uint32_t)TIMER_SMCFG_SMC); + /* set the SMC bit */ + TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SLAVE_MODE_EXTERNAL0; +} + +/*! + \brief configure TIMER the external clock mode0 + \param[in] timer_periph: TIMERx(x=0..4,7,8,11) + \param[in] extprescaler: + only one parameter can be selected which is shown as below: + \arg TIMER_EXT_TRI_PSC_OFF: no divided + \arg TIMER_EXT_TRI_PSC_DIV2: divided by 2 + \arg TIMER_EXT_TRI_PSC_DIV4: divided by 4 + \arg TIMER_EXT_TRI_PSC_DIV8: divided by 8 + \param[in] extpolarity: + only one parameter can be selected which is shown as below: + \arg TIMER_ETP_FALLING: active low or falling edge active + \arg TIMER_ETP_RISING: active high or rising edge active + \param[in] extfilter: a value between 0 and 15 + \param[out] none + \retval none +*/ +void timer_external_clock_mode0_config(uint32_t timer_periph, uint32_t extprescaler, + uint32_t extpolarity, uint32_t extfilter) +{ + /* configure TIMER external trigger input */ + timer_external_trigger_config(timer_periph, extprescaler, extpolarity, extfilter); + + /* reset the SMC bit,TRGS bit */ + TIMER_SMCFG(timer_periph) &= (~(uint32_t)(TIMER_SMCFG_SMC | TIMER_SMCFG_TRGS)); + /* set the SMC bit,TRGS bit */ + TIMER_SMCFG(timer_periph) |= (uint32_t)(TIMER_SLAVE_MODE_EXTERNAL0 | TIMER_SMCFG_TRGSEL_ETIFP); +} + +/*! + \brief configure TIMER the external clock mode1 + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[in] extprescaler: + only one parameter can be selected which is shown as below: + \arg TIMER_EXT_TRI_PSC_OFF: no divided + \arg TIMER_EXT_TRI_PSC_DIV2: divided by 2 + \arg TIMER_EXT_TRI_PSC_DIV4: divided by 4 + \arg TIMER_EXT_TRI_PSC_DIV8: divided by 8 + \param[in] extpolarity: + only one parameter can be selected which is shown as below: + \arg TIMER_ETP_FALLING: active low or falling edge active + \arg TIMER_ETP_RISING: active high or rising edge active + \param[in] extfilter: a value between 0 and 15 + \param[out] none + \retval none +*/ +void timer_external_clock_mode1_config(uint32_t timer_periph, uint32_t extprescaler, + uint32_t extpolarity, uint32_t extfilter) +{ + /* configure TIMER external trigger input */ + timer_external_trigger_config(timer_periph, extprescaler, extpolarity, extfilter); + + TIMER_SMCFG(timer_periph) |= (uint32_t)TIMER_SMCFG_SMC1; +} + +/*! + \brief disable TIMER the external clock mode1 + \param[in] timer_periph: TIMERx(x=0..4,7) + \param[out] none + \retval none +*/ +void timer_external_clock_mode1_disable(uint32_t timer_periph) +{ + TIMER_SMCFG(timer_periph) &= ~(uint32_t)TIMER_SMCFG_SMC1; +} + +/*! + \brief configure TIMER channel remap function + \param[in] timer_periph: TIMERx(x=1,4,10) + \param[in] remap: + only one parameter can be selected which is shown as below: + \arg TIMER1_ITI1_RMP_TIMER7_TRGO: timer1 internal trigger input1 remap to TIMER7_TRGO + \arg TIMER1_ITI1_RMP_ETHERNET_PTP: timer1 internal trigger input1 remap to ethernet PTP + \arg TIMER1_ITI1_RMP_USB_FS_SOF: timer1 internal trigger input1 remap to USB FS SOF + \arg TIMER1_ITI1_RMP_USB_HS_SOF: timer1 internal trigger input1 remap to USB HS SOF + \arg TIMER4_CI3_RMP_GPIO: timer4 channel 3 input remap to GPIO pin + \arg TIMER4_CI3_RMP_IRC32K: timer4 channel 3 input remap to IRC32K + \arg TIMER4_CI3_RMP_LXTAL: timer4 channel 3 input remap to LXTAL + \arg TIMER4_CI3_RMP_RTC_WAKEUP_INT: timer4 channel 3 input remap to RTC wakeup interrupt + \arg TIMER10_ITI1_RMP_GPIO: timer10 internal trigger input1 remap based on GPIO setting + \arg TIMER10_ITI1_RMP_RTC_HXTAL_DIV: timer10 internal trigger input1 remap HXTAL _DIV(clock used for RTC which is HXTAL clock divided by RTCDIV bits in RCU_CFG0 register) + \param[out] none + \retval none +*/ +void timer_channel_remap_config(uint32_t timer_periph, uint32_t remap) +{ + TIMER_IRMP(timer_periph) = (uint32_t)remap; +} + +/*! + \brief configure TIMER write CHxVAL register selection + \param[in] timer_periph: TIMERx(x=0,1,2,13,14,15,16) + \param[in] ccsel: + only one parameter can be selected which is shown as below: + \arg TIMER_CHVSEL_DISABLE: no effect + \arg TIMER_CHVSEL_ENABLE: when write the CHxVAL register, if the write value is same as the CHxVAL value, the write access is ignored + \param[out] none + \retval none +*/ +void timer_write_chxval_register_config(uint32_t timer_periph, uint16_t ccsel) +{ + if(TIMER_CHVSEL_ENABLE == ccsel) { + TIMER_CFG(timer_periph) |= (uint32_t)TIMER_CFG_CHVSEL; + } else if(TIMER_CHVSEL_DISABLE == ccsel) { + TIMER_CFG(timer_periph) &= ~(uint32_t)TIMER_CFG_CHVSEL; + } else { + /* illegal parameters */ + } +} + +/*! + \brief configure TIMER output value selection + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] outsel: + only one parameter can be selected which is shown as below: + \arg TIMER_OUTSEL_DISABLE: no effect + \arg TIMER_OUTSEL_ENABLE: if POEN and IOS is 0, the output disabled + \param[out] none + \retval none +*/ +void timer_output_value_selection_config(uint32_t timer_periph, uint16_t outsel) +{ + if(TIMER_OUTSEL_ENABLE == outsel) { + TIMER_CFG(timer_periph) |= (uint32_t)TIMER_CFG_OUTSEL; + } else if(TIMER_OUTSEL_DISABLE == outsel) { + TIMER_CFG(timer_periph) &= ~(uint32_t)TIMER_CFG_OUTSEL; + } else { + /* illegal parameters */ + } +} + +/*! + \brief enable the TIMER composite pwm + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel 0(TIMERx(x=0,7)) + \arg TIMER_CH_1: TIMER channel 1(TIMERx(x=0,7)) + \arg TIMER_CH_2: TIMER channel 2(TIMERx(x=0,7)) + \arg TIMER_CH_3: TIMER channel 3(TIMERx(x=0,7)) + \param[out] none + \retval none +*/ +void timer_channel_composite_pwm_enable(uint32_t timer_periph, uint32_t channel) +{ + TIMER_CTL2(timer_periph) |= (uint32_t)(TIMER_CTL2_CH0CPWMEN << channel); +} + +/*! + \brief disable the TIMER composite pwm + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel 0(TIMERx(x=0,7)) + \arg TIMER_CH_1: TIMER channel 1(TIMERx(x=0,7)) + \arg TIMER_CH_2: TIMER channel 2(TIMERx(x=0,7)) + \arg TIMER_CH_3: TIMER channel 3(TIMERx(x=0,7)) + \param[out] none + \retval none +*/ +void timer_channel_composite_pwm_disable(uint32_t timer_periph, uint32_t channel) +{ + TIMER_CTL2(timer_periph) &= (~(uint32_t)(TIMER_CTL2_CH0CPWMEN << channel)); +} + +/*! + \brief configure TIMER channel additional compare value + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel 0(TIMERx(x=0,7)) + \arg TIMER_CH_1: TIMER channel 1(TIMERx(x=0,7)) + \arg TIMER_CH_2: TIMER channel 2(TIMERx(x=0,7)) + \arg TIMER_CH_3: TIMER channel 3(TIMERx(x=0,7)) + \param[in] value: channel additional compare value + \param[out] none + \retval none +*/ +void timer_channel_additional_compare_value_config(uint32_t timer_periph, uint16_t channel, + uint32_t value) +{ + switch(channel) { + /* configure CH0COMV_ADD value */ + case TIMER_CH_0: + TIMER_CH0COMV_ADD(timer_periph) = (uint32_t)value; + break; + /* configure CH1COMV_ADD value */ + case TIMER_CH_1: + TIMER_CH1COMV_ADD(timer_periph) = (uint32_t)value; + break; + /* configure CH2COMV_ADD value */ + case TIMER_CH_2: + TIMER_CH2COMV_ADD(timer_periph) = (uint32_t)value; + break; + /* configure CH3COMV_ADD value */ + case TIMER_CH_3: + TIMER_CH3COMV_ADD(timer_periph) = (uint32_t)value; + break; + default: + break; + } +} + +/*! + \brief configure TIMER channel additional output shadow function + \param[in] timer_periph: TIMERx(x=0~4,7,14~16,22,23,30,31,40~44) + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel 0(TIMERx(x=0,7)) + \arg TIMER_CH_1: TIMER channel 1(TIMERx(x=0,7)) + \arg TIMER_CH_2: TIMER channel 2(TIMERx(x=0,7)) + \arg TIMER_CH_3: TIMER channel 3(TIMERx(x=0,7)) + \param[in] ocshadow: channel additional compare output shadow state + only one parameter can be selected which is shown as below: + \arg TIMER_ADD_SHADOW_ENABLE: channel additional compare output shadow enable + \arg TIMER_ADD_SHADOW_DISABLE: channel additional compare output shadow disable + \param[out] none + \retval none +*/ +void timer_channel_additional_output_shadow_config(uint32_t timer_periph, uint16_t channel, + uint16_t ocshadow) +{ + switch(channel) { + /* configure TIMER_CH_0 */ + case TIMER_CH_0: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH0COMADDSEN); + TIMER_CHCTL0(timer_periph) |= ((uint32_t)(ocshadow) << 28U); + break; + /* configure TIMER_CH_1 */ + case TIMER_CH_1: + TIMER_CHCTL0(timer_periph) &= (~(uint32_t)TIMER_CHCTL0_CH1COMADDSEN); + TIMER_CHCTL0(timer_periph) |= ((uint32_t)(ocshadow) << 29U); + break; + /* configure TIMER_CH_2 */ + case TIMER_CH_2: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH2COMADDSEN); + TIMER_CHCTL1(timer_periph) |= ((uint32_t)(ocshadow) << 28U); + break; + /* configure TIMER_CH_3 */ + case TIMER_CH_3: + TIMER_CHCTL1(timer_periph) &= (~(uint32_t)TIMER_CHCTL1_CH3COMADDSEN); + TIMER_CHCTL1(timer_periph) |= ((uint32_t)(ocshadow) << 29U); + break; + default: + break; + } +} + +/*! + \brief read TIMER channel additional compare value + \param[in] timer_periph: TIMERx(x=0,7) + \param[in] channel: + only one parameter can be selected which is shown as below: + \arg TIMER_CH_0: TIMER channel 0(TIMERx(x=0,7)) + \arg TIMER_CH_1: TIMER channel 1(TIMERx(x=0,7)) + \arg TIMER_CH_2: TIMER channel 2(TIMERx(x=0,7)) + \arg TIMER_CH_3: TIMER channel 3(TIMERx(x=0,7)) + \param[out] none + \retval value: channel additional compare value +*/ +uint32_t timer_channel_additional_compare_value_read(uint32_t timer_periph, uint16_t channel) +{ + uint32_t value = 0U; + switch(channel) { + case TIMER_CH_0: + /* read CH0COMV_ADD value */ + value = TIMER_CH0COMV_ADD(timer_periph); + break; + case TIMER_CH_1: + /* read CH1COMV_ADD value */ + value = TIMER_CH1COMV_ADD(timer_periph); + break; + case TIMER_CH_2: + /* read CH2COMV_ADD value */ + value = TIMER_CH2COMV_ADD(timer_periph); + break; + case TIMER_CH_3: + /* read CH3COMV_ADD value */ + value = TIMER_CH3COMV_ADD(timer_periph); + break; + default: + break; + } + return value; +} + +/*! + \brief get TIMER flags + \param[in] timer_periph: please refer to the following parameters + \param[in] flag: the timer interrupt flags + only one parameter can be selected which is shown as below: + \arg TIMER_FLAG_UP: update flag,TIMERx(x=0..13) + \arg TIMER_FLAG_CH0: channel 0 flag,TIMERx(x=0..4,7..13) + \arg TIMER_FLAG_CH1: channel 1 flag,TIMERx(x=0..4,7,8,11) + \arg TIMER_FLAG_CH2: channel 2 flag,TIMERx(x=0..4,7) + \arg TIMER_FLAG_CH3: channel 3 flag,TIMERx(x=0..4,7) + \arg TIMER_FLAG_CMT: channel control update flag,TIMERx(x=0,7) + \arg TIMER_FLAG_TRG: trigger flag,TIMERx(x=0,7,8,11) + \arg TIMER_FLAG_BRK: break flag,TIMERx(x=0,7) + \arg TIMER_FLAG_CH0O: channel 0 overcapture flag,TIMERx(x=0..4,7..11) + \arg TIMER_FLAG_CH1O: channel 1 overcapture flag,TIMERx(x=0..4,7,8,11) + \arg TIMER_FLAG_CH2O: channel 2 overcapture flag,TIMERx(x=0..4,7) + \arg TIMER_FLAG_CH3O: channel 3 overcapture flag,TIMERx(x=0..4,7) + \arg TIMER_FLAG_CH0COMADD: Channel 0 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_FLAG_CH1COMADD: Channel 1 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_FLAG_CH2COMADD: Channel 2 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_FLAG_CH3COMADD: Channel 3 additional compare interrupt flag, TIMERx(x=0,7) + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus timer_flag_get(uint32_t timer_periph, uint32_t flag) +{ + if(RESET != (TIMER_INTF(timer_periph) & flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear TIMER flags + \param[in] timer_periph: please refer to the following parameters + \param[in] flag: the timer interrupt flags + only one parameter can be selected which is shown as below: + \arg TIMER_FLAG_UP: update flag,TIMERx(x=0..13) + \arg TIMER_FLAG_CH0: channel 0 flag,TIMERx(x=0..4,7..13) + \arg TIMER_FLAG_CH1: channel 1 flag,TIMERx(x=0..4,7,8,11) + \arg TIMER_FLAG_CH2: channel 2 flag,TIMERx(x=0..4,7) + \arg TIMER_FLAG_CH3: channel 3 flag,TIMERx(x=0..4,7) + \arg TIMER_FLAG_CMT: channel control update flag,TIMERx(x=0,7) + \arg TIMER_FLAG_TRG: trigger flag,TIMERx(x=0,7,8,11) + \arg TIMER_FLAG_BRK: break flag,TIMERx(x=0,7) + \arg TIMER_FLAG_CH0O: channel 0 overcapture flag,TIMERx(x=0..4,7..11) + \arg TIMER_FLAG_CH1O: channel 1 overcapture flag,TIMERx(x=0..4,7,8,11) + \arg TIMER_FLAG_CH2O: channel 2 overcapture flag,TIMERx(x=0..4,7) + \arg TIMER_FLAG_CH3O: channel 3 overcapture flag,TIMERx(x=0..4,7) + \arg TIMER_FLAG_CH0COMADD: Channel 0 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_FLAG_CH1COMADD: Channel 1 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_FLAG_CH2COMADD: Channel 2 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_FLAG_CH3COMADD: Channel 3 additional compare interrupt flag, TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_flag_clear(uint32_t timer_periph, uint32_t flag) +{ + TIMER_INTF(timer_periph) &= (~(uint32_t)flag); +} + +/*! + \brief enable the TIMER interrupt + \param[in] timer_periph: please refer to the following parameters + \param[in] interrupt: timer interrupt enable source + only one parameter can be selected which is shown as below: + \arg TIMER_INT_UP: update interrupt enable, TIMERx(x=0..13) + \arg TIMER_INT_CH0: channel 0 interrupt enable, TIMERx(x=0..4,7..13) + \arg TIMER_INT_CH1: channel 1 interrupt enable, TIMERx(x=0..4,7,8,11) + \arg TIMER_INT_CH2: channel 2 interrupt enable, TIMERx(x=0..4,7) + \arg TIMER_INT_CH3: channel 3 interrupt enable , TIMERx(x=0..4,7) + \arg TIMER_INT_CMT: commutation interrupt enable, TIMERx(x=0,7) + \arg TIMER_INT_TRG: trigger interrupt enable, TIMERx(x=0..4,7,8,11) + \arg TIMER_INT_BRK: break interrupt enable, TIMERx(x=0,7) + \arg TIMER_INT_CH0COMADD: channel 0 additional compare interrupt enable, TIMERx(x=0,7) + \arg TIMER_INT_CH1COMADD: channel 1 additional compare interrupt enable, TIMERx(x=0,7) + \arg TIMER_INT_CH2COMADD: channel 2 additional compare interrupt enable, TIMERx(x=0,7) + \arg TIMER_INT_CH3COMADD: channel 3 additional compare interrupt enable, TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_interrupt_enable(uint32_t timer_periph, uint32_t interrupt) +{ + TIMER_DMAINTEN(timer_periph) |= (uint32_t) interrupt; +} + +/*! + \brief disable the TIMER interrupt + \param[in] timer_periph: please refer to the following parameters + \param[in] interrupt: timer interrupt source enable + only one parameter can be selected which is shown as below: + \arg TIMER_INT_UP: update interrupt enable, TIMERx(x=0..13) + \arg TIMER_INT_CH0: channel 0 interrupt enable, TIMERx(x=0..4,7..13) + \arg TIMER_INT_CH1: channel 1 interrupt enable, TIMERx(x=0..4,7,8,11) + \arg TIMER_INT_CH2: channel 2 interrupt enable, TIMERx(x=0..4,7) + \arg TIMER_INT_CH3: channel 3 interrupt enable , TIMERx(x=0..4,7) + \arg TIMER_INT_CMT: commutation interrupt enable, TIMERx(x=0,7) + \arg TIMER_INT_TRG: trigger interrupt enable, TIMERx(x=0..4,7,8,11) + \arg TIMER_INT_BRK: break interrupt enable, TIMERx(x=0,7) + \arg TIMER_INT_CH0COMADD: channel 0 additional compare interrupt disable, TIMERx(x=0,7) + \arg TIMER_INT_CH1COMADD: channel 1 additional compare interrupt disable, TIMERx(x=0,7) + \arg TIMER_INT_CH2COMADD: channel 2 additional compare interrupt disable, TIMERx(x=0,7) + \arg TIMER_INT_CH3COMADD: channel 3 additional compare interrupt disable, TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_interrupt_disable(uint32_t timer_periph, uint32_t interrupt) +{ + TIMER_DMAINTEN(timer_periph) &= (~(uint32_t)interrupt); +} + +/*! + \brief get timer interrupt flag + \param[in] timer_periph: please refer to the following parameters + \param[in] interrupt: the timer interrupt bits + only one parameter can be selected which is shown as below: + \arg TIMER_INT_FLAG_UP: update interrupt flag,TIMERx(x=0..13) + \arg TIMER_INT_FLAG_CH0: channel 0 interrupt flag,TIMERx(x=0..4,7..13) + \arg TIMER_INT_FLAG_CH1: channel 1 interrupt flag,TIMERx(x=0..4,7,8,11) + \arg TIMER_INT_FLAG_CH2: channel 2 interrupt flag,TIMERx(x=0..4,7) + \arg TIMER_INT_FLAG_CH3: channel 3 interrupt flag,TIMERx(x=0..4,7) + \arg TIMER_INT_FLAG_CMT: channel commutation interrupt flag,TIMERx(x=0,7) + \arg TIMER_INT_FLAG_TRG: trigger interrupt flag,TIMERx(x=0,7,8,11) + \arg TIMER_INT_FLAG_BRK: break interrupt flag,TIMERx(x=0,7) + \arg TIMER_INT_FLAG_CH0COMADD: channel 0 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_INT_FLAG_CH1COMADD: channel 1 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_INT_FLAG_CH2COMADD: channel 2 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_INT_FLAG_CH3COMADD: channel 3 additional compare interrupt flag, TIMERx(x=0,7) + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus timer_interrupt_flag_get(uint32_t timer_periph, uint32_t interrupt) +{ + uint32_t val; + val = (TIMER_DMAINTEN(timer_periph) & interrupt); + if((RESET != (TIMER_INTF(timer_periph) & interrupt)) && (RESET != val)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear TIMER interrupt flag + \param[in] timer_periph: please refer to the following parameters + \param[in] interrupt: the timer interrupt bits + only one parameter can be selected which is shown as below: + \arg TIMER_INT_FLAG_UP: update interrupt flag,TIMERx(x=0..13) + \arg TIMER_INT_FLAG_CH0: channel 0 interrupt flag,TIMERx(x=0..4,7..13) + \arg TIMER_INT_FLAG_CH1: channel 1 interrupt flag,TIMERx(x=0..4,7,8,11) + \arg TIMER_INT_FLAG_CH2: channel 2 interrupt flag,TIMERx(x=0..4,7) + \arg TIMER_INT_FLAG_CH3: channel 3 interrupt flag,TIMERx(x=0..4,7) + \arg TIMER_INT_FLAG_CMT: channel commutation interrupt flag,TIMERx(x=0,7) + \arg TIMER_INT_FLAG_TRG: trigger interrupt flag,TIMERx(x=0,7,8,11) + \arg TIMER_INT_FLAG_BRK: break interrupt flag,TIMERx(x=0,7) + \arg TIMER_INT_FLAG_CH0COMADD: channel 0 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_INT_FLAG_CH1COMADD: channel 1 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_INT_FLAG_CH2COMADD: channel 2 additional compare interrupt flag, TIMERx(x=0,7) + \arg TIMER_INT_FLAG_CH3COMADD: channel 3 additional compare interrupt flag, TIMERx(x=0,7) + \param[out] none + \retval none +*/ +void timer_interrupt_flag_clear(uint32_t timer_periph, uint32_t interrupt) +{ + TIMER_INTF(timer_periph) &= (~(uint32_t)interrupt); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_tli.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_tli.c new file mode 100644 index 0000000..d47a79e --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_tli.c @@ -0,0 +1,595 @@ +/*! + \file gd32f5xx_tli.c + \brief TLI driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_tli.h" + +#define TLI_DEFAULT_VALUE 0x00000000U +#define TLI_OPAQUE_VALUE 0x000000FFU + +/*! + \brief deinitialize TLI registers + \param[in] none + \param[out] none + \retval none +*/ +void tli_deinit(void) +{ + rcu_periph_reset_enable(RCU_TLIRST); + rcu_periph_reset_disable(RCU_TLIRST); +} + +/*! + \brief initialize the parameters of TLI parameter structure with the default values, it is suggested + that call this function after a tli_parameter_struct structure is defined + \param[in] none + \param[out] tli_struct: the data needed to initialize TLI + synpsz_vpsz: size of the vertical synchronous pulse + synpsz_hpsz: size of the horizontal synchronous pulse + backpsz_vbpsz: size of the vertical back porch plus synchronous pulse + backpsz_hbpsz: size of the horizontal back porch plus synchronous pulse + activesz_vasz: size of the vertical active area width plus back porch and synchronous pulse + activesz_hasz: size of the horizontal active area width plus back porch and synchronous pulse + totalsz_vtsz: vertical total size of the display, including active area, back porch, synchronous + totalsz_htsz: vorizontal total size of the display, including active area, back porch, synchronous + backcolor_red: background value red + backcolor_green: background value green + backcolor_blue: background value blue + signalpolarity_hs: TLI_HSYN_ACTLIVE_LOW,TLI_HSYN_ACTLIVE_HIGHT + signalpolarity_vs: TLI_VSYN_ACTLIVE_LOW,TLI_VSYN_ACTLIVE_HIGHT + signalpolarity_de: TLI_DE_ACTLIVE_LOW,TLI_DE_ACTLIVE_HIGHT + signalpolarity_pixelck: TLI_PIXEL_CLOCK_TLI,TLI_PIXEL_CLOCK_INVERTEDTLI + \retval none +*/ +void tli_struct_para_init(tli_parameter_struct *tli_struct) +{ + /* initialize the struct parameters with default values */ + tli_struct->synpsz_vpsz = TLI_DEFAULT_VALUE; + tli_struct->synpsz_hpsz = TLI_DEFAULT_VALUE; + tli_struct->backpsz_vbpsz = TLI_DEFAULT_VALUE; + tli_struct->backpsz_hbpsz = TLI_DEFAULT_VALUE; + tli_struct->activesz_vasz = TLI_DEFAULT_VALUE; + tli_struct->activesz_hasz = TLI_DEFAULT_VALUE; + tli_struct->totalsz_vtsz = TLI_DEFAULT_VALUE; + tli_struct->totalsz_htsz = TLI_DEFAULT_VALUE; + tli_struct->backcolor_red = TLI_DEFAULT_VALUE; + tli_struct->backcolor_green = TLI_DEFAULT_VALUE; + tli_struct->backcolor_blue = TLI_DEFAULT_VALUE; + tli_struct->signalpolarity_hs = TLI_HSYN_ACTLIVE_LOW; + tli_struct->signalpolarity_vs = TLI_VSYN_ACTLIVE_LOW; + tli_struct->signalpolarity_de = TLI_DE_ACTLIVE_LOW; + tli_struct->signalpolarity_pixelck = TLI_PIXEL_CLOCK_TLI; +} + +/*! + \brief initialize TLI display timing parameters + \param[in] tli_struct: the data needed to initialize TLI + synpsz_vpsz: size of the vertical synchronous pulse + synpsz_hpsz: size of the horizontal synchronous pulse + backpsz_vbpsz: size of the vertical back porch plus synchronous pulse + backpsz_hbpsz: size of the horizontal back porch plus synchronous pulse + activesz_vasz: size of the vertical active area width plus back porch and synchronous pulse + activesz_hasz: size of the horizontal active area width plus back porch and synchronous pulse + totalsz_vtsz: vertical total size of the display, including active area, back porch, synchronous + totalsz_htsz: vorizontal total size of the display, including active area, back porch, synchronous + backcolor_red: background value red + backcolor_green: background value green + backcolor_blue: background value blue + signalpolarity_hs: TLI_HSYN_ACTLIVE_LOW,TLI_HSYN_ACTLIVE_HIGHT + signalpolarity_vs: TLI_VSYN_ACTLIVE_LOW,TLI_VSYN_ACTLIVE_HIGHT + signalpolarity_de: TLI_DE_ACTLIVE_LOW,TLI_DE_ACTLIVE_HIGHT + signalpolarity_pixelck: TLI_PIXEL_CLOCK_TLI,TLI_PIXEL_CLOCK_INVERTEDTLI + \param[out] none + \retval none +*/ +void tli_init(tli_parameter_struct *tli_struct) +{ + /* synchronous pulse size configuration */ + TLI_SPSZ &= ~(TLI_SPSZ_VPSZ | TLI_SPSZ_HPSZ); + TLI_SPSZ = (uint32_t)((uint32_t)tli_struct->synpsz_vpsz | ((uint32_t)tli_struct->synpsz_hpsz << 16U)); + /* back-porch size configuration */ + TLI_BPSZ &= ~(TLI_BPSZ_VBPSZ | TLI_BPSZ_HBPSZ); + TLI_BPSZ = (uint32_t)((uint32_t)tli_struct->backpsz_vbpsz | ((uint32_t)tli_struct->backpsz_hbpsz << 16U)); + /* active size configuration */ + TLI_ASZ &= ~(TLI_ASZ_VASZ | TLI_ASZ_HASZ); + TLI_ASZ = (tli_struct->activesz_vasz | (tli_struct->activesz_hasz << 16U)); + /* total size configuration */ + TLI_TSZ &= ~(TLI_TSZ_VTSZ | TLI_TSZ_HTSZ); + TLI_TSZ = (tli_struct->totalsz_vtsz | (tli_struct->totalsz_htsz << 16U)); + /* background color configuration */ + TLI_BGC &= ~(TLI_BGC_BVB | (TLI_BGC_BVG) | (TLI_BGC_BVR)); + TLI_BGC = (tli_struct->backcolor_blue | (tli_struct->backcolor_green << 8U) | (tli_struct->backcolor_red << 16U)); + TLI_CTL &= ~(TLI_CTL_HPPS | TLI_CTL_VPPS | TLI_CTL_DEPS | TLI_CTL_CLKPS); + TLI_CTL |= (tli_struct->signalpolarity_hs | tli_struct->signalpolarity_vs | \ + tli_struct->signalpolarity_de | tli_struct->signalpolarity_pixelck); + +} + +/*! + \brief configure TLI dither function + \param[in] dither_stat + only one parameter can be selected which is shown as below: + \arg TLI_DITHER_ENABLE + \arg TLI_DITHER_DISABLE + \param[out] none + \retval none +*/ +void tli_dither_config(uint8_t dither_stat) +{ + if(TLI_DITHER_ENABLE == dither_stat) { + TLI_CTL |= TLI_CTL_DFEN; + } else { + TLI_CTL &= ~(TLI_CTL_DFEN); + } +} + +/*! + \brief enable TLI + \param[in] none + \param[out] none + \retval none +*/ +void tli_enable(void) +{ + TLI_CTL |= TLI_CTL_TLIEN; +} + +/*! + \brief disable TLI + \param[in] none + \param[out] none + \retval none +*/ +void tli_disable(void) +{ + TLI_CTL &= ~(TLI_CTL_TLIEN); +} + +/*! + \brief configure TLI reload mode + \param[in] reload_mod + only one parameter can be selected which is shown as below: + \arg TLI_FRAME_BLANK_RELOAD_EN + \arg TLI_REQUEST_RELOAD_EN + \param[out] none + \retval none +*/ +void tli_reload_config(uint8_t reload_mod) +{ + if(TLI_FRAME_BLANK_RELOAD_EN == reload_mod) { + /* the layer configuration will be reloaded at frame blank */ + TLI_RL |= TLI_RL_FBR; + } else { + /* the layer configuration will be reloaded after this bit sets */ + TLI_RL |= TLI_RL_RQR; + } +} + +/*! + \brief initialize the parameters of TLI layer structure with the default values, it is suggested + that call this function after a tli_layer_parameter_struct structure is defined + \param[in] none + \param[out] layer_struct: TLI Layer parameter struct + layer_window_rightpos: window right position + layer_window_leftpos: window left position + layer_window_bottompos: window bottom position + layer_window_toppos: window top position + layer_ppf: LAYER_PPF_ARGB8888,LAYER_PPF_RGB888,LAYER_PPF_RGB565, + LAYER_PPF_ARG1555,LAYER_PPF_ARGB4444,LAYER_PPF_L8, + LAYER_PPF_AL44,LAYER_PPF_AL88 + layer_sa: specified alpha + layer_default_alpha: the default color alpha + layer_default_red: the default color red + layer_default_green: the default color green + layer_default_blue: the default color blue + layer_acf1: LAYER_ACF1_SA,LAYER_ACF1_PASA + layer_acf2: LAYER_ACF2_SA,LAYER_ACF2_PASA + layer_frame_bufaddr: frame buffer base address + layer_frame_buf_stride_offset: frame buffer stride offset + layer_frame_line_length: frame line length + layer_frame_total_line_number: frame total line number + \retval none +*/ +void tli_layer_struct_para_init(tli_layer_parameter_struct *layer_struct) +{ + /* initialize the struct parameters with default values */ + layer_struct->layer_window_rightpos = TLI_DEFAULT_VALUE; + layer_struct->layer_window_leftpos = TLI_DEFAULT_VALUE; + layer_struct->layer_window_bottompos = TLI_DEFAULT_VALUE; + layer_struct->layer_window_toppos = TLI_DEFAULT_VALUE; + layer_struct->layer_ppf = LAYER_PPF_ARGB8888; + layer_struct->layer_sa = TLI_OPAQUE_VALUE; + layer_struct->layer_default_alpha = TLI_DEFAULT_VALUE; + layer_struct->layer_default_red = TLI_DEFAULT_VALUE; + layer_struct->layer_default_green = TLI_DEFAULT_VALUE; + layer_struct->layer_default_blue = TLI_DEFAULT_VALUE; + layer_struct->layer_acf1 = LAYER_ACF1_PASA; + layer_struct->layer_acf2 = LAYER_ACF2_PASA; + layer_struct->layer_frame_bufaddr = TLI_DEFAULT_VALUE; + layer_struct->layer_frame_buf_stride_offset = TLI_DEFAULT_VALUE; + layer_struct->layer_frame_line_length = TLI_DEFAULT_VALUE; + layer_struct->layer_frame_total_line_number = TLI_DEFAULT_VALUE; +} + +/*! + \brief initialize TLI layer + \param[in] layerx: LAYERx(x=0,1) + \param[in] layer_struct: TLI Layer parameter struct + layer_window_rightpos: window right position + layer_window_leftpos: window left position + layer_window_bottompos: window bottom position + layer_window_toppos: window top position + layer_ppf: LAYER_PPF_ARGB8888,LAYER_PPF_RGB888,LAYER_PPF_RGB565, + LAYER_PPF_ARG1555,LAYER_PPF_ARGB4444,LAYER_PPF_L8, + LAYER_PPF_AL44,LAYER_PPF_AL88 + layer_sa: specified alpha + layer_default_alpha: the default color alpha + layer_default_red: the default color red + layer_default_green: the default color green + layer_default_blue: the default color blue + layer_acf1: LAYER_ACF1_SA,LAYER_ACF1_PASA + layer_acf2: LAYER_ACF2_SA,LAYER_ACF2_PASA + layer_frame_bufaddr: frame buffer base address + layer_frame_buf_stride_offset: frame buffer stride offset + layer_frame_line_length: frame line length + layer_frame_total_line_number: frame total line number + \param[out] none + \retval none +*/ +void tli_layer_init(uint32_t layerx, tli_layer_parameter_struct *layer_struct) +{ + /* configure layer window horizontal position */ + TLI_LxHPOS(layerx) &= ~(TLI_LxHPOS_WLP | (TLI_LxHPOS_WRP)); + TLI_LxHPOS(layerx) = (uint32_t)((uint32_t)layer_struct->layer_window_leftpos | ((uint32_t)layer_struct->layer_window_rightpos << 16U)); + /* configure layer window vertical position */ + TLI_LxVPOS(layerx) &= ~(TLI_LxVPOS_WTP | (TLI_LxVPOS_WBP)); + TLI_LxVPOS(layerx) = (uint32_t)((uint32_t)layer_struct->layer_window_toppos | ((uint32_t)layer_struct->layer_window_bottompos << 16U)); + /* configure layer packeted pixel format */ + TLI_LxPPF(layerx) &= ~(TLI_LxPPF_PPF); + TLI_LxPPF(layerx) = layer_struct->layer_ppf; + /* configure layer specified alpha */ + TLI_LxSA(layerx) &= ~(TLI_LxSA_SA); + TLI_LxSA(layerx) = layer_struct->layer_sa; + /* configure layer default color */ + TLI_LxDC(layerx) &= ~(TLI_LxDC_DCB | (TLI_LxDC_DCG) | (TLI_LxDC_DCR) | (TLI_LxDC_DCA)); + TLI_LxDC(layerx) = (uint32_t)((uint32_t)layer_struct->layer_default_blue | ((uint32_t)layer_struct->layer_default_green << 8U) + | ((uint32_t)layer_struct->layer_default_red << 16U) + | ((uint32_t)layer_struct->layer_default_alpha << 24U)); + + /* configure layer alpha calculation factors */ + TLI_LxBLEND(layerx) &= ~(TLI_LxBLEND_ACF2 | (TLI_LxBLEND_ACF1)); + TLI_LxBLEND(layerx) = ((layer_struct->layer_acf2) | (layer_struct->layer_acf1)); + /* configure layer frame buffer base address */ + TLI_LxFBADDR(layerx) &= ~(TLI_LxFBADDR_FBADD); + TLI_LxFBADDR(layerx) = (layer_struct->layer_frame_bufaddr); + /* configure layer frame line length */ + TLI_LxFLLEN(layerx) &= ~(TLI_LxFLLEN_FLL | (TLI_LxFLLEN_STDOFF)); + TLI_LxFLLEN(layerx) = (uint32_t)((uint32_t)layer_struct->layer_frame_line_length | ((uint32_t)layer_struct->layer_frame_buf_stride_offset << 16U)); + /* configure layer frame total line number */ + TLI_LxFTLN(layerx) &= ~(TLI_LxFTLN_FTLN); + TLI_LxFTLN(layerx) = (uint32_t)(layer_struct->layer_frame_total_line_number); + +} + +/*! + \brief reconfigure window position + \param[in] layerx: LAYERx(x=0,1) + \param[in] offset_x: new horizontal offset + \param[in] offset_y: new vertical offset + \param[out] none + \retval none +*/ +void tli_layer_window_offset_modify(uint32_t layerx, uint16_t offset_x, uint16_t offset_y) +{ + /* configure window start position */ + uint32_t layer_ppf, line_num, hstart, vstart; + uint32_t line_length = 0U; + TLI_LxHPOS(layerx) &= ~(TLI_LxHPOS_WLP | (TLI_LxHPOS_WRP)); + TLI_LxVPOS(layerx) &= ~(TLI_LxVPOS_WTP | (TLI_LxVPOS_WBP)); + hstart = (uint32_t)offset_x + (((TLI_BPSZ & TLI_BPSZ_HBPSZ) >> 16U) + 1U); + vstart = (uint32_t)offset_y + ((TLI_BPSZ & TLI_BPSZ_VBPSZ) + 1U); + line_num = (TLI_LxFTLN(layerx) & TLI_LxFTLN_FTLN); + layer_ppf = (TLI_LxPPF(layerx) & TLI_LxPPF_PPF); + /* the bytes of a line equal TLI_LxFLLEN_FLL bits value minus 3 */ + switch(layer_ppf) { + case LAYER_PPF_ARGB8888: + /* each pixel includes 4bytes, when pixel format is ARGB8888 */ + line_length = (((TLI_LxFLLEN(layerx) & TLI_LxFLLEN_FLL) - 3U) / 4U); + break; + case LAYER_PPF_RGB888: + /* each pixel includes 3bytes, when pixel format is RGB888 */ + line_length = (((TLI_LxFLLEN(layerx) & TLI_LxFLLEN_FLL) - 3U) / 3U); + break; + case LAYER_PPF_RGB565: + case LAYER_PPF_ARGB1555: + case LAYER_PPF_ARGB4444: + case LAYER_PPF_AL88: + /* each pixel includes 2bytes, when pixel format is RGB565,ARG1555,ARGB4444 or AL88 */ + line_length = (((TLI_LxFLLEN(layerx) & TLI_LxFLLEN_FLL) - 3U) / 2U); + break; + case LAYER_PPF_L8: + case LAYER_PPF_AL44: + /* each pixel includes 1byte, when pixel format is L8 or AL44 */ + line_length = (((TLI_LxFLLEN(layerx) & TLI_LxFLLEN_FLL) - 3U)); + break; + default: + break; + } + /* reconfigure window position */ + TLI_LxHPOS(layerx) = (hstart | ((hstart + line_length - 1U) << 16U)); + TLI_LxVPOS(layerx) = (vstart | ((vstart + line_num - 1U) << 16U)); +} + +/*! + \brief initialize the parameters of TLI layer LUT structure with the default values, it is suggested + that call this function after a tli_layer_lut_parameter_struct structure is defined + \param[in] none + \param[out] lut_struct: TLI layer LUT parameter struct + layer_table_addr: look up table write address + layer_lut_channel_red: red channel of a LUT entry + layer_lut_channel_green: green channel of a LUT entry + layer_lut_channel_blue: blue channel of a LUT entry + \retval none +*/ +void tli_lut_struct_para_init(tli_layer_lut_parameter_struct *lut_struct) +{ + /* initialize the struct parameters with default values */ + lut_struct->layer_table_addr = TLI_DEFAULT_VALUE; + lut_struct->layer_lut_channel_red = TLI_DEFAULT_VALUE; + lut_struct->layer_lut_channel_green = TLI_DEFAULT_VALUE; + lut_struct->layer_lut_channel_blue = TLI_DEFAULT_VALUE; +} + +/*! + \brief initialize TLI layer LUT + \param[in] layerx: LAYERx(x=0,1) + \param[in] lut_struct: TLI layer LUT parameter struct + layer_table_addr: look up table write address + layer_lut_channel_red: red channel of a LUT entry + layer_lut_channel_green: green channel of a LUT entry + layer_lut_channel_blue: blue channel of a LUT entry + \param[out] none + \retval none +*/ +void tli_lut_init(uint32_t layerx, tli_layer_lut_parameter_struct *lut_struct) +{ + TLI_LxLUT(layerx) = (uint32_t)(((uint32_t)lut_struct->layer_lut_channel_blue) | ((uint32_t)lut_struct->layer_lut_channel_green << 8U) + | ((uint32_t)lut_struct->layer_lut_channel_red << 16U + | ((uint32_t)lut_struct->layer_table_addr << 24U))); +} + +/*! + \brief initialize TLI layer color key + \param[in] layerx: LAYERx(x=0,1) + \param[in] redkey: color key red + \param[in] greenkey: color key green + \param[in] bluekey: color key blue + \param[out] none + \retval none +*/ +void tli_color_key_init(uint32_t layerx, uint8_t redkey, uint8_t greenkey, uint8_t bluekey) +{ + TLI_LxCKEY(layerx) = (((uint32_t)bluekey) | ((uint32_t)greenkey << 8U) | ((uint32_t)redkey << 16U)); +} + +/*! + \brief enable TLI layer + \param[in] layerx: LAYERx(x=0,1) + \param[out] none + \retval none +*/ +void tli_layer_enable(uint32_t layerx) +{ + TLI_LxCTL(layerx) |= TLI_LxCTL_LEN; +} + +/*! + \brief disable TLI layer + \param[in] layerx: LAYERx(x=0,1) + \param[out] none + \retval none +*/ +void tli_layer_disable(uint32_t layerx) +{ + TLI_LxCTL(layerx) &= ~(TLI_LxCTL_LEN); +} + +/*! + \brief enable TLI layer color keying + \param[in] layerx: LAYERx(x=0,1) + \param[out] none + \retval none +*/ +void tli_color_key_enable(uint32_t layerx) +{ + TLI_LxCTL(layerx) |= TLI_LxCTL_CKEYEN; +} + +/*! + \brief disable TLI layer color keying + \param[in] layerx: LAYERx(x=0,1) + \param[out] none + \retval none +*/ +void tli_color_key_disable(uint32_t layerx) +{ + TLI_LxCTL(layerx) &= ~(TLI_LxCTL_CKEYEN); +} + +/*! + \brief enable TLI layer LUT + \param[in] layerx: LAYERx(x=0,1) + \param[out] none + \retval none +*/ +void tli_lut_enable(uint32_t layerx) +{ + TLI_LxCTL(layerx) |= TLI_LxCTL_LUTEN; +} + +/*! + \brief disable TLI layer LUT + \param[in] layerx: LAYERx(x=0,1) + \param[out] none + \retval none +*/ +void tli_lut_disable(uint32_t layerx) +{ + TLI_LxCTL(layerx) &= ~(TLI_LxCTL_LUTEN); +} + +/*! + \brief set line mark value + \param[in] line_num: line number + \param[out] none + \retval none +*/ +void tli_line_mark_set(uint16_t line_num) +{ + TLI_LM &= ~(TLI_LM_LM); + TLI_LM = (uint32_t)line_num; +} + +/*! + \brief get current displayed position + \param[in] none + \param[out] none + \retval position of current pixel +*/ +uint32_t tli_current_pos_get(void) +{ + return TLI_CPPOS; +} + +/*! + \brief enable TLI interrupt + \param[in] int_flag: TLI interrupt flags + one or more parameters can be selected which are shown as below: + \arg TLI_INT_LM: line mark interrupt + \arg TLI_INT_FE: FIFO error interrupt + \arg TLI_INT_TE: transaction error interrupt + \arg TLI_INT_LCR: layer configuration reloaded interrupt + \param[out] none + \retval none +*/ +void tli_interrupt_enable(uint32_t int_flag) +{ + TLI_INTEN |= (int_flag); +} + +/*! + \brief disable TLI interrupt + \param[in] int_flag: TLI interrupt flags + one or more parameters can be selected which are shown as below: + \arg TLI_INT_LM: line mark interrupt + \arg TLI_INT_FE: FIFO error interrupt + \arg TLI_INT_TE: transaction error interrupt + \arg TLI_INT_LCR: layer configuration reloaded interrupt + \param[out] none + \retval none +*/ +void tli_interrupt_disable(uint32_t int_flag) +{ + TLI_INTEN &= ~(int_flag); +} + +/*! + \brief get TLI interrupt flag + \param[in] int_flag: TLI interrupt flags + one or more parameters can be selected which are shown as below: + \arg TLI_INT_FLAG_LM: line mark interrupt flag + \arg TLI_INT_FLAG_FE: FIFO error interrupt flag + \arg TLI_INT_FLAG_TE: transaction error interrupt flag + \arg TLI_INT_FLAG_LCR: layer configuration reloaded interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus tli_interrupt_flag_get(uint32_t int_flag) +{ + uint32_t state; + state = TLI_INTF; + if(state & int_flag) { + state = TLI_INTEN; + if(state & int_flag) { + return SET; + } + } + return RESET; +} + +/*! + \brief clear TLI interrupt flag + \param[in] int_flag: TLI interrupt flags + one or more parameters can be selected which are shown as below: + \arg TLI_INT_FLAG_LM: line mark interrupt flag + \arg TLI_INT_FLAG_FE: FIFO error interrupt flag + \arg TLI_INT_FLAG_TE: transaction error interrupt flag + \arg TLI_INT_FLAG_LCR: layer configuration reloaded interrupt flag + \param[out] none + \retval none +*/ +void tli_interrupt_flag_clear(uint32_t int_flag) +{ + TLI_INTC |= (int_flag); +} + +/*! + \brief get TLI flag or state in TLI_INTF register or TLI_STAT register + \param[in] flag: TLI flags or states + only one parameter can be selected which is shown as below: + \arg TLI_FLAG_VDE: current VDE state + \arg TLI_FLAG_HDE: current HDE state + \arg TLI_FLAG_VS: current VS status of the TLI + \arg TLI_FLAG_HS: current HS status of the TLI + \arg TLI_FLAG_LM: line mark interrupt flag + \arg TLI_FLAG_FE: FIFO error interrupt flag + \arg TLI_FLAG_TE: transaction error interrupt flag + \arg TLI_FLAG_LCR: layer configuration reloaded interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus tli_flag_get(uint32_t flag) +{ + uint32_t stat; + /* choose which register to get flag or state */ + if(flag >> 31U) { + stat = TLI_INTF; + } else { + stat = TLI_STAT; + } + if(flag & stat) { + return SET; + } else { + return RESET; + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_trng.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_trng.c new file mode 100644 index 0000000..f9e15db --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_trng.c @@ -0,0 +1,153 @@ +/*! + \file gd32f5xx_trng.c + \brief TRNG driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_trng.h" + +/*! + \brief reset TRNG + \param[in] none + \param[out] none + \retval none +*/ +void trng_deinit(void) +{ + rcu_periph_reset_enable(RCU_TRNGRST); + rcu_periph_reset_disable(RCU_TRNGRST); +} + +/*! + \brief enable TRNG + \param[in] none + \param[out] none + \retval none +*/ +void trng_enable(void) +{ + TRNG_CTL |= TRNG_CTL_TRNGEN; +} + +/*! + \brief disable TRNG + \param[in] none + \param[out] none + \retval none +*/ +void trng_disable(void) +{ + TRNG_CTL &= ~TRNG_CTL_TRNGEN; +} + +/*! + \brief get the true random data + \param[in] none + \param[out] none + \retval uint32_t: 0x0-0xFFFFFFFF +*/ +uint32_t trng_get_true_random_data(void) +{ + return (TRNG_DATA); +} + +/*! + \brief get TRNG flag status + \param[in] flag: TRNG flag + only one parameter can be selected which is shown as below: + \arg TRNG_FLAG_DRDY: random Data ready status + \arg TRNG_FLAG_CECS: clock error current status + \arg TRNG_FLAG_SECS: seed error current status + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus trng_flag_get(trng_flag_enum flag) +{ + if(RESET != (TRNG_STAT & flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief enable TRNG interrupt + \param[in] none + \param[out] none + \retval none +*/ +void trng_interrupt_enable(void) +{ + TRNG_CTL |= TRNG_CTL_TRNGIE; +} + +/*! + \brief disable TRNG interrupt + \param[in] none + \param[out] none + \retval none +*/ +void trng_interrupt_disable(void) +{ + TRNG_CTL &= ~TRNG_CTL_TRNGIE; +} + +/*! + \brief get TRNG interrupt flag status + \param[in] int_flag: TRNG interrupt flag + only one parameter can be selected which is shown as below: + \arg TRNG_INT_FLAG_CEIF: clock error interrupt flag + \arg TRNG_INT_FLAG_SEIF: seed error interrupt flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus trng_interrupt_flag_get(trng_int_flag_enum int_flag) +{ + if(RESET != (TRNG_STAT & int_flag)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear TRNG interrupt flag status + \param[in] int_flag: TRNG interrupt flag + only one parameter can be selected which is shown as below: + \arg TRNG_INT_FLAG_CEIF: clock error interrupt flag + \arg TRNG_INT_FLAG_SEIF: seed error interrupt flag + \param[out] none + \retval none +*/ +void trng_interrupt_flag_clear(trng_int_flag_enum int_flag) +{ + TRNG_STAT &= ~(uint32_t)int_flag; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_usart.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_usart.c new file mode 100644 index 0000000..f863129 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_usart.c @@ -0,0 +1,1010 @@ +/*! + \file gd32f5xx_usart.c + \brief USART driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_usart.h" + +/* USART register bit offset */ +#define GP_GUAT_OFFSET ((uint32_t)8U) /* bit offset of GUAT in USART_GP */ +#define CTL3_SCRTNUM_OFFSET ((uint32_t)1U) /* bit offset of SCRTNUM in USART_CTL3 */ +#define RT_BL_OFFSET ((uint32_t)24U) /* bit offset of BL in USART_RT */ + +/*! + \brief reset USART/UART + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_deinit(uint32_t usart_periph) +{ + switch(usart_periph) { + case USART0: + rcu_periph_reset_enable(RCU_USART0RST); + rcu_periph_reset_disable(RCU_USART0RST); + break; + case USART1: + rcu_periph_reset_enable(RCU_USART1RST); + rcu_periph_reset_disable(RCU_USART1RST); + break; + case USART2: + rcu_periph_reset_enable(RCU_USART2RST); + rcu_periph_reset_disable(RCU_USART2RST); + break; + case USART5: + rcu_periph_reset_enable(RCU_USART5RST); + rcu_periph_reset_disable(RCU_USART5RST); + break; + case UART3: + rcu_periph_reset_enable(RCU_UART3RST); + rcu_periph_reset_disable(RCU_UART3RST); + break; + case UART4: + rcu_periph_reset_enable(RCU_UART4RST); + rcu_periph_reset_disable(RCU_UART4RST); + break; + case UART6: + rcu_periph_reset_enable(RCU_UART6RST); + rcu_periph_reset_disable(RCU_UART6RST); + break; + case UART7: + rcu_periph_reset_enable(RCU_UART7RST); + rcu_periph_reset_disable(RCU_UART7RST); + break; + default: + break; + } +} + +/*! + \brief configure USART baud rate value + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] baudval: baud rate value + \param[out] none + \retval none +*/ +void usart_baudrate_set(uint32_t usart_periph, uint32_t baudval) +{ + uint32_t uclk = 0U, intdiv = 0U, fradiv = 0U, udiv = 0U; + switch(usart_periph) { + /* get clock frequency */ + case USART0: + uclk = rcu_clock_freq_get(CK_APB2); + break; + case USART5: + uclk = rcu_clock_freq_get(CK_APB2); + break; + case USART1: + uclk = rcu_clock_freq_get(CK_APB1); + break; + case USART2: + uclk = rcu_clock_freq_get(CK_APB1); + break; + case UART3: + uclk = rcu_clock_freq_get(CK_APB1); + break; + case UART4: + uclk = rcu_clock_freq_get(CK_APB1); + break; + case UART6: + uclk = rcu_clock_freq_get(CK_APB1); + break; + case UART7: + uclk = rcu_clock_freq_get(CK_APB1); + break; + default: + break; + } + if(USART_CTL0(usart_periph) & USART_CTL0_OVSMOD) { + /* when oversampling by 8, configure the value of USART_BAUD */ + udiv = ((2U * uclk) + baudval / 2U) / baudval; + intdiv = udiv & 0xfff0U; + fradiv = (udiv >> 1U) & 0x7U; + USART_BAUD(usart_periph) = ((USART_BAUD_FRADIV | USART_BAUD_INTDIV) & (intdiv | fradiv)); + } else { + /* when oversampling by 16, configure the value of USART_BAUD */ + udiv = (uclk + baudval / 2U) / baudval; + intdiv = udiv & 0xfff0U; + fradiv = udiv & 0xfU; + USART_BAUD(usart_periph) = ((USART_BAUD_FRADIV | USART_BAUD_INTDIV) & (intdiv | fradiv)); + } +} + +/*! + \brief configure USART parity function + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] paritycfg: configure USART parity + only one parameter can be selected which is shown as below: + \arg USART_PM_NONE: no parity + \arg USART_PM_EVEN: even parity + \arg USART_PM_ODD: odd parity + \param[out] none + \retval none +*/ +void usart_parity_config(uint32_t usart_periph, uint32_t paritycfg) +{ + /* clear USART_CTL0 PM,PCEN Bits */ + USART_CTL0(usart_periph) &= ~(USART_CTL0_PM | USART_CTL0_PCEN); + /* configure USART parity mode */ + USART_CTL0(usart_periph) |= paritycfg ; +} + +/*! + \brief configure USART word length + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] wlen: USART word length configure + only one parameter can be selected which is shown as below: + \arg USART_WL_8BIT: 8 bits + \arg USART_WL_9BIT: 9 bits + \param[out] none + \retval none +*/ +void usart_word_length_set(uint32_t usart_periph, uint32_t wlen) +{ + /* clear USART_CTL0 WL bit */ + USART_CTL0(usart_periph) &= ~USART_CTL0_WL; + /* configure USART word length */ + USART_CTL0(usart_periph) |= wlen; +} + +/*! + \brief configure USART stop bit length + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] stblen: USART stop bit configure + only one parameter can be selected which is shown as below: + \arg USART_STB_1BIT: 1 bit + \arg USART_STB_0_5BIT: 0.5 bit(not available for UARTx(x=3,4,6,7)) + \arg USART_STB_2BIT: 2 bits + \arg USART_STB_1_5BIT: 1.5 bits(not available for UARTx(x=3,4,6,7)) + \param[out] none + \retval none +*/ +void usart_stop_bit_set(uint32_t usart_periph, uint32_t stblen) +{ + /* clear USART_CTL1 STB bits */ + USART_CTL1(usart_periph) &= ~USART_CTL1_STB; + /* configure USART stop bits */ + USART_CTL1(usart_periph) |= stblen; +} +/*! + \brief enable USART + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_enable(uint32_t usart_periph) +{ + USART_CTL0(usart_periph) |= USART_CTL0_UEN; +} + +/*! + \brief disable USART + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_disable(uint32_t usart_periph) +{ + USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN); +} + +/*! + \brief configure USART transmitter + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] txconfig: enable or disable USART transmitter + only one parameter can be selected which is shown as below: + \arg USART_TRANSMIT_ENABLE: enable USART transmission + \arg USART_TRANSMIT_DISABLE: enable USART transmission + \param[out] none + \retval none +*/ +void usart_transmit_config(uint32_t usart_periph, uint32_t txconfig) +{ + uint32_t ctl = 0U; + + ctl = USART_CTL0(usart_periph); + ctl &= ~USART_CTL0_TEN; + ctl |= txconfig; + /* configure transfer mode */ + USART_CTL0(usart_periph) = ctl; +} + +/*! + \brief configure USART receiver + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] rxconfig: enable or disable USART receiver + only one parameter can be selected which is shown as below: + \arg USART_RECEIVE_ENABLE: enable USART reception + \arg USART_RECEIVE_DISABLE: disable USART reception + \param[out] none + \retval none +*/ +void usart_receive_config(uint32_t usart_periph, uint32_t rxconfig) +{ + uint32_t ctl = 0U; + + ctl = USART_CTL0(usart_periph); + ctl &= ~USART_CTL0_REN; + ctl |= rxconfig; + /* configure transfer mode */ + USART_CTL0(usart_periph) = ctl; +} + +/*! + \brief data is transmitted/received with the LSB/MSB first + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] msbf: LSB/MSB + only one parameter can be selected which is shown as below: + \arg USART_MSBF_LSB: LSB first + \arg USART_MSBF_MSB: MSB first + \param[out] none + \retval none +*/ +void usart_data_first_config(uint32_t usart_periph, uint32_t msbf) +{ + uint32_t ctl = 0U; + + ctl = USART_CTL3(usart_periph); + ctl &= ~(USART_CTL3_MSBF); + ctl |= msbf; + /* configure data transmitted/received mode */ + USART_CTL3(usart_periph) = ctl; +} + +/*! + \brief configure USART inversion + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] invertpara: refer to enum USART_INVERT_CONFIG + only one parameter can be selected which is shown as below: + \arg USART_DINV_ENABLE: data bit level inversion + \arg USART_DINV_DISABLE: data bit level not inversion + \arg USART_TXPIN_ENABLE: TX pin level inversion + \arg USART_TXPIN_DISABLE: TX pin level not inversion + \arg USART_RXPIN_ENABLE: RX pin level inversion + \arg USART_RXPIN_DISABLE: RX pin level not inversion + \param[out] none + \retval none +*/ +void usart_invert_config(uint32_t usart_periph, usart_invert_enum invertpara) +{ + /* inverted or not the specified siginal */ + switch(invertpara) { + case USART_DINV_ENABLE: + USART_CTL3(usart_periph) |= USART_CTL3_DINV; + break; + case USART_TXPIN_ENABLE: + USART_CTL3(usart_periph) |= USART_CTL3_TINV; + break; + case USART_RXPIN_ENABLE: + USART_CTL3(usart_periph) |= USART_CTL3_RINV; + break; + case USART_DINV_DISABLE: + USART_CTL3(usart_periph) &= ~(USART_CTL3_DINV); + break; + case USART_TXPIN_DISABLE: + USART_CTL3(usart_periph) &= ~(USART_CTL3_TINV); + break; + case USART_RXPIN_DISABLE: + USART_CTL3(usart_periph) &= ~(USART_CTL3_RINV); + break; + default: + break; + } +} + +/*! + \brief configure the USART oversample mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] oversamp: oversample value + only one parameter can be selected which is shown as below: + \arg USART_OVSMOD_8: 8 bits + \arg USART_OVSMOD_16: 16 bits + \param[out] none + \retval none +*/ +void usart_oversample_config(uint32_t usart_periph, uint32_t oversamp) +{ + /* clear OVSMOD bit */ + USART_CTL0(usart_periph) &= ~(USART_CTL0_OVSMOD); + USART_CTL0(usart_periph) |= oversamp; +} + +/*! + \brief configure sample bit method + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] obsm: sample bit + only one parameter can be selected which is shown as below: + \arg USART_OSB_1bit: 1 bit + \arg USART_OSB_3bit: 3 bits + \param[out] none + \retval none +*/ +void usart_sample_bit_config(uint32_t usart_periph, uint32_t obsm) +{ + USART_CTL2(usart_periph) &= ~(USART_CTL2_OSB); + USART_CTL2(usart_periph) |= obsm; +} + +/*! + \brief enable receiver timeout of USART + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[out] none + \retval none +*/ +void usart_receiver_timeout_enable(uint32_t usart_periph) +{ + USART_CTL3(usart_periph) |= USART_CTL3_RTEN; +} + +/*! + \brief disable receiver timeout of USART + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[out] none + \retval none +*/ +void usart_receiver_timeout_disable(uint32_t usart_periph) +{ + USART_CTL3(usart_periph) &= ~(USART_CTL3_RTEN); +} + +/*! + \brief configure receiver timeout threshold + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] rtimeout: 0-0x00FFFFFF + \param[out] none + \retval none +*/ +void usart_receiver_timeout_threshold_config(uint32_t usart_periph, uint32_t rtimeout) +{ + USART_RT(usart_periph) &= ~(USART_RT_RT); + USART_RT(usart_periph) |= rtimeout; +} + +/*! + \brief USART transmit data function + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] data: data of transmission + \param[out] none + \retval none +*/ +void usart_data_transmit(uint32_t usart_periph, uint32_t data) +{ + USART_DATA(usart_periph) = ((uint16_t)USART_DATA_DATA & data); +} + +/*! + \brief USART receive data function + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval data of received +*/ +uint16_t usart_data_receive(uint32_t usart_periph) +{ + return (uint16_t)(GET_BITS(USART_DATA(usart_periph), 0U, 8U)); +} + +/*! + \brief configure address of the USART + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] addr: address of USART/UART + \param[out] none + \retval none +*/ +void usart_address_config(uint32_t usart_periph, uint8_t addr) +{ + USART_CTL1(usart_periph) &= ~(USART_CTL1_ADDR); + USART_CTL1(usart_periph) |= (USART_CTL1_ADDR & addr); +} + +/*! + \brief enable mute mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_mute_mode_enable(uint32_t usart_periph) +{ + USART_CTL0(usart_periph) |= USART_CTL0_RWU; +} + +/*! + \brief disable mute mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_mute_mode_disable(uint32_t usart_periph) +{ + USART_CTL0(usart_periph) &= ~(USART_CTL0_RWU); +} + +/*! + \brief configure wakeup method in mute mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] wmehtod: two method be used to enter or exit the mute mode + only one parameter can be selected which is shown as below: + \arg USART_WM_IDLE: idle line + \arg USART_WM_ADDR: address mask + \param[out] none + \retval none +*/ +void usart_mute_mode_wakeup_config(uint32_t usart_periph, uint32_t wmehtod) +{ + USART_CTL0(usart_periph) &= ~(USART_CTL0_WM); + USART_CTL0(usart_periph) |= wmehtod; +} + +/*! + \brief enable LIN mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_lin_mode_enable(uint32_t usart_periph) +{ + USART_CTL1(usart_periph) |= USART_CTL1_LMEN; +} + +/*! + \brief disable LIN mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_lin_mode_disable(uint32_t usart_periph) +{ + USART_CTL1(usart_periph) &= ~(USART_CTL1_LMEN); +} + +/*! + \brief configure lin break frame length + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] lblen: lin break frame length + only one parameter can be selected which is shown as below: + \arg USART_LBLEN_10B: 10 bits + \arg USART_LBLEN_11B: 11 bits + \param[out] none + \retval none +*/ +void usart_lin_break_detection_length_config(uint32_t usart_periph, uint32_t lblen) +{ + USART_CTL1(usart_periph) &= ~(USART_CTL1_LBLEN); + USART_CTL1(usart_periph) |= (USART_CTL1_LBLEN & lblen); +} + +/*! + \brief send break frame + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_send_break(uint32_t usart_periph) +{ + USART_CTL0(usart_periph) |= USART_CTL0_SBKCMD; +} + +/*! + \brief enable half-duplex mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_halfduplex_enable(uint32_t usart_periph) +{ + USART_CTL2(usart_periph) |= USART_CTL2_HDEN; +} + +/*! + \brief disable half-duplex mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_halfduplex_disable(uint32_t usart_periph) +{ + USART_CTL2(usart_periph) &= ~(USART_CTL2_HDEN); +} + +/*! + \brief enable CK pin in synchronous mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[out] none + \retval none +*/ +void usart_synchronous_clock_enable(uint32_t usart_periph) +{ + USART_CTL1(usart_periph) |= USART_CTL1_CKEN; +} + +/*! + \brief disable CK pin in synchronous mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[out] none + \retval none +*/ +void usart_synchronous_clock_disable(uint32_t usart_periph) +{ + USART_CTL1(usart_periph) &= ~(USART_CTL1_CKEN); +} + +/*! + \brief configure USART synchronous mode parameters + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] clen: CK length + only one parameter can be selected which is shown as below: + \arg USART_CLEN_NONE: there are 7 CK pulses for an 8 bit frame and 8 CK pulses for a 9 bit frame + \arg USART_CLEN_EN: there are 8 CK pulses for an 8 bit frame and 9 CK pulses for a 9 bit frame + \param[in] cph: clock phase + only one parameter can be selected which is shown as below: + \arg USART_CPH_1CK: first clock transition is the first data capture edge + \arg USART_CPH_2CK: second clock transition is the first data capture edge + \param[in] cpl: clock polarity + only one parameter can be selected which is shown as below: + \arg USART_CPL_LOW: steady low value on CK pin + \arg USART_CPL_HIGH: steady high value on CK pin + \param[out] none + \retval none +*/ +void usart_synchronous_clock_config(uint32_t usart_periph, uint32_t clen, uint32_t cph, uint32_t cpl) +{ + uint32_t ctl = 0U; + + /* read USART_CTL1 register */ + ctl = USART_CTL1(usart_periph); + ctl &= ~(USART_CTL1_CLEN | USART_CTL1_CPH | USART_CTL1_CPL); + /* set CK length, CK phase, CK polarity */ + ctl |= (USART_CTL1_CLEN & clen) | (USART_CTL1_CPH & cph) | (USART_CTL1_CPL & cpl); + + USART_CTL1(usart_periph) = ctl; +} + +/*! + \brief configure guard time value in smartcard mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] guat: guard time value, 0-0xFF + \param[out] none + \retval none +*/ +void usart_guard_time_config(uint32_t usart_periph, uint32_t guat) +{ + USART_GP(usart_periph) &= ~(USART_GP_GUAT); + USART_GP(usart_periph) |= (USART_GP_GUAT & ((guat) << GP_GUAT_OFFSET)); +} + +/*! + \brief enable smartcard mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[out] none + \retval none +*/ +void usart_smartcard_mode_enable(uint32_t usart_periph) +{ + USART_CTL2(usart_periph) |= USART_CTL2_SCEN; +} + +/*! + \brief disable smartcard mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[out] none + \retval none +*/ +void usart_smartcard_mode_disable(uint32_t usart_periph) +{ + USART_CTL2(usart_periph) &= ~(USART_CTL2_SCEN); +} + +/*! + \brief enable NACK in smartcard mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[out] none + \retval none +*/ +void usart_smartcard_mode_nack_enable(uint32_t usart_periph) +{ + USART_CTL2(usart_periph) |= USART_CTL2_NKEN; +} + +/*! + \brief disable NACK in smartcard mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[out] none + \retval none +*/ +void usart_smartcard_mode_nack_disable(uint32_t usart_periph) +{ + USART_CTL2(usart_periph) &= ~(USART_CTL2_NKEN); +} + +/*! + \brief configure smartcard auto-retry number + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] scrtnum: smartcard auto-retry number + \param[out] none + \retval none +*/ +void usart_smartcard_autoretry_config(uint32_t usart_periph, uint32_t scrtnum) +{ + USART_CTL3(usart_periph) &= ~(USART_CTL3_SCRTNUM); + USART_CTL3(usart_periph) |= (USART_CTL3_SCRTNUM & ((scrtnum) << CTL3_SCRTNUM_OFFSET)); +} + +/*! + \brief configure block length in Smartcard T=1 reception + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] bl: block length + \param[out] none + \retval none +*/ +void usart_block_length_config(uint32_t usart_periph, uint32_t bl) +{ + USART_RT(usart_periph) &= ~(USART_RT_BL); + USART_RT(usart_periph) |= (USART_RT_BL & ((bl) << RT_BL_OFFSET)); +} + +/*! + \brief enable IrDA mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_irda_mode_enable(uint32_t usart_periph) +{ + USART_CTL2(usart_periph) |= USART_CTL2_IREN; +} + +/*! + \brief disable IrDA mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[out] none + \retval none +*/ +void usart_irda_mode_disable(uint32_t usart_periph) +{ + USART_CTL2(usart_periph) &= ~(USART_CTL2_IREN); +} + +/*! + \brief configure the peripheral clock prescaler in USART IrDA low-power mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] psc: 0-0xFF + \param[out] none + \retval none +*/ +void usart_prescaler_config(uint32_t usart_periph, uint8_t psc) +{ + USART_GP(usart_periph) &= ~(USART_GP_PSC); + USART_GP(usart_periph) |= psc; +} + +/*! + \brief configure IrDA low-power + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] irlp: IrDA low-power or normal + only one parameter can be selected which is shown as below: + \arg USART_IRLP_LOW: low-power + \arg USART_IRLP_NORMAL: normal + \param[out] none + \retval none +*/ +void usart_irda_lowpower_config(uint32_t usart_periph, uint32_t irlp) +{ + USART_CTL2(usart_periph) &= ~(USART_CTL2_IRLP); + USART_CTL2(usart_periph) |= (USART_CTL2_IRLP & irlp); +} + +/*! + \brief configure hardware flow control RTS + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] rtsconfig: enable or disable RTS + only one parameter can be selected which is shown as below: + \arg USART_RTS_ENABLE: enable RTS + \arg USART_RTS_DISABLE: disable RTS + \param[out] none + \retval none +*/ +void usart_hardware_flow_rts_config(uint32_t usart_periph, uint32_t rtsconfig) +{ + uint32_t ctl = 0U; + + ctl = USART_CTL2(usart_periph); + ctl &= ~USART_CTL2_RTSEN; + ctl |= rtsconfig; + /* configure RTS */ + USART_CTL2(usart_periph) = ctl; +} + +/*! + \brief configure hardware flow control CTS + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] ctsconfig: enable or disable CTS + only one parameter can be selected which is shown as below: + \arg USART_CTS_ENABLE: enable CTS + \arg USART_CTS_DISABLE: disable CTS + \param[out] none + \retval none +*/ +void usart_hardware_flow_cts_config(uint32_t usart_periph, uint32_t ctsconfig) +{ + uint32_t ctl = 0U; + + ctl = USART_CTL2(usart_periph); + ctl &= ~USART_CTL2_CTSEN; + ctl |= ctsconfig; + /* configure CTS */ + USART_CTL2(usart_periph) = ctl; +} + +/*! + \brief configure break frame coherence mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] bcm: + only one parameter can be selected which is shown as below: + \arg USART_BCM_NONE: no parity error is detected + \arg USART_BCM_EN: parity error is detected + \param[out] none + \retval none +*/ +void usart_break_frame_coherence_config(uint32_t usart_periph, uint32_t bcm) +{ + USART_CHC(usart_periph) &= ~(USART_CHC_BCM); + USART_CHC(usart_periph) |= (USART_CHC_BCM & bcm); +} + +/*! + \brief configure parity check coherence mode + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] pcm: + only one parameter can be selected which is shown as below: + \arg USART_PCM_NONE: not check parity + \arg USART_PCM_EN: check the parity + \param[out] none + \retval none +*/ +void usart_parity_check_coherence_config(uint32_t usart_periph, uint32_t pcm) +{ + USART_CHC(usart_periph) &= ~(USART_CHC_PCM); + USART_CHC(usart_periph) |= (USART_CHC_PCM & pcm); +} + +/*! + \brief configure hardware flow control coherence mode + \param[in] usart_periph: USARTx(x=0,1,2,5) + \param[in] hcm: + only one parameter can be selected which is shown as below: + \arg USART_HCM_NONE: nRTS signal equals to the rxne status register + \arg USART_HCM_EN: nRTS signal is set when the last data bit has been sampled + \param[out] none + \retval none +*/ +void usart_hardware_flow_coherence_config(uint32_t usart_periph, uint32_t hcm) +{ + USART_CHC(usart_periph) &= ~(USART_CHC_HCM); + USART_CHC(usart_periph) |= (USART_CHC_HCM & hcm); +} + +/*! + \brief configure USART DMA for reception + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] dmacmd: enable or disable DMA for reception + only one parameter can be selected which is shown as below: + \arg USART_DENR_ENABLE: DMA enable for reception + \arg USART_DENR_DISABLE: DMA disable for reception + \param[out] none + \retval none +*/ +void usart_dma_receive_config(uint32_t usart_periph, uint32_t dmacmd) +{ + uint32_t ctl = 0U; + + ctl = USART_CTL2(usart_periph); + ctl &= ~USART_CTL2_DENR; + ctl |= dmacmd; + /* configure DMA reception */ + USART_CTL2(usart_periph) = ctl; +} + +/*! + \brief configure USART DMA for transmission + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] dmacmd: enable or disable DMA for transmission + only one parameter can be selected which is shown as below: + \arg USART_DENT_ENABLE: DMA enable for transmission + \arg USART_DENT_DISABLE: DMA disable for transmission + \param[out] none + \retval none +*/ +void usart_dma_transmit_config(uint32_t usart_periph, uint32_t dmacmd) +{ + uint32_t ctl = 0U; + + ctl = USART_CTL2(usart_periph); + ctl &= ~USART_CTL2_DENT; + ctl |= dmacmd; + /* configure DMA transmission */ + USART_CTL2(usart_periph) = ctl; +} + +/*! + \brief get USART flag status + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] flag: USART flags, refer to usart_flag_enum + only one parameter can be selected which is shown as below: + \arg USART_FLAG_CTS: CTS change flag + \arg USART_FLAG_LBD: LIN break detected flag + \arg USART_FLAG_TBE: transmit data buffer empty + \arg USART_FLAG_TC: transmission complete + \arg USART_FLAG_RBNE: read data buffer not empty + \arg USART_FLAG_IDLE: IDLE frame detected flag + \arg USART_FLAG_ORERR: overrun error + \arg USART_FLAG_NERR: noise error flag + \arg USART_FLAG_FERR: frame error flag + \arg USART_FLAG_PERR: parity error flag + \arg USART_FLAG_BSY: busy flag + \arg USART_FLAG_EB: end of block flag + \arg USART_FLAG_RT: receiver timeout flag + \arg USART_FLAG_EPERR: early parity error flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus usart_flag_get(uint32_t usart_periph, usart_flag_enum flag) +{ + if(RESET != (USART_REG_VAL(usart_periph, flag) & BIT(USART_BIT_POS(flag)))) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear USART flag status + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] flag: USART flags, refer to usart_flag_enum + only one parameter can be selected which is shown as below: + \arg USART_FLAG_CTS: CTS change flag + \arg USART_FLAG_LBD: LIN break detected flag + \arg USART_FLAG_TC: transmission complete + \arg USART_FLAG_RBNE: read data buffer not empty + \arg USART_FLAG_EB: end of block flag + \arg USART_FLAG_RT: receiver timeout flag + \arg USART_FLAG_EPERR: early parity error flag + \param[out] none + \retval none +*/ +void usart_flag_clear(uint32_t usart_periph, usart_flag_enum flag) +{ + if (USART_FLAG_EPERR == flag) { + USART_REG_VAL(usart_periph, flag) &= ~BIT(USART_BIT_POS(flag)); + } else { + USART_REG_VAL(usart_periph, flag) = ~BIT(USART_BIT_POS(flag)); + } +} + +/*! + \brief enable USART interrupt + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] interrupt: USART interrupts, refer to usart_interrupt_enum + only one parameter can be selected which is shown as below: + \arg USART_INT_PERR: parity error interrupt + \arg USART_INT_TBE: transmitter buffer empty interrupt + \arg USART_INT_TC: transmission complete interrupt + \arg USART_INT_RBNE: read data buffer not empty interrupt and overrun error interrupt + \arg USART_INT_IDLE: IDLE line detected interrupt + \arg USART_INT_LBD: LIN break detected interrupt + \arg USART_INT_ERR: error interrupt + \arg USART_INT_CTS: CTS interrupt + \arg USART_INT_RT: interrupt enable bit of receive timeout event + \arg USART_INT_EB: interrupt enable bit of end of block event + \param[out] none + \retval none +*/ +void usart_interrupt_enable(uint32_t usart_periph, usart_interrupt_enum interrupt) +{ + USART_REG_VAL(usart_periph, interrupt) |= BIT(USART_BIT_POS(interrupt)); +} + +/*! + \brief disable USART interrupt + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] interrupt: USART interrupts, refer to usart_interrupt_enum + only one parameter can be selected which is shown as below: + \arg USART_INT_PERR: parity error interrupt + \arg USART_INT_TBE: transmitter buffer empty interrupt + \arg USART_INT_TC: transmission complete interrupt + \arg USART_INT_RBNE: read data buffer not empty interrupt and overrun error interrupt + \arg USART_INT_IDLE: IDLE line detected interrupt + \arg USART_INT_LBD: LIN break detected interrupt + \arg USART_INT_ERR: error interrupt + \arg USART_INT_CTS: CTS interrupt + \arg USART_INT_RT: interrupt enable bit of receive timeout event + \arg USART_INT_EB: interrupt enable bit of end of block event + \param[out] none + \retval none +*/ +void usart_interrupt_disable(uint32_t usart_periph, usart_interrupt_enum interrupt) +{ + USART_REG_VAL(usart_periph, interrupt) &= ~BIT(USART_BIT_POS(interrupt)); +} + +/*! + \brief get USART interrupt and flag status + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] int_flag: USART interrupt flags, refer to usart_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg USART_INT_FLAG_PERR: parity error interrupt and flag + \arg USART_INT_FLAG_TBE: transmitter buffer empty interrupt and flag + \arg USART_INT_FLAG_TC: transmission complete interrupt and flag + \arg USART_INT_FLAG_RBNE: read data buffer not empty interrupt and flag + \arg USART_INT_FLAG_RBNE_ORERR: read data buffer not empty interrupt and overrun error flag + \arg USART_INT_FLAG_IDLE: IDLE line detected interrupt and flag + \arg USART_INT_FLAG_LBD: LIN break detected interrupt and flag + \arg USART_INT_FLAG_CTS: CTS interrupt and flag + \arg USART_INT_FLAG_ERR_ORERR: error interrupt and overrun error + \arg USART_INT_FLAG_ERR_NERR: error interrupt and noise error flag + \arg USART_INT_FLAG_ERR_FERR: error interrupt and frame error flag + \arg USART_INT_FLAG_EB: interrupt enable bit of end of block event and flag + \arg USART_INT_FLAG_RT: interrupt enable bit of receive timeout event and flag + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus usart_interrupt_flag_get(uint32_t usart_periph, usart_interrupt_flag_enum int_flag) +{ + uint32_t intenable = 0U, flagstatus = 0U; + /* get the interrupt enable bit status */ + intenable = (USART_REG_VAL(usart_periph, int_flag) & BIT(USART_BIT_POS(int_flag))); + /* get the corresponding flag bit status */ + flagstatus = (USART_REG_VAL2(usart_periph, int_flag) & BIT(USART_BIT_POS2(int_flag))); + + if((0U != flagstatus) && (0U != intenable)) { + return SET; + } else { + return RESET; + } +} + +/*! + \brief clear interrupt flag and flag status + \param[in] usart_periph: USARTx(x=0,1,2,5)/UARTx(x=3,4,6,7) + \param[in] int_flag: USART interrupt flags, refer to usart_interrupt_flag_enum + only one parameter can be selected which is shown as below: + \arg USART_INT_FLAG_CTS: CTS change flag + \arg USART_INT_FLAG_LBD: LIN break detected flag + \arg USART_INT_FLAG_TC: transmission complete + \arg USART_INT_FLAG_RBNE: read data buffer not empty + \arg USART_INT_FLAG_EB: end of block flag + \arg USART_INT_FLAG_RT: receiver timeout flag + \param[out] none + \retval none +*/ +void usart_interrupt_flag_clear(uint32_t usart_periph, usart_interrupt_flag_enum int_flag) +{ + USART_REG_VAL2(usart_periph, int_flag) = ~BIT(USART_BIT_POS2(int_flag)); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_wwdgt.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_wwdgt.c new file mode 100644 index 0000000..76b1a60 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_standard_peripheral/Source/gd32f5xx_wwdgt.c @@ -0,0 +1,141 @@ +/*! + \file gd32f5xx_wwdgt.c + \brief WWDGT driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "gd32f5xx_wwdgt.h" + +/*! + \brief reset the window watchdog timer configuration + \param[in] none + \param[out] none + \retval none +*/ +void wwdgt_deinit(void) +{ + rcu_periph_reset_enable(RCU_WWDGTRST); + rcu_periph_reset_disable(RCU_WWDGTRST); +} + +/*! + \brief start the window watchdog timer counter + \param[in] none + \param[out] none + \retval none +*/ +void wwdgt_enable(void) +{ + WWDGT_CTL |= WWDGT_CTL_WDGTEN; +} + +/*! + \brief configure the window watchdog timer counter value + \param[in] counter_value: 0x00 - 0x7F + \param[out] none + \retval none +*/ +void wwdgt_counter_update(uint16_t counter_value) +{ + WWDGT_CTL = (uint32_t)(CTL_CNT(counter_value)); +} + +/*! + \brief configure counter value, window value, and prescaler divider value + \param[in] counter: 0x00 - 0x7F + \param[in] window: 0x00 - 0x7F + \param[in] prescaler: wwdgt prescaler value + only one parameter can be selected which is shown as below: + \arg WWDGT_CFG_PSC_DIV1 : the time base of window watchdog counter = (PCLK1/4096)/1 + \arg WWDGT_CFG_PSC_DIV2 : the time base of window watchdog counter = (PCLK1/4096)/2 + \arg WWDGT_CFG_PSC_DIV4 : the time base of window watchdog counter = (PCLK1/4096)/4 + \arg WWDGT_CFG_PSC_DIV8 : the time base of window watchdog counter = (PCLK1/4096)/8 + \arg WWDGT_CFG_PSC_DIV16 : the time base of window watchdog counter = (PCLK1/4096)/16 + \arg WWDGT_CFG_PSC_DIV32 : the time base of window watchdog counter = (PCLK1/4096)/32 + \arg WWDGT_CFG_PSC_DIV64 : the time base of window watchdog counter = (PCLK1/4096)/64 + \arg WWDGT_CFG_PSC_DIV128 : the time base of window watchdog counter = (PCLK1/4096)/128 + \arg WWDGT_CFG_PSC_DIV256 : the time base of window watchdog counter = (PCLK1/4096)/256 + \arg WWDGT_CFG_PSC_DIV512 : the time base of window watchdog counter = (PCLK1/4096)/512 + \arg WWDGT_CFG_PSC_DIV1024 : the time base of window watchdog counter = (PCLK1/4096)/1024 + \arg WWDGT_CFG_PSC_DIV2048 : the time base of window watchdog counter = (PCLK1/4096)/2048 + \arg WWDGT_CFG_PSC_DIV4096 : the time base of window watchdog counter = (PCLK1/4096)/4096 + \arg WWDGT_CFG_PSC_DIV8192 : the time base of window watchdog counter = (PCLK1/4096)/8192 + \arg WWDGT_CFG_PSC_DIV16384 : the time base of window watchdog counter = (PCLK1/4096)/16384 + \arg WWDGT_CFG_PSC_DIV32768 : the time base of window watchdog counter = (PCLK1/4096)/32768 + \arg WWDGT_CFG_PSC_DIV65536 : the time base of window watchdog counter = (PCLK1/4096)/65536 + \arg WWDGT_CFG_PSC_DIV131072: the time base of window watchdog counter = (PCLK1/4096)/131072 + \arg WWDGT_CFG_PSC_DIV262144: the time base of window watchdog counter = (PCLK1/4096)/262144 + \param[out] none + \retval none +*/ +void wwdgt_config(uint16_t counter, uint16_t window, uint32_t prescaler) +{ + /* configure WIN and PSC bits, configure CNT bit */ + WWDGT_CTL = (uint32_t)(CTL_CNT(counter)); + WWDGT_CFG = (uint32_t)(CFG_WIN(window) | prescaler); +} + +/*! + \brief check early wakeup interrupt state of WWDGT + \param[in] none + \param[out] none + \retval FlagStatus: SET or RESET +*/ +FlagStatus wwdgt_flag_get(void) +{ + if(RESET != (WWDGT_STAT & WWDGT_STAT_EWIF)) { + return SET; + } + + return RESET; +} + +/*! + \brief clear early wakeup interrupt state of WWDGT + \param[in] none + \param[out] none + \retval none +*/ +void wwdgt_flag_clear(void) +{ + WWDGT_STAT = (uint32_t)(RESET); +} + +/*! + \brief enable early wakeup interrupt of WWDGT + \param[in] none + \param[out] none + \retval none +*/ +void wwdgt_interrupt_enable(void) +{ + WWDGT_CFG |= WWDGT_CFG_EWIE; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Include/audio_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Include/audio_core.h new file mode 100644 index 0000000..111bdb8 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Include/audio_core.h @@ -0,0 +1,320 @@ +/*! + \file audio_core.h + \brief the header file of USB audio device class core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __AUDIO_CORE_H +#define __AUDIO_CORE_H + +#include "usbd_enum.h" + +#define FORMAT_24BIT(x) (uint8_t)(x);(uint8_t)((x) >> 8U);(uint8_t)((x) >> 16U) + +/* number of sub-packets in the audio transfer buffer. you can modify this value but always make sure + that it is an even number and higher than 3 */ +#define OUT_PACKET_NUM 200U + +/* total size of the audio transfer buffer */ +#define OUT_BUF_MARGIN 0U +#define TOTAL_OUT_BUF_SIZE ((uint32_t)((SPEAKER_OUT_PACKET + OUT_BUF_MARGIN) * OUT_PACKET_NUM)) + +#define AD_CONFIG_DESC_SET_LEN (sizeof(usb_desc_config_set)) +#define AD_INTERFACE_DESC_SIZE 9U + +#define USB_AD_DESC_SIZ 0x09U +#define AD_STANDARD_EP_DESC_SIZE 0x09U +#define AD_STREAMING_EP_DESC_SIZE 0x07U + +/* audio interface class code */ +#define USB_CLASS_AUDIO 0x01U + +/* audio interface subclass codes */ +#define AD_SUBCLASS_CONTROL 0x01U +#define AD_SUBCLASS_AUDIOSTREAMING 0x02U +#define AD_SUBCLASS_MIDISTREAMING 0x03U + +/* audio interface protocol codes */ +#define AD_PROTOCOL_UNDEFINED 0x00U +#define AD_STREAMING_GENERAL 0x01U +#define AD_STREAMING_FORMAT_TYPE 0x02U + +/* audio class-specific descriptor types */ +#define AD_DESCTYPE_UNDEFINED 0x20U +#define AD_DESCTYPE_DEVICE 0x21U +#define AD_DESCTYPE_CONFIGURATION 0x22U +#define AD_DESCTYPE_STRING 0x23U +#define AD_DESCTYPE_INTERFACE 0x24U +#define AD_DESCTYPE_ENDPOINT 0x25U + +/* audio control interface descriptor subtypes */ +#define AD_CONTROL_HEADER 0x01U +#define AD_CONTROL_INPUT_TERMINAL 0x02U +#define AD_CONTROL_OUTPUT_TERMINAL 0x03U +#define AD_CONTROL_MIXER_UNIT 0x04U +#define AD_CONTROL_SELECTOR_UNIT 0x05U +#define AD_CONTROL_FEATURE_UNIT 0x06U +#define AD_CONTROL_PROCESSING_UNIT 0x07U +#define AD_CONTROL_EXTENSION_UNIT 0x08U + +#define AD_INPUT_TERMINAL_DESC_SIZE 0x0CU +#define AD_OUTPUT_TERMINAL_DESC_SIZE 0x09U +#define AD_STREAMING_INTERFACE_DESC_SIZE 0x07U + +#define AD_CONTROL_MUTE 0x01U +#define AD_CONTROL_VOLUME 0x02U + +#define AD_FORMAT_TYPE_I 0x01U +#define AD_FORMAT_TYPE_III 0x03U + +#define USB_ENDPOINT_TYPE_ISOCHRONOUS 0x01U +#define AD_ENDPOINT_GENERAL 0x01U + +#define AD_REQ_UNDEFINED 0x00U +#define AD_REQ_SET_CUR 0x01U +#define AD_REQ_GET_CUR 0x81U +#define AD_REQ_SET_MIN 0x02U +#define AD_REQ_GET_MIN 0x82U +#define AD_REQ_SET_MAX 0x03U +#define AD_REQ_GET_MAX 0x83U +#define AD_REQ_SET_RES 0x04U +#define AD_REQ_GET_RES 0x84U +#define AD_REQ_SET_MEM 0x05U +#define AD_REQ_GET_MEM 0x85U +#define AD_REQ_GET_STAT 0xFFU + +#define AD_OUT_STREAMING_CTRL 0x05U +#define AD_IN_STREAMING_CTRL 0x02U + +/* audio stream interface number */ +enum +{ +#ifdef USE_USB_AD_MICPHONE + MIC_INTERFACE_COUNT, +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER + SPEAK_INTERFACE_COUNT, +#endif /* USE_USB_AD_SPEAKER */ + CONFIG_DESC_AS_ITF_COUNT, +}; + +#define AC_ITF_TOTAL_LEN (sizeof(usb_desc_AC_itf) + CONFIG_DESC_AS_ITF_COUNT*(sizeof(usb_desc_input_terminal) + \ + sizeof(usb_desc_mono_feature_unit) + sizeof(usb_desc_output_terminal))) + +#pragma pack(1) + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bDescriptorSubtype; /*!< header descriptor subtype */ + uint16_t bcdADC; /*!< audio device class specification release number in binary-coded decimal */ + uint16_t wTotalLength; /*!< total number of bytes */ + uint8_t bInCollection; /*!< the number of the streaming interfaces */ +#ifdef USE_USB_AD_MICPHONE + uint8_t baInterfaceNr0; /*!< interface number of the streaming interfaces */ +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER + uint8_t baInterfaceNr1; /*!< interface number of the streaming interfaces */ +#endif /* USE_USB_AD_SPEAKER */ +} usb_desc_AC_itf; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bDescriptorSubtype; /*!< AS_GENERAL descriptor subtype */ + uint8_t bTerminalLink; /*!< the terminal ID */ + uint8_t bDelay; /*!< delay introduced by the data path */ + uint16_t wFormatTag; /*!< the audio data format */ +} usb_desc_AS_itf; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bDescriptorSubtype; /*!< INPUT_TERMINAL descriptor subtype. */ + uint8_t bTerminalID; /*!< constant uniquely identifying the terminal within the audio function */ + uint16_t wTerminalType; /*!< constant characterizing the type of terminal */ + uint8_t bAssocTerminal; /*!< ID of the output terminal */ + uint8_t bNrChannels; /*!< number of logical output channels */ + uint16_t wChannelConfig; /*!< describes the spatial location of the logical channels */ + uint8_t iChannelNames; /*!< index of a string descriptor */ + uint8_t iTerminal; /*!< index of a string descriptor */ +} usb_desc_input_terminal; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bDescriptorSubtype; /*!< OUTPUT_TERMINAL descriptor subtype */ + uint8_t bTerminalID; /*!< constant uniquely identifying the terminal within the audio function */ + uint16_t wTerminalType; /*!< constant characterizing the type of terminal */ + uint8_t bAssocTerminal; /*!< constant, identifying the input terminal to which this output terminal is associated */ + uint8_t bSourceID; /*!< ID of the unit or terminal */ + uint8_t iTerminal; /*!< index of a string descriptor */ +} usb_desc_output_terminal; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bDescriptorSubtype; /*!< FEATURE_UNIT descriptor subtype */ + uint8_t bUnitID; /*!< constant uniquely identifying the unit within the audio function */ + uint8_t bSourceID; /*!< ID of the unit or terminal */ + uint8_t bControlSize; /*!< size in bytes of an element of the bmaControls() array */ + uint8_t bmaControls0; /*!< a bit set to 1 indicates that the mentioned control is supported for master channel 0 */ + uint8_t bmaControls1; /*!< a bit set to 1 indicates that the mentioned control is supported for logical channel 1 */ + uint8_t iFeature; /*!< index of a string descriptor */ +} usb_desc_mono_feature_unit; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bDescriptorSubtype; /*!< FEATURE_UNIT descriptor subtype */ + uint8_t bUnitID; /*!< constant uniquely identifying the unit within the audio function */ + uint8_t bSourceID; /*!< ID of the unit or terminal */ + uint8_t bControlSize; /*!< size in bytes of an element of the bmaControls() array */ + uint16_t bmaControls0; /*!< a bit set to 1 indicates that the mentioned control is supported for master channel 0 */ + uint16_t bmaControls1; /*!< a bit set to 1 indicates that the mentioned control is supported for logical channel 1 */ + uint16_t bmaControls2; /*!< a bit set to 1 indicates that the mentioned control is supported for logical channel 2 */ + uint8_t iFeature; /*!< index of a string descriptor */ +} usb_desc_stereo_feature_unit; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bDescriptorSubtype; /*!< FORMAT_TYPE descriptor subtype */ + uint8_t bFormatType; /*!< constant identifying the format type */ + uint8_t bNrChannels; /*!< indicates the number of physical channels in the audio data stream */ + uint8_t bSubFrameSize; /*!< the number of bytes occupied by one audio subframe */ + uint8_t bBitResolution; /*!< the number of effectively used bits from the available bits in an audio subframe */ + uint8_t bSamFreqType; /*!< indicates how the sampling frequency can be programmed */ + uint8_t bSamFreq[3]; /*!< sampling frequency ns in Hz for this isochronous data endpoint */ +} usb_desc_format_type; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bEndpointAddress; /*!< the address of the endpoint */ + uint8_t bmAttributes; /*!< transfer type and synchronization type */ + uint16_t wMaxPacketSize; /*!< maximum packet size this endpoint is capable of sending or receiving */ + uint8_t bInterval; /*!< left to the designer's discretion */ + uint8_t bRefresh; /*!< reset to 0 */ + uint8_t bSynchAddress; /*!< reset to 0 */ +} usb_desc_std_ep; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bDescriptorSubtype; /*!< EP_GENERAL descriptor subtype */ + uint8_t bmAttributes; /*!< transfer type and synchronization type */ + uint8_t bLockDelayUnits; /*!< indicates the units used for the wLockDelay field */ + uint16_t wLockDelay; /*!< indicates the time it takes this endpoint to reliably lock its internal clock recovery circuitry */ +} usb_desc_AS_ep; + +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bEndpointAddress; /*!< EP_GENERAL descriptor subtype */ + uint8_t bmAttributes; /*!< transfer type and synchronization type */ + uint16_t wMaxPacketSize; /*!< maximum packet size this endpoint is capable of sending or receiving */ + uint8_t bInterval; /*!< polling interval in milliseconds for the endpoint if it is an INTERRUPT or ISOCHRONOUS type */ + uint8_t Refresh; /*!< bRefresh 1~9, power of 2 */ + uint8_t bSynchAddress; /* bSynchAddress */ +} usb_desc_FeedBack_ep; + +#pragma pack() + +/* USB configuration descriptor structure */ +typedef struct +{ + usb_desc_config config; + usb_desc_itf std_itf; + usb_desc_AC_itf ac_itf; + +#ifdef USE_USB_AD_MICPHONE + usb_desc_input_terminal mic_in_terminal; + usb_desc_mono_feature_unit mic_feature_unit; + usb_desc_output_terminal mic_out_terminal; +#endif + +#ifdef USE_USB_AD_SPEAKER + usb_desc_input_terminal speak_in_terminal; + usb_desc_mono_feature_unit speak_feature_unit; + usb_desc_output_terminal speak_out_terminal; +#endif /* USE_USB_AD_SPEAKER */ + +#ifdef USE_USB_AD_MICPHONE + usb_desc_itf mic_std_as_itf_zeroband; + usb_desc_itf mic_std_as_itf_opera; + usb_desc_AS_itf mic_as_itf; + usb_desc_format_type mic_format_typeI; + usb_desc_std_ep mic_std_endpoint; + usb_desc_AS_ep mic_as_endpoint; +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER + usb_desc_itf speak_std_as_itf_zeroband; + usb_desc_itf speak_std_as_itf_opera; + usb_desc_AS_itf speak_as_itf; + usb_desc_format_type speak_format_typeI; + usb_desc_std_ep speak_std_endpoint; + usb_desc_AS_ep speak_as_endpoint; + usb_desc_FeedBack_ep speak_feedback_endpoint; +#endif /* USE_USB_AD_SPEAKER */ +} usb_desc_config_set; + +typedef struct +{ + /* main buffer for audio data out transfers and its relative pointers */ + uint8_t isoc_out_buff[TOTAL_OUT_BUF_SIZE]; + uint8_t* isoc_out_wrptr; + uint8_t* isoc_out_rdptr; + uint16_t buf_free_size; + uint16_t dam_tx_len; + + __IO uint32_t actual_freq; + __IO uint8_t play_flag; + uint8_t feedback_freq[3]; + uint32_t cur_sam_freq; + + /* usb receive buffer */ + uint8_t usb_rx_buffer[SPEAKER_OUT_MAX_PACKET]; + + /* main buffer for audio control requests transfers and its relative variables */ + uint8_t audioctl[64]; + uint8_t audioctl_unit; + uint32_t audioctl_len; +} usbd_audio_handler; + +extern usb_desc audio_desc; +extern usb_class_core usbd_audio_cb; +extern usbd_audio_handler audio_handler; + +#endif /* __AUDIO_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Include/audio_out_itf.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Include/audio_out_itf.h new file mode 100644 index 0000000..34bb205 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Include/audio_out_itf.h @@ -0,0 +1,49 @@ +/*! + \file audio_out_itf.h + \brief audio OUT (playback) interface header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __AUDIO_OUT_ITF_H +#define __AUDIO_OUT_ITF_H + +#include "usbd_conf.h" +#include "string.h" + +typedef struct { + uint8_t (*audio_init) (uint32_t audio_freq, uint32_t volume); + uint8_t (*audio_deinit) (void); + uint8_t (*audio_cmd) (uint8_t* pbuf, uint32_t size, uint8_t cmd); +} audio_fops_struct; + +extern audio_fops_struct audio_out_fops; + +#endif /* __AUDIO_OUT_ITF_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Source/audio_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Source/audio_core.c new file mode 100644 index 0000000..34984a2 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Source/audio_core.c @@ -0,0 +1,959 @@ +/*! + \file audio_core.c + \brief USB audio device class core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "audio_out_itf.h" +#include "audio_core.h" +#include +#include + +#define USBD_VID 0x28E9U +#define USBD_PID 0x9574U + +#define VOL_MIN 0U /* volume Minimum Value */ +#define VOL_MAX 100U /* volume Maximum Value */ +#define VOL_RES 1U /* volume Resolution */ +#define VOL_0dB 70U /* 0dB is in the middle of VOL_MIN and VOL_MAX */ + +#ifdef USE_USB_AD_MICPHONE +extern volatile uint32_t count_data; +extern const char wavetestdata[]; +#define LENGTH_DATA (1747 * 32) +#endif /* USE_USB_AD_MICPHONE */ + +__ALIGN_BEGIN usbd_audio_handler audio_handler __ALIGN_END; + +/* local function prototypes ('static') */ +static uint8_t audio_init (usb_dev *udev, uint8_t config_index); +static uint8_t audio_deinit (usb_dev *udev, uint8_t config_index); +static uint8_t audio_req_handler (usb_dev *udev, usb_req *req); +static uint8_t audio_set_intf (usb_dev *udev, usb_req *req); +static uint8_t audio_ctlx_out (usb_dev *udev); +static uint8_t audio_data_in (usb_dev *udev, uint8_t ep_num); +static uint8_t audio_data_out (usb_dev *udev, uint8_t ep_num); +static uint8_t audio_sof (usb_dev *udev); +static uint8_t audio_iso_in_incomplete (usb_dev *udev); +static uint8_t audio_iso_out_incomplete (usb_dev *udev); +static uint32_t usbd_audio_spk_get_feedback(usb_dev *udev); +static void get_feedback_fs_rate(uint32_t rate, uint8_t *buf); + +usb_class_core usbd_audio_cb = { + .init = audio_init, + .deinit = audio_deinit, + .req_proc = audio_req_handler, + .set_intf = audio_set_intf, + .ctlx_out = audio_ctlx_out, + .data_in = audio_data_in, + .data_out = audio_data_out, + .SOF = audio_sof, + .incomplete_isoc_in = audio_iso_in_incomplete, + .incomplete_isoc_out = audio_iso_out_incomplete +}; + +/* note:it should use the c99 standard when compiling the below codes */ +/* USB standard device descriptor */ +__ALIGN_BEGIN const usb_desc_dev audio_dev_desc __ALIGN_END = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV + }, + .bcdUSB = 0x0200U, + .bDeviceClass = 0x00U, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM +}; + +/* USB device configuration descriptor */ +__ALIGN_BEGIN const usb_desc_config_set audio_config_set __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG + }, + .wTotalLength = AD_CONFIG_DESC_SET_LEN, + .bNumInterfaces = 0x01U + CONFIG_DESC_AS_ITF_COUNT, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0xC0U, + .bMaxPower = 0x32U + }, + + .std_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x00U, + .bInterfaceClass = USB_CLASS_AUDIO, + .bInterfaceSubClass = AD_SUBCLASS_CONTROL, + .bInterfaceProtocol = AD_PROTOCOL_UNDEFINED, + .iInterface = 0x00U + }, + + .ac_itf = + { + .header = + { + .bLength = sizeof(usb_desc_AC_itf), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = 0x01U, + .bcdADC = 0x0100U, + .wTotalLength = AC_ITF_TOTAL_LEN, + .bInCollection = CONFIG_DESC_AS_ITF_COUNT, +#ifdef USE_USB_AD_MICPHONE + .baInterfaceNr0 = 0x01U, +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER + .baInterfaceNr1 = 0x02U +#endif /* USE_USB_AD_SPEAKER */ + }, + +#ifdef USE_USB_AD_MICPHONE + .mic_in_terminal = + { + .header = + { + .bLength = sizeof(usb_desc_input_terminal), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = 0x02U, + .bTerminalID = 0x01U, + .wTerminalType = 0x0201U, + .bAssocTerminal = 0x00U, + .bNrChannels = 0x02U, + .wChannelConfig = 0x0003U, + .iChannelNames = 0x00U, + .iTerminal = 0x00U + }, + + .mic_feature_unit = + { + .header = + { + .bLength = sizeof(usb_desc_mono_feature_unit), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_CONTROL_FEATURE_UNIT, + .bUnitID = AD_IN_STREAMING_CTRL, + .bSourceID = 0x01U, + .bControlSize = 0x01U, + .bmaControls0 = AD_CONTROL_MUTE | AD_CONTROL_VOLUME, + .bmaControls1 = 0x00U, + .iFeature = 0x00U + }, + + .mic_out_terminal = + { + .header = + { + .bLength = sizeof(usb_desc_output_terminal), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_CONTROL_OUTPUT_TERMINAL, + .bTerminalID = 0x03U, + .wTerminalType = 0x0101U, + .bAssocTerminal = 0x00U, + .bSourceID = 0x02U, + .iTerminal = 0x00U + }, +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER + .speak_in_terminal = + { + .header = + { + .bLength = sizeof(usb_desc_input_terminal), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_CONTROL_INPUT_TERMINAL, + .bTerminalID = 0x04U, + .wTerminalType = 0x0101U, + .bAssocTerminal = 0x00U, + .bNrChannels = 0x02U, + .wChannelConfig = 0x0003U, + .iChannelNames = 0x00U, + .iTerminal = 0x00U + }, + + .speak_feature_unit = + { + .header = + { + .bLength = sizeof(usb_desc_mono_feature_unit), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_CONTROL_FEATURE_UNIT, + .bUnitID = AD_OUT_STREAMING_CTRL, + .bSourceID = 0x04U, + .bControlSize = 0x01U, + .bmaControls0 = AD_CONTROL_MUTE | AD_CONTROL_VOLUME, + .bmaControls1 = 0x00U, + .iFeature = 0x00U + }, + + .speak_out_terminal = + { + .header = + { + .bLength = sizeof(usb_desc_output_terminal), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_CONTROL_OUTPUT_TERMINAL, + .bTerminalID = 0x06U, + .wTerminalType = 0x0301U, + .bAssocTerminal = 0x00U, + .bSourceID = 0x05U, + .iTerminal = 0x00U + }, +#endif /* USE_USB_AD_SPEAKER */ + +#ifdef USE_USB_AD_MICPHONE + .mic_std_as_itf_zeroband = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x01U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x00U, + .bInterfaceClass = USB_CLASS_AUDIO, + .bInterfaceSubClass = AD_SUBCLASS_AUDIOSTREAMING, + .bInterfaceProtocol = AD_PROTOCOL_UNDEFINED, + .iInterface = 0x00U + }, + + .mic_std_as_itf_opera = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x01U, + .bAlternateSetting = 0x01U, + .bNumEndpoints = 0x01U, + .bInterfaceClass = USB_CLASS_AUDIO, + .bInterfaceSubClass = AD_SUBCLASS_AUDIOSTREAMING, + .bInterfaceProtocol = AD_PROTOCOL_UNDEFINED, + .iInterface = 0x00U + }, + + .mic_as_itf = + { + .header = + { + .bLength = sizeof(usb_desc_AS_itf), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_STREAMING_GENERAL, + .bTerminalLink = 0x03U, + .bDelay = 0x01U, + .wFormatTag = 0x0001U, + }, + + .mic_format_typeI = + { + .header = + { + .bLength = sizeof(usb_desc_format_type), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_STREAMING_FORMAT_TYPE, + .bFormatType = AD_FORMAT_TYPE_I, + .bNrChannels = MIC_IN_CHANNEL_NBR, + .bSubFrameSize = 0x02U, + .bBitResolution = MIC_IN_BIT_RESOLUTION, + .bSamFreqType = 0x01U, + .bSamFreq[0] = (uint8_t)USBD_MIC_FREQ, + .bSamFreq[1] = USBD_MIC_FREQ >> 8U, + .bSamFreq[2] = USBD_MIC_FREQ >> 16U + }, + + .mic_std_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_std_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = AD_IN_EP, + .bmAttributes = USB_ENDPOINT_TYPE_ISOCHRONOUS, + .wMaxPacketSize = MIC_IN_PACKET, + .bInterval = 0x01U, + .bRefresh = 0x00U, + .bSynchAddress = 0x00U + }, + + .mic_as_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_AS_ep), + .bDescriptorType = AD_DESCTYPE_ENDPOINT + }, + .bDescriptorSubtype = AD_ENDPOINT_GENERAL, + .bmAttributes = 0x00U, + .bLockDelayUnits = 0x00U, + .wLockDelay = 0x0000U, + }, +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER + .speak_std_as_itf_zeroband = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x02U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x00U, + .bInterfaceClass = USB_CLASS_AUDIO, + .bInterfaceSubClass = AD_SUBCLASS_AUDIOSTREAMING, + .bInterfaceProtocol = AD_PROTOCOL_UNDEFINED, + .iInterface = 0x00U + }, + + .speak_std_as_itf_opera = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x02U, + .bAlternateSetting = 0x01U, + .bNumEndpoints = 0x02U, + .bInterfaceClass = USB_CLASS_AUDIO, + .bInterfaceSubClass = AD_SUBCLASS_AUDIOSTREAMING, + .bInterfaceProtocol = AD_PROTOCOL_UNDEFINED, + .iInterface = 0x00U + }, + + .speak_as_itf = + { + .header = + { + .bLength = sizeof(usb_desc_AS_itf), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_STREAMING_GENERAL, + .bTerminalLink = 0x04U, + .bDelay = 0x01U, + .wFormatTag = 0x0001U, + }, + + .speak_format_typeI = + { + .header = + { + .bLength = sizeof(usb_desc_format_type), + .bDescriptorType = AD_DESCTYPE_INTERFACE + }, + .bDescriptorSubtype = AD_STREAMING_FORMAT_TYPE, + .bFormatType = AD_FORMAT_TYPE_I, + .bNrChannels = SPEAKER_OUT_CHANNEL_NBR, + .bSubFrameSize = 0x02U, + .bBitResolution = SPEAKER_OUT_BIT_RESOLUTION, + .bSamFreqType = 0x01U, + .bSamFreq[0] = (uint8_t)USBD_SPEAKER_FREQ, + .bSamFreq[1] = USBD_SPEAKER_FREQ >> 8U, + .bSamFreq[2] = USBD_SPEAKER_FREQ >> 16U + }, + + .speak_std_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_std_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = AD_OUT_EP, + .bmAttributes = USB_EP_ATTR_ISO | USB_EP_ATTR_ASYNC, + .wMaxPacketSize = SPEAKER_OUT_PACKET, + .bInterval = 0x01U, + .bRefresh = 0x00U, + .bSynchAddress = AD_FEEDBACK_IN_EP, + }, + + .speak_as_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_AS_ep), + .bDescriptorType = AD_DESCTYPE_ENDPOINT + }, + .bDescriptorSubtype = AD_ENDPOINT_GENERAL, + .bmAttributes = 0x00U, + .bLockDelayUnits = 0x00U, + .wLockDelay = 0x0000U, + }, + + .speak_feedback_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_FeedBack_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = AD_FEEDBACK_IN_EP, + .bmAttributes = USB_EP_ATTR_ISO | USB_EP_ATTR_ASYNC | USB_EP_ATTR_FEEDBACK, + .wMaxPacketSize = FEEDBACK_IN_PACKET, + .bInterval = 0x01U, + .Refresh = FEEDBACK_IN_INTERVAL, /* refresh every 32(2^5) ms */ + .bSynchAddress = 0x00U, + }, +#endif /* USE_USB_AD_SPEAKER */ +}; + +/* USB language ID descriptor */ +static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR + }, + + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(10), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(14), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'A', 'u', 'd', 'i', 'o'} +}; + +/* USBD serial string */ +static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +/* USB string descriptor */ +void *const usbd_audio_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *)&usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *)&manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *)&product_string, + [STR_IDX_SERIAL] = (uint8_t *)&serial_string +}; + +/* USB descriptor configure */ +usb_desc audio_desc = { + .dev_desc = (uint8_t *)&audio_dev_desc, + .config_desc = (uint8_t *)&audio_config_set, + .strings = usbd_audio_strings +}; + +/*! + \brief initialize the AUDIO device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_init (usb_dev *udev, uint8_t config_index) +{ + memset((void *)&audio_handler, 0, sizeof(usbd_audio_handler)); + +#ifdef USE_USB_AD_MICPHONE +{ + usb_desc_std_ep std_ep = audio_config_set.mic_std_endpoint; + + usb_desc_ep ep = { + .header = std_ep.header, + .bEndpointAddress = std_ep.bEndpointAddress, + .bmAttributes = std_ep.bmAttributes, + .wMaxPacketSize = std_ep.wMaxPacketSize, + .bInterval = std_ep.bInterval + }; + + /* initialize TX endpoint */ + usbd_ep_setup (udev, &ep); +} +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER +{ + audio_handler.isoc_out_rdptr = audio_handler.isoc_out_buff; + audio_handler.isoc_out_wrptr = audio_handler.isoc_out_buff; + + usb_desc_std_ep std_ep = audio_config_set.speak_std_endpoint; + + usb_desc_ep ep1 = { + .header = std_ep.header, + .bEndpointAddress = std_ep.bEndpointAddress, + .bmAttributes = std_ep.bmAttributes, + .wMaxPacketSize = SPEAKER_OUT_MAX_PACKET, + .bInterval = std_ep.bInterval + }; + + /* initialize RX endpoint */ + usbd_ep_setup (udev, &ep1); + + /* prepare out endpoint to receive next audio packet */ + usbd_ep_recev (udev, AD_OUT_EP, audio_handler.usb_rx_buffer, SPEAKER_OUT_MAX_PACKET); + + /* initialize the audio output hardware layer */ + if (USBD_OK != audio_out_fops.audio_init(USBD_SPEAKER_FREQ, DEFAULT_VOLUME)) { + return USBD_FAIL; + } + + usb_desc_FeedBack_ep feedback_ep = audio_config_set.speak_feedback_endpoint; + + usb_desc_ep ep2 = { + .header = feedback_ep.header, + .bEndpointAddress = feedback_ep.bEndpointAddress, + .bmAttributes = feedback_ep.bmAttributes, + .wMaxPacketSize = feedback_ep.wMaxPacketSize, + .bInterval = feedback_ep.bInterval + }; + + /* initialize Tx endpoint */ + usbd_ep_setup (udev, &ep2); +} +#endif /* USE_USB_AD_SPEAKER */ + + return USBD_OK; +} + +/*! + \brief de-initialize the AUDIO device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_deinit (usb_dev *udev, uint8_t config_index) +{ +#ifdef USE_USB_AD_MICPHONE + /* deinitialize AUDIO endpoints */ + usbd_ep_clear(udev, AD_IN_EP); +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER + /* deinitialize AUDIO endpoints */ + usbd_ep_clear(udev, AD_OUT_EP); + + /* deinitialize the audio output hardware layer */ + if (USBD_OK != audio_out_fops.audio_deinit()) { + return USBD_FAIL; + } + + /* deinitialize AUDIO endpoints */ + usbd_ep_clear(udev, AD_FEEDBACK_IN_EP); +#endif /* USE_USB_AD_SPEAKER */ + + return USBD_OK; +} + +/*! + \brief handle the AUDIO class-specific requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_req_handler (usb_dev *udev, usb_req *req) +{ + uint8_t status = REQ_NOTSUPP; + + usb_transc *transc_in = &udev->dev.transc_in[0]; + usb_transc *transc_out = &udev->dev.transc_out[0]; + + switch (req->bRequest) { + case AD_REQ_GET_CUR: + transc_in->xfer_buf = audio_handler.audioctl; + transc_in->remain_len = req->wLength; + + status = REQ_SUPP; + break; + + case AD_REQ_SET_CUR: + if (req->wLength) { + transc_out->xfer_buf = audio_handler.audioctl; + transc_out->remain_len = req->wLength; + + udev->dev.class_core->command = AD_REQ_SET_CUR; + + audio_handler.audioctl_len = req->wLength; + audio_handler.audioctl_unit = BYTE_HIGH(req->wIndex); + + status = REQ_SUPP; + } + break; + + case AD_REQ_GET_MIN: + *((uint16_t *)audio_handler.audioctl) = VOL_MIN; + transc_in->xfer_buf = audio_handler.audioctl; + transc_in->remain_len = req->wLength; + status = REQ_SUPP; + break; + + case AD_REQ_GET_MAX: + *((uint16_t *)audio_handler.audioctl) = VOL_MAX; + transc_in->xfer_buf = audio_handler.audioctl; + transc_in->remain_len = req->wLength; + status = REQ_SUPP; + break; + + case AD_REQ_GET_RES: + *((uint16_t *)audio_handler.audioctl) = VOL_RES; + transc_in->xfer_buf = audio_handler.audioctl; + transc_in->remain_len = req->wLength; + status = REQ_SUPP; + break; + + default: + break; + } + + return status; +} + +/*! + \brief handle the AUDIO set interface requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_set_intf(usb_dev *udev, usb_req *req) +{ + udev->dev.class_core->alter_set = req->wValue; + + if(0xFF != req->wValue){ + if (req->wValue != 0){ + /* deinit audio handler */ + memset((void *)&audio_handler, 0, sizeof(usbd_audio_handler)); + + audio_handler.play_flag = 0; + audio_handler.isoc_out_rdptr = audio_handler.isoc_out_buff; + audio_handler.isoc_out_wrptr = audio_handler.isoc_out_buff; + + /* feedback calculate sample freq */ + audio_handler.actual_freq = I2S_ACTUAL_SAM_FREQ(USBD_SPEAKER_FREQ); + get_feedback_fs_rate(audio_handler.actual_freq, audio_handler.feedback_freq); + + /* send feedback data of estimated frequence*/ + usbd_ep_send(udev, AD_FEEDBACK_IN_EP, audio_handler.feedback_freq, FEEDBACK_IN_PACKET); + } else { + /* stop audio output */ + audio_out_fops.audio_cmd(audio_handler.isoc_out_rdptr, SPEAKER_OUT_PACKET/2, AD_CMD_STOP); + + audio_handler.play_flag = 0; + audio_handler.isoc_out_rdptr = audio_handler.isoc_out_buff; + audio_handler.isoc_out_wrptr = audio_handler.isoc_out_buff; + + usbd_fifo_flush (udev, AD_IN_EP); + usbd_fifo_flush (udev, AD_FEEDBACK_IN_EP); + usbd_fifo_flush (udev, AD_OUT_EP); + } + } + + return 0; +} + +/*! + \brief handles the control transfer OUT callback + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_ctlx_out (usb_dev *udev) +{ +#ifdef USE_USB_AD_SPEAKER + /* handles audio control requests data */ + /* check if an audio_control request has been issued */ + if (AD_REQ_SET_CUR == udev->dev.class_core->command) { + /* in this driver, to simplify code, only SET_CUR request is managed */ + + /* check for which addressed unit the audio_control request has been issued */ + if (AD_OUT_STREAMING_CTRL == audio_handler.audioctl_unit) { + /* in this driver, to simplify code, only one unit is manage */ + + /* reset the audioctl_cmd variable to prevent re-entering this function */ + udev->dev.class_core->command = 0U; + + audio_handler.audioctl_len = 0U; + } + } +#endif /* USE_USB_AD_SPEAKER */ + + return USBD_OK; +} + +/*! + \brief handles the audio IN data stage + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint number + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_data_in (usb_dev *udev, uint8_t ep_num) +{ +#ifdef USE_USB_AD_MICPHONE + if(ep_num == EP_ID(AD_IN_EP)){ + if(count_data < LENGTH_DATA){ + /* Prepare next buffer to be sent: dummy data */ + usbd_ep_send(udev, AD_IN_EP,(uint8_t*)&wavetestdata[count_data],MIC_IN_PACKET); + count_data += MIC_IN_PACKET; + } else { + usbd_ep_send(udev, AD_IN_EP,(uint8_t*)wavetestdata,MIC_IN_PACKET); + count_data = MIC_IN_PACKET; + } + } +#endif /* USE_USB_AD_MICPHONE */ + +#ifdef USE_USB_AD_SPEAKER + if(ep_num == EP_ID(AD_FEEDBACK_IN_EP)){ + /* calculate feedback actual freq */ + audio_handler.actual_freq = usbd_audio_spk_get_feedback(udev); + get_feedback_fs_rate(audio_handler.actual_freq, audio_handler.feedback_freq); + + usbd_ep_send(udev, AD_FEEDBACK_IN_EP, audio_handler.feedback_freq, FEEDBACK_IN_PACKET); + } +#endif /* USE_USB_AD_SPEAKER */ + + return USBD_OK; +} + +/*! + \brief handles the audio OUT data stage + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint number + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_data_out (usb_dev *udev, uint8_t ep_num) +{ + uint16_t usb_rx_length, tail_len; + + /* get receive length */ + usb_rx_length = ((usb_core_driver *)udev)->dev.transc_out[ep_num].xfer_count; + + if(audio_handler.isoc_out_wrptr >= audio_handler.isoc_out_rdptr){ + audio_handler.buf_free_size = TOTAL_OUT_BUF_SIZE + audio_handler.isoc_out_rdptr - audio_handler.isoc_out_wrptr; + }else{ + audio_handler.buf_free_size = audio_handler.isoc_out_rdptr - audio_handler.isoc_out_wrptr; + } + + /* free buffer enough to save rx data */ + if(audio_handler.buf_free_size > usb_rx_length){ + if(audio_handler.isoc_out_wrptr >= audio_handler.isoc_out_rdptr){ + tail_len = audio_handler.isoc_out_buff + TOTAL_OUT_BUF_SIZE - audio_handler.isoc_out_wrptr; + + if(tail_len >= usb_rx_length){ + memcpy(audio_handler.isoc_out_wrptr, audio_handler.usb_rx_buffer, usb_rx_length); + + /* increment the buffer pointer */ + audio_handler.isoc_out_wrptr += usb_rx_length; + + /* increment the Buffer pointer or roll it back when all buffers are full */ + if(audio_handler.isoc_out_wrptr >= (audio_handler.isoc_out_buff + TOTAL_OUT_BUF_SIZE)){ + /* all buffers are full: roll back */ + audio_handler.isoc_out_wrptr = audio_handler.isoc_out_buff; + } + }else{ + memcpy(audio_handler.isoc_out_wrptr, audio_handler.usb_rx_buffer, tail_len); + /* adjust write pointer */ + audio_handler.isoc_out_wrptr = audio_handler.isoc_out_buff; + + memcpy(audio_handler.isoc_out_wrptr, &audio_handler.usb_rx_buffer[tail_len], usb_rx_length - tail_len); + /* adjust write pointer */ + audio_handler.isoc_out_wrptr += usb_rx_length - tail_len; + } + }else{ + memcpy(audio_handler.isoc_out_wrptr, audio_handler.usb_rx_buffer, usb_rx_length); + + /* increment the buffer pointer */ + audio_handler.isoc_out_wrptr += usb_rx_length; + } + } + + /* Toggle the frame index */ + udev->dev.transc_out[ep_num].frame_num = (udev->dev.transc_out[ep_num].frame_num)? 0U:1U; + + /* prepare out endpoint to receive next audio packet */ + usbd_ep_recev (udev, AD_OUT_EP, audio_handler.usb_rx_buffer, SPEAKER_OUT_MAX_PACKET); + + if(audio_handler.isoc_out_wrptr >= audio_handler.isoc_out_rdptr){ + audio_handler.buf_free_size = TOTAL_OUT_BUF_SIZE + audio_handler.isoc_out_rdptr - audio_handler.isoc_out_wrptr; + }else{ + audio_handler.buf_free_size = audio_handler.isoc_out_rdptr - audio_handler.isoc_out_wrptr; + } + + if ((0U == audio_handler.play_flag) && (audio_handler.buf_free_size < TOTAL_OUT_BUF_SIZE/2)) { + /* enable start of streaming */ + audio_handler.play_flag = 1U; + + /* initialize the audio output hardware layer */ + if (USBD_OK != audio_out_fops.audio_cmd(audio_handler.isoc_out_rdptr, SPEAKER_OUT_MAX_PACKET/2, AD_CMD_PLAY)) { + return USBD_FAIL; + } + + audio_handler.dam_tx_len = SPEAKER_OUT_MAX_PACKET; + } + + return USBD_OK; +} + +/*! + \brief handles the SOF event (data buffer update and synchronization) + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_sof (usb_dev *udev) +{ + return USBD_OK; +} + +/*! + \brief handles the audio ISO IN Incomplete event + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_iso_in_incomplete (usb_dev *udev) +{ + (void)usb_txfifo_flush (&udev->regs, EP_ID(AD_FEEDBACK_IN_EP)); + + audio_handler.actual_freq = usbd_audio_spk_get_feedback(udev); + get_feedback_fs_rate(audio_handler.actual_freq, audio_handler.feedback_freq); + + /* send feedback data of estimated frequence*/ + usbd_ep_send(udev, AD_FEEDBACK_IN_EP, audio_handler.feedback_freq, FEEDBACK_IN_PACKET); + + return USBD_OK; +} + +/*! + \brief handles the audio ISO OUT Incomplete event + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +static uint8_t audio_iso_out_incomplete (usb_dev *udev) +{ + return USBD_OK; +} + +/*! + \brief calculate feedback sample frequency + \param[in] udev: pointer to USB device instance + \param[out] none + \retval feedback frequency value +*/ +static uint32_t usbd_audio_spk_get_feedback(usb_dev *udev) +{ + static uint32_t fb_freq; + + /* calculate buffer free size */ + if(audio_handler.isoc_out_wrptr >= audio_handler.isoc_out_rdptr){ + audio_handler.buf_free_size = TOTAL_OUT_BUF_SIZE + audio_handler.isoc_out_rdptr - audio_handler.isoc_out_wrptr; + }else{ + audio_handler.buf_free_size = audio_handler.isoc_out_rdptr - audio_handler.isoc_out_wrptr; + } + + /* calculate feedback frequency */ + if(audio_handler.buf_free_size <= (TOTAL_OUT_BUF_SIZE/4)){ + fb_freq = I2S_ACTUAL_SAM_FREQ(USBD_SPEAKER_FREQ) - FEEDBACK_FREQ_OFFSET; + }else if(audio_handler.buf_free_size >= (TOTAL_OUT_BUF_SIZE*3/4)){ + fb_freq = I2S_ACTUAL_SAM_FREQ(USBD_SPEAKER_FREQ) + FEEDBACK_FREQ_OFFSET; + }else{ + fb_freq = I2S_ACTUAL_SAM_FREQ(USBD_SPEAKER_FREQ); + } + + return fb_freq; +} + +/*! + \brief get feedback value from rate in USB full speed + \param[in] rate: sample frequence + \param[in] buf: pointer to result buffer + \param[out] none + \retval USB device operation status +*/ +static void get_feedback_fs_rate(uint32_t rate, uint8_t *buf) +{ + rate = ((rate / 1000) << 14) | ((rate % 1000) << 4); + + buf[0] = rate; + buf[1] = rate >> 8; + buf[2] = rate >> 16; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Source/audio_out_itf.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Source/audio_out_itf.c new file mode 100644 index 0000000..c9515a0 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/audio/Source/audio_out_itf.c @@ -0,0 +1,168 @@ +/*! + \file audio_out_itf.c + \brief audio OUT (playback) interface functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "audio_core.h" +#include "audio_out_itf.h" + +/* local function prototypes ('static') */ +static uint8_t init (uint32_t audio_freq, uint32_t volume); +static uint8_t deinit (void); +static uint8_t audio_cmd (uint8_t* pbuf, uint32_t size, uint8_t cmd); + +/* local variable defines */ +static uint8_t audio_state = AD_STATE_INACTIVE; + +audio_fops_struct audio_out_fops = +{ + .audio_init = init, + .audio_deinit = deinit, + .audio_cmd = audio_cmd, +}; + +/*! + \brief initialize and configures all required resources + \param[in] audio_freq: statrt_up audio frequency + \param[in] volume: start_up volume to be set + \param[out] none + \retval AD_OK if all operations succeed, otherwise, AD_FAIL. +*/ +static uint8_t init (uint32_t audio_freq, uint32_t volume) +{ + static uint32_t initialized = 0U; + + /* check if the low layer has already been initialized */ + if (0U == initialized) { + /* initialize GPIO */ + codec_gpio_init(); + + /* initialize i2s */ + codec_audio_interface_init(audio_freq); + + /* initialize DMA */ + codec_i2s_dma_init(); + + /* prevent reinitializing the interface again */ + initialized = 1U; + } + + /* update the audio state machine */ + audio_state = AD_STATE_ACTIVE; + + return AD_OK; +} + +/*! + \brief free all resources used by low layer and stops audio-play function + \param[in] none + \param[out] none + \retval AD_OK if all operations succeed, otherwise, AD_FAIL. +*/ +static uint8_t deinit (void) +{ + /* update the audio state machine */ + audio_state = AD_STATE_INACTIVE; + + return AD_OK; +} + +/*! + \brief play, stop, pause or resume current file + \param[in] pbuf: address from which file should be played + \param[in] size: size of the current buffer/file + \param[in] cmd: command to be executed, can be: + \arg AD_CMD_PLAY + \arg AD_CMD_PAUSE + \arg AD_CMD_RESUME + \arg AD_CMD_STOP + \param[out] none + \retval AD_OK if all operations succeed, otherwise, AD_FAIL. +*/ +static uint8_t audio_cmd (uint8_t* pbuf, uint32_t size, uint8_t cmd) +{ + /* check the current state */ + if ((AD_STATE_INACTIVE == audio_state) || (AD_STATE_ERROR == audio_state)) { + audio_state = AD_STATE_ERROR; + + return AD_FAIL; + } + + switch (cmd) { + /* process the play command */ + case AD_CMD_PLAY: + /* if current state is active or stopped */ + if ((AD_STATE_ACTIVE == audio_state) || \ + (AD_STATE_STOPPED == audio_state) || \ + (AD_STATE_PLAYING == audio_state)) { + audio_play((uint32_t)pbuf, size); + audio_state = AD_STATE_PLAYING; + + return AD_OK; + } else if (AD_STATE_PAUSED == audio_state) { + audio_pause_resume(AD_RESUME, (uint32_t)pbuf, (size/2)); + audio_state = AD_STATE_PLAYING; + + return AD_OK; + } else { + return AD_FAIL; + } + + /* process the stop command */ + case AD_CMD_STOP: + if (AD_STATE_PLAYING != audio_state) { + /* unsupported command */ + return AD_FAIL; + } else { + audio_stop(); + audio_state = AD_STATE_STOPPED; + + return AD_OK; + } + + /* process the pause command */ + case AD_CMD_PAUSE: + if (AD_STATE_PLAYING != audio_state) { + /* unsupported command */ + return AD_FAIL; + } else { + audio_pause_resume(AD_PAUSE, (uint32_t)pbuf, (size/2)); + audio_state = AD_STATE_PAUSED; + + return AD_OK; + } + + /* unsupported command */ + default: + return AD_FAIL; + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/cdc/Include/cdc_acm_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/cdc/Include/cdc_acm_core.h new file mode 100644 index 0000000..22fb2dd --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/cdc/Include/cdc_acm_core.h @@ -0,0 +1,65 @@ +/*! + \file cdc_acm_core.h + \brief the header file of cdc acm driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __CDC_ACM_CORE_H +#define __CDC_ACM_CORE_H + +#include "usbd_enum.h" +#include "usb_cdc.h" + +#define USB_CDC_RX_LEN USB_CDC_DATA_PACKET_SIZE + +typedef struct { + uint8_t data[USB_CDC_RX_LEN]; + uint8_t cmd[USB_CDC_CMD_PACKET_SIZE]; + + uint8_t packet_sent; + uint8_t packet_receive; + uint32_t receive_length; + + acm_line line_coding; +} usb_cdc_handler; + +extern usb_desc cdc_desc; +extern usb_class_core cdc_class; + +/* function declarations */ +/* check CDC ACM is ready for data transfer */ +uint8_t cdc_acm_check_ready(usb_dev *udev); +/* send CDC ACM data */ +void cdc_acm_data_send(usb_dev *udev, uint8_t *buf, uint8_t len, uint32_t *readLen); +/* receive CDC ACM data */ +void cdc_acm_data_receive(usb_dev *udev, uint8_t *buf, uint8_t len, uint32_t *readLen); + +#endif /* __CDC_ACM_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/cdc/Source/cdc_acm_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/cdc/Source/cdc_acm_core.c new file mode 100644 index 0000000..d46d530 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/cdc/Source/cdc_acm_core.c @@ -0,0 +1,550 @@ +/*! + \file cdc_acm_core.c + \brief CDC ACM driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "cdc_acm_core.h" +#include "osal.h" + +#define USBD_VID 0x2CA3U +#define USBD_PID 0xf002U + +/* note:it should use the C99 standard when compiling the below codes */ +/* USB standard device descriptor */ +__ALIGN_BEGIN const usb_desc_dev cdc_dev_desc __ALIGN_END = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV, + }, + .bcdUSB = 0x0200U, + .bDeviceClass = USB_CLASS_CDC, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM, +}; + +/* USB device configuration descriptor */ +__ALIGN_BEGIN const usb_cdc_desc_config_set cdc_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG, + }, + .wTotalLength = USB_CDC_ACM_CONFIG_DESC_SIZE, + .bNumInterfaces = 0x02U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0x80U, + .bMaxPower = 0x32U + }, + + .cmd_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x01U, + .bInterfaceClass = USB_CLASS_CDC, + .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, + .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, + .iInterface = 0x00U + }, + + .cdc_header = + { + .header = + { + .bLength = sizeof(usb_desc_header_func), + .bDescriptorType = USB_DESCTYPE_CS_INTERFACE + }, + .bDescriptorSubtype = 0x00U, + .bcdCDC = 0x0110U + }, + + .cdc_call_managment = + { + .header = + { + .bLength = sizeof(usb_desc_call_managment_func), + .bDescriptorType = USB_DESCTYPE_CS_INTERFACE + }, + .bDescriptorSubtype = 0x01U, + .bmCapabilities = 0x00U, + .bDataInterface = 0x01U + }, + + .cdc_acm = + { + .header = + { + .bLength = sizeof(usb_desc_acm_func), + .bDescriptorType = USB_DESCTYPE_CS_INTERFACE + }, + .bDescriptorSubtype = 0x02U, + .bmCapabilities = 0x02U, + }, + + .cdc_union = + { + .header = + { + .bLength = sizeof(usb_desc_union_func), + .bDescriptorType = USB_DESCTYPE_CS_INTERFACE + }, + .bDescriptorSubtype = 0x06U, + .bMasterInterface = 0x00U, + .bSlaveInterface0 = 0x01U, + }, + + .cdc_cmd_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP, + }, + .bEndpointAddress = CDC_CMD_EP, + .bmAttributes = USB_EP_ATTR_INT, + .wMaxPacketSize = USB_CDC_CMD_PACKET_SIZE, + .bInterval = 0x0AU + }, + + .cdc_data_interface = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF, + }, + .bInterfaceNumber = 0x01U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x02U, + .bInterfaceClass = USB_CLASS_DATA, + .bInterfaceSubClass = 0x00U, + .bInterfaceProtocol = USB_CDC_PROTOCOL_NONE, + .iInterface = 0x00U + }, + + .cdc_out_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP, + }, + .bEndpointAddress = CDC_DATA_OUT_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = USB_CDC_DATA_PACKET_SIZE, + .bInterval = 0x00U + }, + + .cdc_in_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = CDC_DATA_IN_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = USB_CDC_DATA_PACKET_SIZE, + .bInterval = 0x00U + } +}; + +/* USB language ID Descriptor */ +static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(10), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'C', 'D', 'C', '_', 'A', 'C', 'M'} +}; + +/* USBD serial string */ +static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +/* USB string descriptor set */ +void *const usbd_cdc_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *) &usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *) &manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *) &product_string, + [STR_IDX_SERIAL] = (uint8_t *) &serial_string +}; + +usb_desc cdc_desc = +{ + .dev_desc = (uint8_t *) &cdc_dev_desc, + .config_desc = (uint8_t *) &cdc_config_desc, + .strings = usbd_cdc_strings +}; + +/* local function prototypes ('static') */ +static uint8_t cdc_acm_init (usb_dev *udev, uint8_t config_index); +static uint8_t cdc_acm_deinit (usb_dev *udev, uint8_t config_index); +static uint8_t cdc_acm_req (usb_dev *udev, usb_req *req); +static uint8_t cdc_acm_ctlx_out (usb_dev *udev); +static uint8_t cdc_acm_in (usb_dev *udev, uint8_t ep_num); +static uint8_t cdc_acm_out (usb_dev *udev, uint8_t ep_num); + +/* USB CDC device class callbacks structure */ +usb_class_core cdc_class = +{ + .command = NO_CMD, + .alter_set = 0U, + + .init = cdc_acm_init, + .deinit = cdc_acm_deinit, + .req_proc = cdc_acm_req, + .ctlx_out = cdc_acm_ctlx_out, + .data_in = cdc_acm_in, + .data_out = cdc_acm_out +}; + +/*! + \brief check CDC ACM is ready for data transfer + \param[in] udev: pointer to USB device instance + \param[out] none + \retval 0 if CDC is ready, 5 else +*/ +uint8_t cdc_acm_check_ready(usb_dev *udev) +{ + if (udev->dev.class_data[CDC_COM_INTERFACE] != NULL) { + usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE]; + + if ((1U == cdc->packet_receive) && (1U == cdc->packet_sent)) { + return 0U; + } + } + + return 1U; +} + +/*! + \brief send CDC ACM data + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +void cdc_acm_data_send(usb_dev *udev, uint8_t *buf, uint8_t len, uint32_t *readLen) +{ + usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE]; + uint32_t cnt = 0; + + cdc->packet_sent = 0U; + + usbd_ep_send (udev, CDC_DATA_IN_EP, buf, len); + while(1) { + Osal_TaskSleepMs(1); + if (cdc->packet_sent == 1) { + *readLen = len; + break; + } + + if (cnt++ >= 100) + { + cnt = 0; + *readLen = 0; + break; + } + } + usbd_fifo_flush(udev, CDC_DATA_IN_EP); +} + +/*! + \brief receive CDC ACM data + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +void cdc_acm_data_receive(usb_dev *udev, uint8_t *buf, uint8_t len, uint32_t *readLen) +{ + usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE]; + + cdc->packet_receive = 0U; + + usbd_ep_recev(udev, CDC_DATA_OUT_EP, (uint8_t*)(cdc->data), USB_CDC_DATA_PACKET_SIZE); + while(1) { + Osal_TaskSleepMs(1); + if (cdc->packet_receive == 1) { + memcpy(buf, cdc->data, cdc->receive_length); + *readLen = cdc->receive_length; + break; + } + } + usbd_fifo_flush(udev, CDC_DATA_OUT_EP); +} + +/*! + \brief initialize the CDC ACM device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t cdc_acm_init (usb_dev *udev, uint8_t config_index) +{ + static __ALIGN_BEGIN usb_cdc_handler cdc_handler __ALIGN_END; + + /* initialize the data Tx endpoint */ + usbd_ep_setup (udev, &(cdc_config_desc.cdc_in_endpoint)); + + /* initialize the data Rx endpoint */ + usbd_ep_setup (udev, &(cdc_config_desc.cdc_out_endpoint)); + + /* initialize the command Tx endpoint */ + usbd_ep_setup (udev, &(cdc_config_desc.cdc_cmd_endpoint)); + + /* initialize CDC handler structure */ + cdc_handler.packet_receive = 1U; + cdc_handler.packet_sent = 1U; + cdc_handler.receive_length = 0U; + + cdc_handler.line_coding = (acm_line){ + .dwDTERate = 921600U, + .bCharFormat = 0U, + .bParityType = 0U, + .bDataBits = 0x08U + }; + + udev->dev.class_data[CDC_COM_INTERFACE] = (void *)&cdc_handler; + + return USBD_OK; +} + +/*! + \brief deinitialize the CDC ACM device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t cdc_acm_deinit (usb_dev *udev, uint8_t config_index) +{ + /* deinitialize the data Tx/Rx endpoint */ + usbd_ep_clear (udev, CDC_DATA_IN_EP); + usbd_ep_clear (udev, CDC_DATA_OUT_EP); + + /* deinitialize the command Tx endpoint */ + usbd_ep_clear (udev, CDC_CMD_EP); + + return USBD_OK; +} + +/*! + \brief handle the CDC ACM class-specific requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t cdc_acm_req (usb_dev *udev, usb_req *req) +{ + usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE]; + + usb_transc *transc = NULL; + + switch (req->bRequest) { + case SEND_ENCAPSULATED_COMMAND: + /* no operation for this driver */ + break; + + case GET_ENCAPSULATED_RESPONSE: + /* no operation for this driver */ + break; + + case SET_COMM_FEATURE: + /* no operation for this driver */ + break; + + case GET_COMM_FEATURE: + /* no operation for this driver */ + break; + + case CLEAR_COMM_FEATURE: + /* no operation for this driver */ + break; + + case SET_LINE_CODING: + transc = &udev->dev.transc_out[0]; + + /* set the value of the current command to be processed */ + udev->dev.class_core->alter_set = req->bRequest; + + /* enable EP0 prepare to receive command data packet */ + transc->remain_len = req->wLength; + transc->xfer_buf = cdc->cmd; + break; + + case GET_LINE_CODING: + transc = &udev->dev.transc_in[0]; + + cdc->cmd[0] = (uint8_t)(cdc->line_coding.dwDTERate); + cdc->cmd[1] = (uint8_t)(cdc->line_coding.dwDTERate >> 8); + cdc->cmd[2] = (uint8_t)(cdc->line_coding.dwDTERate >> 16); + cdc->cmd[3] = (uint8_t)(cdc->line_coding.dwDTERate >> 24); + cdc->cmd[4] = cdc->line_coding.bCharFormat; + cdc->cmd[5] = cdc->line_coding.bParityType; + cdc->cmd[6] = cdc->line_coding.bDataBits; + + transc->xfer_buf = cdc->cmd; + transc->remain_len = 7U; + break; + + case SET_CONTROL_LINE_STATE: + /* no operation for this driver */ + break; + + case SEND_BREAK: + /* no operation for this driver */ + break; + + default: + break; + } + + return USBD_OK; +} + +/*! + \brief command data received on control endpoint + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +static uint8_t cdc_acm_ctlx_out (usb_dev *udev) +{ + usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE]; + + if (udev->dev.class_core->alter_set != NO_CMD) { + /* process the command data */ + cdc->line_coding.dwDTERate = (uint32_t)((uint32_t)cdc->cmd[0] | + ((uint32_t)cdc->cmd[1] << 8U) | + ((uint32_t)cdc->cmd[2] << 16U) | + ((uint32_t)cdc->cmd[3] << 24U)); + + cdc->line_coding.bCharFormat = cdc->cmd[4]; + cdc->line_coding.bParityType = cdc->cmd[5]; + cdc->line_coding.bDataBits = cdc->cmd[6]; + + udev->dev.class_core->alter_set = NO_CMD; + } + + return USBD_OK; +} + +/*! + \brief handle CDC ACM data in + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier + \param[out] none + \retval USB device operation status +*/ +static uint8_t cdc_acm_in (usb_dev *udev, uint8_t ep_num) +{ + usb_transc *transc = &udev->dev.transc_in[EP_ID(ep_num)]; + + usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE]; + + if ((0U == transc->xfer_len % transc->max_len) && (0U != transc->xfer_len)) { + usbd_ep_send (udev, ep_num, NULL, 0U); + } else { + cdc->packet_sent = 1U; + } + + return USBD_OK; +} + +/*! + \brief handle CDC ACM data out + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier + \param[out] none + \retval USB device operation status +*/ +static uint8_t cdc_acm_out (usb_dev *udev, uint8_t ep_num) +{ + usb_cdc_handler *cdc = (usb_cdc_handler *)udev->dev.class_data[CDC_COM_INTERFACE]; + + cdc->packet_receive = 1U; + cdc->receive_length = ((usb_core_driver *)udev)->dev.transc_out[ep_num].xfer_count; + + return USBD_OK; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Include/dfu_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Include/dfu_core.h new file mode 100644 index 0000000..73f2a79 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Include/dfu_core.h @@ -0,0 +1,175 @@ +/*! + \file dfu_core.h + \brief the header file of USB DFU device class core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DFU_CORE_H +#define __DFU_CORE_H + +#include "usbd_enum.h" + +/* DFU class code */ +#define USB_DFU_CLASS 0xFEU + +/* DFU subclass code */ +#define USB_DFU_SUBCLASS_UPGRADE 0x01U + +/* DFU protocol code */ +#define USB_DFU_PROTOCL_RUNTIME 0x01U +#define USB_DFU_PROTOCL_DFU 0x02U + +/* manifestation state */ +#define MANIFEST_COMPLETE 0x00U +#define MANIFEST_IN_PROGRESS 0x01U + +/* DFU attributes code */ +#define USB_DFU_CAN_DOWNLOAD 0x01U +#define USB_DFU_CAN_UPLOAD 0x02U +#define USB_DFU_MANIFEST_TOLERANT 0x04U +#define USB_DFU_WILL_DETACH 0x08U + +/* special commands with download request */ +#define GET_COMMANDS 0x00U +#define SET_ADDRESS_POINTER 0x21U +#define ERASE 0x41U + +/* memory operation command */ +#define CMD_ERASE 0U +#define CMD_WRITE 1U + +#define _BYTE1(x) (uint8_t)((x) & 0xFFU) /*!< addressing cycle 1st byte */ +#define _BYTE2(x) (uint8_t)(((x) & 0xFF00U) >> 8U) /*!< addressing cycle 2nd byte */ +#define _BYTE3(x) (uint8_t)(((x) & 0xFF0000U) >> 16U) /*!< addressing cycle 3rd byte */ + +#define FLASH_ERASE_TIMEOUT 60U +#define FLASH_WRITE_TIMEOUT 80U + +/* bit detach capable = bit 3 in bmAttributes field */ +#define DFU_DETACH_MASK (uint8_t)(0x10U) + +#define DFU_DESC_TYPE 0x21U + +/* DFU device state defines */ +typedef enum { + STATE_APP_IDLE = 0x00U, + STATE_APP_DETACH, + STATE_DFU_IDLE, + STATE_DFU_DNLOAD_SYNC, + STATE_DFU_DNBUSY, + STATE_DFU_DNLOAD_IDLE, + STATE_DFU_MANIFEST_SYNC, + STATE_DFU_MANIFEST, + STATE_DFU_MANIFEST_WAIT_RESET, + STATE_DFU_UPLOAD_IDLE, + STATE_DFU_ERROR +} dfu_state; + +/* DFU device status defines */ +typedef enum { + STATUS_OK = 0x00U, + STATUS_ERR_TARGET, + STATUS_ERR_FILE, + STATUS_ERR_WRITE, + STATUS_ERR_ERASE, + STATUS_ERR_CHECK_ERASED, + STATUS_ERR_PROG, + STATUS_ERR_VERIFY, + STATUS_ERR_ADDRESS, + STATUS_ERR_NOTDONE, + STATUS_ERR_FIRMWARE, + STATUS_ERR_VENDOR, + STATUS_ERR_USBR, + STATUS_ERR_POR, + STATUS_ERR_UNKNOWN, + STATUS_ERR_STALLEDPKT +} dfu_status; + +/* DFU class-specific requests */ +typedef enum { + DFU_DETACH = 0U, + DFU_DNLOAD, + DFU_UPLOAD, + DFU_GETSTATUS, + DFU_CLRSTATUS, + DFU_GETSTATE, + DFU_ABORT, + DFU_REQ_MAX +} dfu_requests; + +#pragma pack(1) + +/* USB DFU function descriptor structure */ +typedef struct +{ + usb_desc_header header; /*!< descriptor header, including type and size */ + uint8_t bmAttributes; /*!< DFU attributes */ + uint16_t wDetachTimeOut; /*!< time, in milliseconds, that the device will wait after receipt of the DFU_DETACH request. If */ + uint16_t wTransferSize; /*!< maximum number of bytes that the device can accept per control-write transaction */ + uint16_t bcdDFUVersion; /*!< numeric expression identifying the version of the DFU specification release. */ +} usb_desc_dfu_func; + +#pragma pack() + +/* USB configuration descriptor structure */ +typedef struct +{ + usb_desc_config config; + usb_desc_itf dfu_itf0; + usb_desc_itf dfu_itf1; + usb_desc_itf dfu_itf2; + usb_desc_dfu_func dfu_func; +} usb_dfu_desc_config_set; + +/* USB DFU handler structure */ +typedef struct +{ + uint8_t bStatus; + uint8_t bwPollTimeout0; + uint8_t bwPollTimeout1; + uint8_t bwPollTimeout2; + uint8_t bState; + uint8_t iString; + + uint8_t manifest_state; + uint32_t data_len; + uint16_t block_num; + uint32_t base_addr; + + uint8_t buf[TRANSFER_SIZE]; +} usbd_dfu_handler; + +typedef void (*app_func) (void); + +extern usb_desc dfu_desc; +extern usb_class_core dfu_class; + +#endif /* DFU_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Include/dfu_mem.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Include/dfu_mem.h new file mode 100644 index 0000000..3762189 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Include/dfu_mem.h @@ -0,0 +1,83 @@ +/*! + \file dfu_mem.h + \brief USB DFU device media access layer header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DFU_MEM_H +#define __DFU_MEM_H + +#include "usb_conf.h" + +typedef struct _dfu_mem_prop +{ + const uint8_t* pstr_desc; + + uint8_t (*mem_init) (void); + uint8_t (*mem_deinit) (void); + uint8_t (*mem_erase) (uint32_t addr); + uint8_t (*mem_write) (uint8_t *buf, uint32_t addr, uint32_t len); + uint8_t* (*mem_read) (uint8_t *buf, uint32_t addr, uint32_t len); + uint8_t (*mem_checkaddr) (uint32_t addr); + + const uint32_t erase_timeout; + const uint32_t write_timeout; +} dfu_mem_prop; + +typedef enum +{ + MEM_OK = 0, + MEM_FAIL +} mem_status; + +#define _1ST_BYTE(x) (uint8_t)((x) & 0xFF) /*!< addressing cycle 1st byte */ +#define _2ND_BYTE(x) (uint8_t)(((x) & 0xFF00) >> 8) /*!< addressing cycle 2nd byte */ +#define _3RD_BYTE(x) (uint8_t)(((x) & 0xFF0000) >> 16) /*!< addressing cycle 3rd byte */ + +#define POLLING_TIMEOUT_SET(x) buffer[0] = _1ST_BYTE(x);\ + buffer[1] = _2ND_BYTE(x);\ + buffer[2] = _3RD_BYTE(x); + +/* function declarations */ +/* initialize the memory media on the GD32 */ +uint8_t dfu_mem_init(void); +/* deinitialize the memory media on the GD32 */ +uint8_t dfu_mem_deinit(void); +/* erase a memory sector */ +uint8_t dfu_mem_erase(uint32_t addr); +/* write data to sectors of memory */ +uint8_t dfu_mem_write(uint8_t *buf, uint32_t addr, uint32_t len); +/* read data from sectors of memory */ +uint8_t* dfu_mem_read(uint8_t *buf, uint32_t addr, uint32_t len); +/* get the status of a given memory and store in buffer */ +uint8_t dfu_mem_getstatus(uint32_t addr, uint8_t cmd, uint8_t *buffer); + +#endif /* __DFU_MEM_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Source/dfu_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Source/dfu_core.c new file mode 100644 index 0000000..0d1a531 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Source/dfu_core.c @@ -0,0 +1,733 @@ +/*! + \file dfu_core.c + \brief USB DFU device class core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "dfu_core.h" +#include "dfu_mem.h" +#include "drv_usb_hw.h" +#include + +#define USBD_VID 0x28E9U +#define USBD_PID 0x0189U + +/* local function prototypes ('static') */ +static uint8_t dfu_init(usb_dev *udev, uint8_t config_index); +static uint8_t dfu_deinit(usb_dev *udev, uint8_t config_index); +static uint8_t dfu_req_handler(usb_dev *udev, usb_req *req); +static uint8_t dfu_ctlx_in(usb_dev *udev); + +static void dfu_mode_leave(usb_dev *udev); +static uint8_t dfu_getstatus_complete (usb_dev *udev); + +/* DFU requests management functions */ +static void dfu_detach(usb_dev *udev, usb_req *req); +static void dfu_dnload(usb_dev *udev, usb_req *req); +static void dfu_upload(usb_dev *udev, usb_req *req); +static void dfu_getstatus(usb_dev *udev, usb_req *req); +static void dfu_clrstatus(usb_dev *udev, usb_req *req); +static void dfu_getstate(usb_dev *udev, usb_req *req); +static void dfu_abort(usb_dev *udev, usb_req *req); + +static void string_to_unicode (uint8_t *str, uint16_t *pbuf); + +static void (*dfu_request_process[])(usb_dev *udev, usb_req *req) = +{ + [DFU_DETACH] = dfu_detach, + [DFU_DNLOAD] = dfu_dnload, + [DFU_UPLOAD] = dfu_upload, + [DFU_GETSTATUS] = dfu_getstatus, + [DFU_CLRSTATUS] = dfu_clrstatus, + [DFU_GETSTATE] = dfu_getstate, + [DFU_ABORT] = dfu_abort +}; + +/* note:it should use the c99 standard when compiling the below codes */ +/* USB standard device descriptor */ +__ALIGN_BEGIN const usb_desc_dev dfu_dev_desc __ALIGN_END = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV + }, + .bcdUSB = 0x0200U, + .bDeviceClass = 0x00U, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM +}; + +/* USB device configuration descriptor */ +__ALIGN_BEGIN const usb_dfu_desc_config_set dfu_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG + }, + .wTotalLength = sizeof(usb_dfu_desc_config_set), + .bNumInterfaces = 0x01U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0x80U, + .bMaxPower = 0x32U + }, + + .dfu_itf0 = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x00U, + .bInterfaceClass = USB_DFU_CLASS, + .bInterfaceSubClass = USB_DFU_SUBCLASS_UPGRADE, + .bInterfaceProtocol = USB_DFU_PROTOCL_DFU, + .iInterface = STR_IDX_ALT_ITF0 + }, + + .dfu_itf1 = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x01U, + .bNumEndpoints = 0x00U, + .bInterfaceClass = USB_DFU_CLASS, + .bInterfaceSubClass = USB_DFU_SUBCLASS_UPGRADE, + .bInterfaceProtocol = USB_DFU_PROTOCL_DFU, + .iInterface = STR_IDX_ALT_ITF1 + }, + + .dfu_itf2 = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x02U, + .bNumEndpoints = 0x00U, + .bInterfaceClass = USB_DFU_CLASS, + .bInterfaceSubClass = USB_DFU_SUBCLASS_UPGRADE, + .bInterfaceProtocol = USB_DFU_PROTOCL_DFU, + .iInterface = STR_IDX_ALT_ITF2 + }, + + .dfu_func= + { + .header = + { + .bLength = sizeof(usb_desc_dfu_func), + .bDescriptorType = DFU_DESC_TYPE + }, + .bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_CAN_UPLOAD | USB_DFU_WILL_DETACH, + .wDetachTimeOut = 0x00FFU, + .wTransferSize = TRANSFER_SIZE, + .bcdDFUVersion = 0x0110U, + }, +}; + +/* USB language ID descriptor */ +static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR + }, + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(10U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'D', 'F', 'U'} +}; + +/* USB serial string */ +static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(2U), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +/* USB configure string */ +static __ALIGN_BEGIN const usb_desc_str config_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(15U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', ' ', 'U', 'S', 'B', ' ', 'C', 'O', 'N', 'F', 'I', 'G'} +}; + +/* alternate interface 0 string */ +static __ALIGN_BEGIN usb_desc_str interface_string0 __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(2U), + .bDescriptorType = USB_DESCTYPE_STR, + }, +}; + +/* alternate interface 1 string */ +static __ALIGN_BEGIN usb_desc_str interface_string1 __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(2U), + .bDescriptorType = USB_DESCTYPE_STR, + }, +}; + +/* alternate interface 2 string */ +static __ALIGN_BEGIN usb_desc_str interface_string2 __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(2U), + .bDescriptorType = USB_DESCTYPE_STR, + }, +}; + +void *const usbd_dfu_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *)&usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *)&manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *)&product_string, + [STR_IDX_SERIAL] = (uint8_t *)&serial_string, + [STR_IDX_CONFIG] = (uint8_t *)&config_string, + [STR_IDX_ALT_ITF0] = (uint8_t *)&interface_string0, + [STR_IDX_ALT_ITF1] = (uint8_t *)&interface_string1, + [STR_IDX_ALT_ITF2] = (uint8_t *)&interface_string2, +}; + +usb_desc dfu_desc = { + .dev_desc = (uint8_t *)&dfu_dev_desc, + .config_desc = (uint8_t *)&dfu_config_desc, + .strings = usbd_dfu_strings +}; + +usb_class_core dfu_class = { + .init = dfu_init, + .deinit = dfu_deinit, + .req_proc = dfu_req_handler, + .ctlx_in = dfu_ctlx_in +}; + +/*! + \brief initialize the DFU device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t dfu_init (usb_dev *udev, uint8_t config_index) +{ + static __ALIGN_BEGIN usbd_dfu_handler dfu_handler __ALIGN_END; + + /* unlock the internal flash */ + dfu_mem_init(); + + memset((void *)&dfu_handler, 0, sizeof(usbd_dfu_handler)); + + dfu_handler.manifest_state = MANIFEST_COMPLETE; + dfu_handler.bState = STATE_DFU_IDLE; + dfu_handler.bStatus = STATUS_OK; + + udev->dev.class_data[USBD_DFU_INTERFACE] = (void *)&dfu_handler; + + /* create interface string */ + string_to_unicode((uint8_t *)dfu_inter_flash_cb.pstr_desc, udev->dev.desc->strings[STR_IDX_ALT_ITF0]); + string_to_unicode((uint8_t *)dfu_nor_flash_cb.pstr_desc, udev->dev.desc->strings[STR_IDX_ALT_ITF1]); + string_to_unicode((uint8_t *)dfu_nand_flash_cb.pstr_desc, udev->dev.desc->strings[STR_IDX_ALT_ITF2]); + + return USBD_OK; +} + +/*! + \brief deinitialize the DFU device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t dfu_deinit (usb_dev *udev, uint8_t config_index) +{ + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + /* restore device default state */ + memset(udev->dev.class_data[USBD_DFU_INTERFACE], 0, sizeof(usbd_dfu_handler)); + + dfu->bState = STATE_DFU_IDLE; + dfu->bStatus = STATUS_OK; + + /* deinit the memory */ + dfu_mem_deinit(); + + return USBD_OK; +} + +/*! + \brief handle the DFU class-specific requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t dfu_req_handler (usb_dev *udev, usb_req *req) +{ + if (req->bRequest < DFU_REQ_MAX) { + dfu_request_process[req->bRequest](udev, req); + } else { + return USBD_FAIL; + } + + return USBD_OK; +} + +/*! + \brief handle data stage + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +static uint8_t dfu_ctlx_in (usb_dev *udev) +{ + dfu_getstatus_complete(udev); + + return USBD_OK; +} + +/*! + \brief leave DFU mode and reset device to jump to user loaded code + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +static void dfu_mode_leave (usb_dev *udev) +{ + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + dfu->manifest_state = MANIFEST_COMPLETE; + + if (dfu_config_desc.dfu_func.bmAttributes & 0x04U) { + dfu->bState = STATE_DFU_MANIFEST_SYNC; + } else { + dfu->bState = STATE_DFU_MANIFEST_WAIT_RESET; + + /* deinit the memory */ + dfu_mem_deinit(); + + /* generate system reset to allow jumping to the user code */ + NVIC_SystemReset(); + } +} + +/*! + \brief handle data IN stage in control endpoint 0 + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status + */ +static uint8_t dfu_getstatus_complete (usb_dev *udev) +{ + uint32_t addr; + + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + if (STATE_DFU_DNBUSY == dfu->bState) { + /* decode the special command */ + if (0U == dfu->block_num) { + if (1U == dfu->data_len){ + if (GET_COMMANDS == dfu->buf[0]) { + /* no operation */ + } + } else if (5U == dfu->data_len) { + if (SET_ADDRESS_POINTER == dfu->buf[0]) { + /* set flash operation address */ + dfu->base_addr = *(uint32_t *)(dfu->buf + 1U); + } else if (ERASE == dfu->buf[0]) { + dfu->base_addr = *(uint32_t *)(dfu->buf + 1U); + + dfu_mem_erase(dfu->base_addr); + } else { + /* no operation */ + } + } else { + /* no operation */ + } + } else if (dfu->block_num > 1U) { /* regular download command */ + /* decode the required address */ + addr = (dfu->block_num - 2U) * TRANSFER_SIZE + dfu->base_addr; + + dfu_mem_write (dfu->buf, addr, dfu->data_len); + + dfu->block_num = 0U; + } else { + /* no operation */ + } + + dfu->data_len = 0U; + + /* update the device state and poll timeout */ + dfu->bState = STATE_DFU_DNLOAD_SYNC; + + return USBD_OK; + } else if (dfu->bState == STATE_DFU_MANIFEST) { /* manifestation in progress */ + /* start leaving DFU mode */ + dfu_mode_leave(udev); + } else { + /* no operation */ + } + + return USBD_OK; +} + +/*! + \brief handle the DFU_DETACH request + \param[in] udev: pointer to USB device instance + \param[in] req: DFU class request + \param[out] none + \retval none. +*/ +static void dfu_detach(usb_dev *udev, usb_req *req) +{ + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + switch (dfu->bState) { + case STATE_DFU_IDLE: + case STATE_DFU_DNLOAD_SYNC: + case STATE_DFU_DNLOAD_IDLE: + case STATE_DFU_MANIFEST_SYNC: + case STATE_DFU_UPLOAD_IDLE: + dfu->bStatus = STATUS_OK; + dfu->bState = STATE_DFU_IDLE; + dfu->iString = 0U; /* iString */ + + dfu->block_num = 0U; + dfu->data_len = 0U; + break; + + default: + break; + } + + /* check the detach capability in the DFU functional descriptor */ + if (dfu_config_desc.dfu_func.wDetachTimeOut & DFU_DETACH_MASK) { + usbd_disconnect (udev); + + usbd_connect (udev); + } else { + /* wait for the period of time specified in detach request */ + usb_mdelay (4U); + } +} + +/*! + \brief handle the DFU_DNLOAD request + \param[in] udev: pointer to USB device instance + \param[in] req: DFU class request + \param[out] none + \retval none +*/ +static void dfu_dnload(usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_out[0]; + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + switch (dfu->bState) { + case STATE_DFU_IDLE: + case STATE_DFU_DNLOAD_IDLE: + if (req->wLength > 0U) { + /* update the global length and block number */ + dfu->block_num = req->wValue; + dfu->data_len = req->wLength; + + dfu->bState = STATE_DFU_DNLOAD_SYNC; + + transc->remain_len = dfu->data_len; + transc->xfer_buf = dfu->buf; + } else { + dfu->manifest_state = MANIFEST_IN_PROGRESS; + dfu->bState = STATE_DFU_MANIFEST_SYNC; + } + break; + + default: + break; + } +} + +/*! + \brief handles the DFU UPLOAD request. + \param[in] udev: pointer to USB device instance + \param[in] req: DFU class request + \param[out] none + \retval none +*/ +static void dfu_upload (usb_dev *udev, usb_req *req) +{ + uint8_t *phy_addr = NULL; + uint32_t addr = 0U; + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + usb_transc *transc = &udev->dev.transc_in[0]; + + if(req->wLength <= 0U) { + dfu->bState = STATE_DFU_IDLE; + return; + } + + switch (dfu->bState) { + case STATE_DFU_IDLE: + case STATE_DFU_UPLOAD_IDLE: + /* update the global length and block number */ + dfu->block_num = req->wValue; + dfu->data_len = req->wLength; + + /* DFU get command */ + if (0U == dfu->block_num) { + /* update the state machine */ + dfu->bState = (dfu->data_len > 3U) ? STATE_DFU_IDLE : STATE_DFU_UPLOAD_IDLE; + + /* store the values of all supported commands */ + dfu->buf[0] = GET_COMMANDS; + dfu->buf[1] = SET_ADDRESS_POINTER; + dfu->buf[2] = ERASE; + + /* send the status data over EP0 */ + transc->xfer_buf = &(dfu->buf[0]); + transc->remain_len = 3U; + } else if (dfu->block_num > 1U) { + dfu->bState = STATE_DFU_UPLOAD_IDLE; + + /* change is accelerated */ + addr = (dfu->block_num - 2U) * TRANSFER_SIZE + dfu->base_addr; + + /* return the physical address where data are stored */ + phy_addr = dfu_mem_read (dfu->buf, addr, dfu->data_len); + + /* send the status data over EP0 */ + transc->xfer_buf = phy_addr; + transc->remain_len = dfu->data_len; + } else { + dfu->bState = STATUS_ERR_STALLEDPKT; + } + break; + + default: + dfu->data_len = 0U; + dfu->block_num = 0U; + break; + } +} + +/*! + \brief handle the DFU_GETSTATUS request + \param[in] udev: pointer to USB device instance + \param[in] req: DFU class request + \param[out] none + \retval none +*/ +static void dfu_getstatus (usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + switch (dfu->bState) { + case STATE_DFU_DNLOAD_SYNC: + if (0U != dfu->data_len) { + dfu->bState = STATE_DFU_DNBUSY; + + if (0U == dfu->block_num) { + if (ERASE == dfu->buf[0]) { + dfu_mem_getstatus (dfu->base_addr, CMD_ERASE, (uint8_t *)&dfu->bwPollTimeout0); + } else { + dfu_mem_getstatus (dfu->base_addr, CMD_WRITE, (uint8_t *)&dfu->bwPollTimeout0); + } + } + } else { + dfu->bState = STATE_DFU_DNLOAD_IDLE; + } + break; + + case STATE_DFU_MANIFEST_SYNC: + if (MANIFEST_IN_PROGRESS == dfu->manifest_state) { + dfu->bState = STATE_DFU_MANIFEST; + dfu->bwPollTimeout0 = 1U; + } else if ((MANIFEST_COMPLETE == dfu->manifest_state) && \ + (dfu_config_desc.dfu_func.bmAttributes & 0x04U)){ + dfu->bState = STATE_DFU_IDLE; + dfu->bwPollTimeout0 = 0U; + } else { + /* no operation */ + } + break; + + default: + break; + } + + /* send the status data of DFU interface to host over EP0 */ + transc->xfer_buf = (uint8_t *)&(dfu->bStatus); + transc->remain_len = 6U; +} + +/*! + \brief handle the DFU_CLRSTATUS request + \param[in] udev: pointer to USB device instance + \param[in] req: DFU class request + \param[out] none + \retval none +*/ +static void dfu_clrstatus (usb_dev *udev, usb_req *req) +{ + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + if (STATE_DFU_ERROR == dfu->bState) { + dfu->bStatus = STATUS_OK; + dfu->bState = STATE_DFU_IDLE; + } else { + /* state error */ + dfu->bStatus = STATUS_ERR_UNKNOWN; + dfu->bState = STATE_DFU_ERROR; + } + + dfu->iString = 0U; /* iString: index = 0 */ +} + +/*! + \brief handle the DFU_GETSTATE request + \param[in] udev: pointer to USB device instance + \param[in] req: DFU class request + \param[out] none + \retval none +*/ +static void dfu_getstate (usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + /* send the current state of the DFU interface to host */ + transc->xfer_buf = &(dfu->bState); + transc->remain_len = 1U; +} + +/*! + \brief handle the DFU_ABORT request + \param[in] udev: pointer to USB device instance + \param[in] req: DFU class request + \param[out] none + \retval none +*/ +static void dfu_abort (usb_dev *udev, usb_req *req) +{ + usbd_dfu_handler *dfu = (usbd_dfu_handler *)udev->dev.class_data[USBD_DFU_INTERFACE]; + + switch (dfu->bState){ + case STATE_DFU_IDLE: + case STATE_DFU_DNLOAD_SYNC: + case STATE_DFU_DNLOAD_IDLE: + case STATE_DFU_MANIFEST_SYNC: + case STATE_DFU_UPLOAD_IDLE: + dfu->bStatus = STATUS_OK; + dfu->bState = STATE_DFU_IDLE; + dfu->iString = 0U; /* iString: index = 0 */ + + dfu->block_num = 0U; + dfu->data_len = 0U; + break; + + default: + break; + } +} + +/*! + \brief convert string value into unicode char + \param[in] str: pointer to plain string + \param[in] pbuf: buffer pointer to store unicode char + \param[out] none + \retval none +*/ +static void string_to_unicode (uint8_t *str, uint16_t *pbuf) +{ + uint8_t index = 0; + + if (str != NULL) { + pbuf[index++] = ((strlen((const char *)str) * 2U + 2U) & 0x00FFU) | ((USB_DESCTYPE_STR << 8U) & 0xFF00); + + while (*str != '\0') { + pbuf[index++] = *str++; + } + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Source/dfu_mem.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Source/dfu_mem.c new file mode 100644 index 0000000..b0f70e7 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/dfu/Source/dfu_mem.c @@ -0,0 +1,243 @@ +/*! + \file dfu_mem.c + \brief USB DFU device media access layer functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "dfu_mem.h" +#include "drv_usb_hw.h" +#include "usbd_transc.h" + +extern usb_core_driver usb_dfu_dev; + +extern struct { + uint8_t buf[TRANSFER_SIZE]; + uint16_t data_len; + uint16_t block_num; + uint32_t base_addr; +} prog; + +dfu_mem_prop* mem_tab[MAX_USED_MEMORY_MEDIA] = { + &dfu_inter_flash_cb, + &dfu_nor_flash_cb, + &dfu_nand_flash_cb, +}; + +/* The list of memory interface string descriptor pointers. This list + can be updated whenever a memory has to be added or removed */ +const uint8_t* USBD_DFU_StringDesc[MAX_USED_MEMORY_MEDIA] = +{ + (const uint8_t *)INTER_FLASH_IF_STR, + (const uint8_t *)NOR_FLASH_IF_STR, + (const uint8_t *)NAND_FLASH_IF_STR +}; + +static uint8_t dfu_mem_checkaddr (uint32_t addr); + +/*! + \brief initialize the memory media on the GD32 + \param[in] none + \param[out] none + \retval MEM_OK +*/ +uint8_t dfu_mem_init (void) +{ + uint32_t mem_index = 0U; + + /* initialize all supported memory medias */ + for (mem_index = 0U; mem_index < MAX_USED_MEMORY_MEDIA; mem_index++) { + /* check if the memory media exists */ + if (NULL != mem_tab[mem_index]->mem_init) { + mem_tab[mem_index]->mem_init(); + } + } + + return MEM_OK; +} + +/*! + \brief deinitialize the memory media on the GD32 + \param[in] none + \param[out] none + \retval MEM_OK +*/ +uint8_t dfu_mem_deinit (void) +{ + uint32_t mem_index = 0U; + + /* deinitialize all supported memory medias */ + for (mem_index = 0U; mem_index < MAX_USED_MEMORY_MEDIA; mem_index++) { + /* check if the memory media exists */ + if (NULL != mem_tab[mem_index]->mem_deinit) { + mem_tab[mem_index]->mem_deinit(); + } + } + + return MEM_OK; +} + +/*! + \brief erase a memory sector + \param[in] addr: memory sector address/code + \param[out] none + \retval MEM_OK +*/ +uint8_t dfu_mem_erase (uint32_t addr) +{ + uint32_t mem_index = dfu_mem_checkaddr(addr); + + /* check if the address is in protected area */ + if (IS_PROTECTED_AREA(addr)) { + return MEM_FAIL; + } + + if (mem_index < MAX_USED_MEMORY_MEDIA) { + /* check if the operation is supported */ + if (NULL != mem_tab[mem_index]->mem_erase) { + return mem_tab[mem_index]->mem_erase(addr); + } else { + return MEM_FAIL; + } + } else { + return MEM_FAIL; + } +} + +/*! + \brief write data to sectors of memory + \param[in] buf: the data buffer to be write + \param[in] addr: memory sector address/code + \param[in] len: data length + \param[out] none + \retval MEM_OK +*/ +uint8_t dfu_mem_write (uint8_t *buf, uint32_t addr, uint32_t len) +{ + uint32_t mem_index = dfu_mem_checkaddr(addr); + + /* check if the address is in protected area */ + if (IS_PROTECTED_AREA(addr)) { + return MEM_FAIL; + } + + if ((addr & MAL_MASK_OB) == OB_RDPT0) { + option_byte_write(addr, buf); + NVIC_SystemReset(); + + return MEM_OK; + } + + if (mem_index < MAX_USED_MEMORY_MEDIA) { + /* check if the operation is supported */ + if (NULL != mem_tab[mem_index]->mem_write) { + return mem_tab[mem_index]->mem_write(buf, addr, len); + } else { + return MEM_FAIL; + } + } else { + return MEM_FAIL; + } +} + +/*! + \brief read data from sectors of memory + \param[in] buf: the data buffer to be write + \param[in] addr: memory sector address/code + \param[in] len: data length + \param[out] none + \retval pointer to buffer +*/ +uint8_t* dfu_mem_read (uint8_t *buf, uint32_t addr, uint32_t len) +{ + uint32_t mem_index = 0U; + + if ((OB_RDPT0 != addr) && (OB_RDPT1 != addr)) { + mem_index = dfu_mem_checkaddr(addr); + } + + if (mem_index < MAX_USED_MEMORY_MEDIA) { + /* check if the operation is supported */ + if (NULL != mem_tab[mem_index]->mem_read) { + return mem_tab[mem_index]->mem_read(buf, addr, len); + } else { + return buf; + } + } else { + return buf; + } +} + +/*! + \brief get the status of a given memory and store in buffer + \param[in] addr: memory sector address/code + \param[in] cmd: 0 for erase and 1 for write + \param[in] buffer: pointer to the buffer where the status data will be stored + \param[out] none + \retval MEM_OK if all operations are OK, MEM_FAIL else +*/ +uint8_t dfu_mem_getstatus (uint32_t addr, uint8_t cmd, uint8_t *buffer) +{ + uint32_t mem_index = dfu_mem_checkaddr(addr); + + if (mem_index < MAX_USED_MEMORY_MEDIA) { + if (cmd & 0x01U) { + POLLING_TIMEOUT_SET(mem_tab[mem_index]->write_timeout); + } else { + POLLING_TIMEOUT_SET(mem_tab[mem_index]->erase_timeout); + } + + return MEM_OK; + } else { + return MEM_FAIL; + } +} + +/*! + \brief check the address is supported + \param[in] addr: memory sector address/code + \param[out] none + \retval index of the addressed memory +*/ +static uint8_t dfu_mem_checkaddr (uint32_t addr) +{ + uint8_t mem_index = 0U; + + /* check with all supported memories */ + for (mem_index = 0U; mem_index < MAX_USED_MEMORY_MEDIA; mem_index++) { + /* if the check address is supported, return the memory index */ + if (MEM_OK == mem_tab[mem_index]->mem_checkaddr(addr)) { + return mem_index; + } + } + + /* if there is no memory found, return MAX_USED_MEMORY_MEDIA */ + return (MAX_USED_MEMORY_MEDIA); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Include/custom_hid_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Include/custom_hid_core.h new file mode 100644 index 0000000..2d8fe84 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Include/custom_hid_core.h @@ -0,0 +1,69 @@ +/*! + \file custom_hid_core.h + \brief definitions for HID core + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __CUSTOM_HID_CORE_H +#define __CUSTOM_HID_CORE_H + +#include "usbd_enum.h" +#include "usb_hid.h" + +#define DESC_LEN_REPORT 96U +#define DESC_LEN_CONFIG 41U + +#define NO_CMD 0xFFU + +#define MAX_PERIPH_NUM 4U + +typedef struct { + uint8_t data[2]; + + uint8_t reportID; + uint8_t idlestate; + uint8_t protocol; +} custom_hid_handler; + +typedef struct { + void (*periph_config[MAX_PERIPH_NUM])(void); +} hid_fop_handler; + +extern usb_desc custom_hid_desc; +extern usb_class_core usbd_custom_hid_cb; + +/* function declarations */ +/* register HID interface operation functions */ +uint8_t custom_hid_itfop_register (usb_dev *udev, hid_fop_handler *hid_fop); +/* send custom HID report */ +uint8_t custom_hid_report_send (usb_dev *udev, uint8_t *report, uint32_t len); + +#endif /* __CUSTOM_HID_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Include/standard_hid_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Include/standard_hid_core.h new file mode 100644 index 0000000..6398185 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Include/standard_hid_core.h @@ -0,0 +1,68 @@ +/*! + \file standard_hid_core.h + \brief definitions for HID core + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __STANDARD_HID_CORE_H +#define __STANDARD_HID_CORE_H + +#include "usbd_enum.h" +#include "usb_hid.h" + +#define USB_HID_CONFIG_DESC_LEN 0x22U +#define USB_HID_REPORT_DESC_LEN 0x2EU + +#define NO_CMD 0xFFU + +typedef struct { + uint32_t protocol; + uint32_t idle_state; + + uint8_t data[HID_IN_PACKET]; + __IO uint8_t prev_transfer_complete; +} standard_hid_handler; + +typedef struct { + void (*hid_itf_config) (void); + void (*hid_itf_data_process) (usb_dev *udev); +} hid_fop_handler; + +extern usb_desc hid_desc; +extern usb_class_core usbd_hid_cb; + +/* function declarations */ +/* register HID interface operation functions */ +uint8_t hid_itfop_register (usb_dev *udev, hid_fop_handler *hid_fop); +/* send keyboard report */ +uint8_t hid_report_send (usb_dev *udev, uint8_t *report, uint32_t len); + +#endif /* __STANDARD_HID_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Source/custom_hid_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Source/custom_hid_core.c new file mode 100644 index 0000000..251abc9 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Source/custom_hid_core.c @@ -0,0 +1,483 @@ +/*! + \file custom_hid_core.c + \brief custom HID class driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "custom_hid_core.h" +#include "usbd_enum.h" +#include + +#define USBD_VID 0x28E9U +#define USBD_PID 0x028AU + +/* Note:it should use the C99 standard when compiling the below codes */ +/* USB standard device descriptor */ +__ALIGN_BEGIN const usb_desc_dev custom_hid_dev_desc __ALIGN_END = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV, + }, + .bcdUSB = 0x0200U, + .bDeviceClass = 0x00U, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM, +}; + +/* USB device configuration descriptor */ +__ALIGN_BEGIN const usb_hid_desc_config_set custom_hid_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG + }, + .wTotalLength = DESC_LEN_CONFIG, + .bNumInterfaces = 0x01U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0x80U, + .bMaxPower = 0x32U + }, + + .hid_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x02U, + .bInterfaceClass = USB_HID_CLASS, + .bInterfaceSubClass = 0x00U, + .bInterfaceProtocol = 0x00U, + .iInterface = 0x00U + }, + + .hid_vendor = + { + .header = + { + .bLength = sizeof(usb_desc_hid), + .bDescriptorType = USB_DESCTYPE_HID + }, + .bcdHID = 0x0111U, + .bCountryCode = 0x00U, + .bNumDescriptors = 0x01U, + .bDescriptorType = USB_DESCTYPE_REPORT, + .wDescriptorLength = DESC_LEN_REPORT, + }, + + .hid_epin = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = CUSTOMHID_IN_EP, + .bmAttributes = USB_EP_ATTR_INT, + .wMaxPacketSize = CUSTOMHID_IN_PACKET, + .bInterval = 0x20U + }, + + .hid_epout = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = CUSTOMHID_OUT_EP, + .bmAttributes = USB_EP_ATTR_INT, + .wMaxPacketSize = CUSTOMHID_OUT_PACKET, + .bInterval = 0x20U + } +}; + +/* USB language ID descriptor */ +static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR + }, + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(10U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(14U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'C', 'u', 's', 't', 'o', 'm', 'H', 'I', 'D'} +}; + +/* USBD serial string */ +static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12U), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +/* USB string descriptor set */ +void *const usbd_hid_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *)&usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *)&manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *)&product_string, + [STR_IDX_SERIAL] = (uint8_t *)&serial_string +}; + +usb_desc custom_hid_desc = { + .dev_desc = (uint8_t *)&custom_hid_dev_desc, + .config_desc = (uint8_t *)&custom_hid_config_desc, + .strings = usbd_hid_strings +}; + +__ALIGN_BEGIN const uint8_t customhid_report_descriptor[DESC_LEN_REPORT] __ALIGN_END = +{ + 0x06, 0x00, 0xFF, /* USAGE_PAGE (Vendor Defined: 0xFF00) */ + 0x09, 0x00, /* USAGE (Custom Device) */ + 0xa1, 0x01, /* COLLECTION (Application) */ + + /* led 1 */ + 0x85, 0x11, /* REPORT_ID (0x11) */ + 0x09, 0x01, /* USAGE (LED 1) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x95, 0x01, /* REPORT_COUNT (1) */ + 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */ + + /* led 2 */ + 0x85, 0x12, /* REPORT_ID (0x12) */ + 0x09, 0x02, /* USAGE (LED 2) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x95, 0x01, /* REPORT_COUNT (1) */ + 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */ + + /* led 3 */ + 0x85, 0x13, /* REPORT_ID (0x13) */ + 0x09, 0x03, /* USAGE (LED 3) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x95, 0x01, /* REPORT_COUNT (1) */ + 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */ + + /* led 4 */ + 0x85, 0x14, /* REPORT_ID (0x14) */ + 0x09, 0x04, /* USAGE (LED 4) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x95, 0x01, /* REPORT_COUNT (1) */ + 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */ + + /* wakeup key */ + 0x85, 0x15, /* REPORT_ID (0x15) */ + 0x09, 0x05, /* USAGE (Push Button) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */ + 0x75, 0x01, /* REPORT_SIZE (1) */ + 0x81, 0x02, /* INPUT (Data,Var,Abs,Vol) */ + + 0x75, 0x07, /* REPORT_SIZE (7) */ + 0x81, 0x03, /* INPUT (Cnst,Var,Abs,Vol) */ + + /* tamper key */ + 0x85, 0x16, /* REPORT_ID (0x16) */ + 0x09, 0x06, /* USAGE (Push Button) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */ + 0x75, 0x01, /* REPORT_SIZE (1) */ + 0x81, 0x02, /* INPUT (Data,Var,Abs,Vol) */ + + 0x75, 0x07, /* REPORT_SIZE (7) */ + 0x81, 0x03, /* INPUT (Cnst,Var,Abs,Vol) */ + + 0xc0 /* END_COLLECTION */ +}; + +/* local function prototypes ('static') */ +static uint8_t custom_hid_init (usb_dev *udev, uint8_t config_index); +static uint8_t custom_hid_deinit (usb_dev *udev, uint8_t config_index); +static uint8_t custom_hid_req_handler (usb_dev *udev, usb_req *req); + +static uint8_t custom_hid_data_in (usb_dev *udev, uint8_t ep_num); +static uint8_t custom_hid_data_out (usb_dev *udev, uint8_t ep_num); + +usb_class_core usbd_custom_hid_cb = +{ + .command = NO_CMD, + .alter_set = 0U, + + .init = custom_hid_init, + .deinit = custom_hid_deinit, + + .req_proc = custom_hid_req_handler, + + .data_in = custom_hid_data_in, + .data_out = custom_hid_data_out +}; + +/*! + \brief register HID interface operation functions + \param[in] udev: pointer to USB device instance + \param[in] hid_fop: HID operation functions structure + \param[out] none + \retval USB device operation status +*/ +uint8_t custom_hid_itfop_register (usb_dev *udev, hid_fop_handler *hid_fop) +{ + if (NULL != hid_fop) { + udev->dev.user_data = hid_fop; + + return USBD_OK; + } + + return USBD_FAIL; +} + +/*! + \brief send custom HID report + \param[in] udev: pointer to USB device instance + \param[in] report: pointer to HID report + \param[in] len: data length + \param[out] none + \retval USB device operation status +*/ +uint8_t custom_hid_report_send (usb_dev *udev, uint8_t *report, uint32_t len) +{ + usbd_ep_send (udev, CUSTOMHID_IN_EP, report, len); + + return USBD_OK; +} + +/*! + \brief initialize the HID device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t custom_hid_init (usb_dev *udev, uint8_t config_index) +{ + static __ALIGN_BEGIN custom_hid_handler hid_handler __ALIGN_END; + + memset((void *)&hid_handler, 0U, sizeof(custom_hid_handler)); + + /* initialize the data Tx endpoint */ + usbd_ep_setup (udev, &(custom_hid_config_desc.hid_epin)); + + /* initialize the data Rx endpoint */ + usbd_ep_setup (udev, &(custom_hid_config_desc.hid_epout)); + + /* prepare receive data */ + usbd_ep_recev (udev, CUSTOMHID_OUT_EP, hid_handler.data, 2U); + + udev->dev.class_data[CUSTOM_HID_INTERFACE] = (void *)&hid_handler; + + if (udev->dev.user_data != NULL) { + for (uint8_t i = 0U; i < MAX_PERIPH_NUM; i++) { + if (((hid_fop_handler *)udev->dev.user_data)->periph_config[i] != NULL) { + ((hid_fop_handler *)udev->dev.user_data)->periph_config[i](); + } + } + } + + return USBD_OK; +} + +/*! + \brief deinitialize the HID device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t custom_hid_deinit (usb_dev *udev, uint8_t config_index) +{ + /* deinitialize HID endpoints */ + usbd_ep_clear(udev, CUSTOMHID_IN_EP); + usbd_ep_clear(udev, CUSTOMHID_OUT_EP); + + return USBD_OK; +} + +/*! + \brief handle the HID class-specific requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t custom_hid_req_handler (usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + + custom_hid_handler *hid = (custom_hid_handler *)udev->dev.class_data[CUSTOM_HID_INTERFACE]; + + switch (req->bRequest) { + case GET_REPORT: + break; + + case GET_IDLE: + transc->xfer_buf = (uint8_t *)&hid->idlestate; + transc->remain_len = 1U; + break; + + case GET_PROTOCOL: + transc->xfer_buf = (uint8_t *)&hid->protocol; + transc->remain_len = 1U; + break; + + case SET_REPORT: + hid->reportID = (uint8_t)(req->wValue); + break; + + case SET_IDLE: + hid->idlestate = (uint8_t)(req->wValue >> 8U); + break; + + case SET_PROTOCOL: + hid->protocol = (uint8_t)(req->wValue); + break; + + case USB_GET_DESCRIPTOR: + if (USB_DESCTYPE_REPORT == (req->wValue >> 8U)) { + transc->remain_len = USB_MIN(DESC_LEN_REPORT, req->wLength); + transc->xfer_buf = (uint8_t *)customhid_report_descriptor; + } + break; + + default: + return USBD_FAIL; + } + + return USBD_OK; +} + +/*! + \brief handle custom HID data + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier + \param[out] none + \retval USB device operation status +*/ +static uint8_t custom_hid_data_in (usb_dev *udev, uint8_t ep_num) +{ + return USBD_OK; +} + +/*! + \brief handle custom HID data + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier + \param[out] none + \retval USB device operation status +*/ +static uint8_t custom_hid_data_out (usb_dev *udev, uint8_t ep_num) +{ + custom_hid_handler *hid = (custom_hid_handler *)udev->dev.class_data[CUSTOM_HID_INTERFACE]; + + /* light the LED */ + switch (hid->data[0]){ + case 0x11U: + if (RESET != hid->data[1]) { + gd_eval_led_on(LED1); + } else { + gd_eval_led_off(LED1); + } + break; + + case 0x12U: + if (RESET != hid->data[1]) { + gd_eval_led_on(LED2); + } else { + gd_eval_led_off(LED2); + } + break; + + case 0x13U: + if (RESET != hid->data[1]) { + gd_eval_led_on(LED3); + } else { + gd_eval_led_off(LED3); + } + break; + + case 0x14U: + break; + + default: + break; + } + + usbd_ep_recev (udev, CUSTOMHID_OUT_EP, hid->data, 2U); + + return USBD_OK; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Source/standard_hid_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Source/standard_hid_core.c new file mode 100644 index 0000000..a1e5fdb --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/hid/Source/standard_hid_core.c @@ -0,0 +1,468 @@ +/*! + \file standard_hid_core.c + \brief HID class driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "standard_hid_core.h" +#include + +#define USBD_VID 0x28e9U +#define USBD_PID 0x0380U + +/* Note:it should use the C99 standard when compiling the below codes */ +/* USB standard device descriptor */ +__ALIGN_BEGIN const usb_desc_dev hid_dev_desc __ALIGN_END = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV + }, + .bcdUSB = 0x0200U, + .bDeviceClass = 0x00U, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM +}; + +__ALIGN_BEGIN const usb_hid_desc_config_set hid_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG + }, + .wTotalLength = USB_HID_CONFIG_DESC_LEN, + .bNumInterfaces = 0x01U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0xA0U, + .bMaxPower = 0x32U + }, + + .hid_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x01U, + .bInterfaceClass = USB_HID_CLASS, + .bInterfaceSubClass = USB_HID_SUBCLASS_BOOT_ITF, + .bInterfaceProtocol = USB_HID_PROTOCOL_KEYBOARD, + .iInterface = 0x00U + }, + + .hid_vendor = + { + .header = + { + .bLength = sizeof(usb_desc_hid), + .bDescriptorType = USB_DESCTYPE_HID + }, + .bcdHID = 0x0111U, + .bCountryCode = 0x00U, + .bNumDescriptors = 0x01U, + .bDescriptorType = USB_DESCTYPE_REPORT, + .wDescriptorLength = USB_HID_REPORT_DESC_LEN, + }, + + .hid_epin = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = HID_IN_EP, + .bmAttributes = USB_EP_ATTR_INT, + .wMaxPacketSize = HID_IN_PACKET, + .bInterval = 0x10U + } +}; + +__ALIGN_BEGIN const usb_hid_desc_config_set other_speed_hid_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_OTHER_SPD_CONFIG + }, + .wTotalLength = USB_HID_CONFIG_DESC_LEN, + .bNumInterfaces = 0x01U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0xA0U, + .bMaxPower = 0x32U + }, + + .hid_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x01U, + .bInterfaceClass = USB_HID_CLASS, + .bInterfaceSubClass = USB_HID_SUBCLASS_BOOT_ITF, + .bInterfaceProtocol = USB_HID_PROTOCOL_KEYBOARD, + .iInterface = 0x00U + }, + + .hid_vendor = + { + .header = + { + .bLength = sizeof(usb_desc_hid), + .bDescriptorType = USB_DESCTYPE_HID + }, + .bcdHID = 0x0111U, + .bCountryCode = 0x00U, + .bNumDescriptors = 0x01U, + .bDescriptorType = USB_DESCTYPE_REPORT, + .wDescriptorLength = USB_HID_REPORT_DESC_LEN, + }, + + .hid_epin = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = HID_IN_EP, + .bmAttributes = USB_EP_ATTR_INT, + .wMaxPacketSize = HID_IN_PACKET, + .bInterval = 0x40U + } +}; + +__ALIGN_BEGIN const uint8_t usbd_qualifier_desc[10] __ALIGN_END = +{ + 0x0A, + 0x06, + 0x00, + 0x02, + 0x00, + 0x00, + 0x00, + 0x40, + 0x01, + 0x00 +}; + +/* USB language ID Descriptor */ +static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR + }, + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(10U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(17U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'K', 'e', 'y', 'b', 'o', 'a', 'r', 'd'} +}; + +/* USBD serial string */ +static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12U), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +void *const usbd_hid_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *)&usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *)&manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *)&product_string, + [STR_IDX_SERIAL] = (uint8_t *)&serial_string +}; + +usb_desc hid_desc = { + .dev_desc = (uint8_t *)&hid_dev_desc, + .config_desc = (uint8_t *)&hid_config_desc, +#if defined(USE_USB_HS) && defined(USE_ULPI_PHY) + .other_speed_config_desc = (uint8_t *)&other_speed_hid_config_desc, + .qualifier_desc = (uint8_t *)&usbd_qualifier_desc, +#endif + .strings = usbd_hid_strings +}; + +__ALIGN_BEGIN const uint8_t hid_report_desc[USB_HID_REPORT_DESC_LEN] __ALIGN_END = +{ + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop) */ + 0x09, 0x06, /* USAGE (Keyboard) */ + 0xa1, 0x01, /* COLLECTION (Application) */ + + 0x05, 0x07, /* USAGE_PAGE (Keyboard/Keypad) */ + 0x19, 0xe0, /* USAGE_MINIMUM (Keyboard LeftControl) */ + 0x29, 0xe7, /* USAGE_MAXIMUM (Keyboard Right GUI) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1) */ + 0x95, 0x08, /* REPORT_COUNT (8) */ + 0x75, 0x01, /* REPORT_SIZE (1) */ + 0x81, 0x02, /* INPUT (Data,Var,Abs) */ + + 0x95, 0x01, /* REPORT_COUNT (1) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x81, 0x03, /* INPUT (Cnst,Var,Abs) */ + + 0x95, 0x06, /* REPORT_COUNT (6) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x26, 0xFF, 0x00, /* LOGICAL_MAXIMUM (255) */ + 0x05, 0x07, /* USAGE_PAGE (Keyboard/Keypad) */ + 0x19, 0x00, /* USAGE_MINIMUM (Reserved (no event indicated)) */ + 0x29, 0x65, /* USAGE_MAXIMUM (Keyboard Application) */ + 0x81, 0x00, /* INPUT (Data,Ary,Abs) */ + + 0xc0 /* END_COLLECTION */ +}; + +/* local function prototypes ('static') */ +static uint8_t hid_init (usb_dev *udev, uint8_t config_index); +static uint8_t hid_deinit (usb_dev *udev, uint8_t config_index); +static uint8_t hid_req (usb_dev *udev, usb_req *req); +static uint8_t hid_data_in (usb_dev *udev, uint8_t ep_num); + +usb_class_core usbd_hid_cb = { + .command = NO_CMD, + .alter_set = 0U, + + .init = hid_init, + .deinit = hid_deinit, + .req_proc = hid_req, + .data_in = hid_data_in +}; + +/*! + \brief register HID interface operation functions + \param[in] udev: pointer to USB device instance + \param[in] hid_fop: HID operation function structure + \param[out] none + \retval USB device operation status +*/ +uint8_t hid_itfop_register (usb_dev *udev, hid_fop_handler *hid_fop) +{ + if (NULL != hid_fop) { + udev->dev.user_data = (void *)hid_fop; + + return USBD_OK; + } + + return USBD_FAIL; +} + +/*! + \brief send keyboard report + \param[in] udev: pointer to USB device instance + \param[in] report: pointer to HID report + \param[in] len: data length + \param[out] none + \retval USB device operation status +*/ +uint8_t hid_report_send (usb_dev *udev, uint8_t *report, uint32_t len) +{ + standard_hid_handler *hid = (standard_hid_handler *)udev->dev.class_data[USBD_HID_INTERFACE]; + + hid->prev_transfer_complete = 0U; + + usbd_ep_send(udev, HID_IN_EP, report, len); + + return USBD_OK; +} + +/*! + \brief initialize the HID device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t hid_init (usb_dev *udev, uint8_t config_index) +{ + static __ALIGN_BEGIN standard_hid_handler hid_handler __ALIGN_END; + + memset((void *)&hid_handler, 0U, sizeof(standard_hid_handler)); + + /* initialize the data TX endpoint */ + usbd_ep_setup (udev, &(hid_config_desc.hid_epin)); + + hid_handler.prev_transfer_complete = 1U; + + udev->dev.class_data[USBD_HID_INTERFACE] = (void *)&hid_handler; + + if (NULL != udev->dev.user_data) { + ((hid_fop_handler *)udev->dev.user_data)->hid_itf_config(); + } + + return USBD_OK; +} + +/*! + \brief deinitialize the HID device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t hid_deinit (usb_dev *udev, uint8_t config_index) +{ + /* deinitialize HID endpoints */ + usbd_ep_clear(udev, HID_IN_EP); + + return USBD_OK; +} + +/*! + \brief handle the HID class-specific requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t hid_req (usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + + standard_hid_handler *hid = (standard_hid_handler *)udev->dev.class_data[USBD_HID_INTERFACE]; + + switch (req->bRequest) { + case GET_REPORT: + /* no use for this driver */ + break; + + case GET_IDLE: + transc->xfer_buf = (uint8_t *)&hid->idle_state; + + transc->remain_len = 1U; + break; + + case GET_PROTOCOL: + transc->xfer_buf = (uint8_t *)&hid->protocol; + + transc->remain_len = 1U; + break; + + case SET_REPORT: + /* no use for this driver */ + break; + + case SET_IDLE: + hid->idle_state = (uint8_t)(req->wValue >> 8U); + break; + + case SET_PROTOCOL: + hid->protocol = (uint8_t)(req->wValue); + break; + + case USB_GET_DESCRIPTOR: + if (USB_DESCTYPE_REPORT == (req->wValue >> 8U)) { + transc->remain_len = USB_MIN(USB_HID_REPORT_DESC_LEN, req->wLength); + transc->xfer_buf = (uint8_t *)hid_report_desc; + + return REQ_SUPP; + } else if (USB_DESCTYPE_HID == (req->wValue >> 8U)) { + transc->remain_len = USB_MIN(9U, req->wLength); + transc->xfer_buf = (uint8_t *)(&(hid_config_desc.hid_vendor)); + } + break; + + default: + break; + } + + return USBD_OK; +} + +/*! + \brief handle data stage + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier + \param[out] none + \retval USB device operation status +*/ +static uint8_t hid_data_in (usb_dev *udev, uint8_t ep_num) +{ + standard_hid_handler *hid = (standard_hid_handler *)udev->dev.class_data[USBD_HID_INTERFACE]; + + if (0U != hid->data[2]) { + hid->data[2] = 0x00U; + + usbd_ep_send(udev, HID_IN_EP, hid->data, HID_IN_PACKET); + } else { + hid->prev_transfer_complete = 1U; + } + + return USBD_OK; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/iap/Include/usb_iap_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/iap/Include/usb_iap_core.h new file mode 100644 index 0000000..823d8f1 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/iap/Include/usb_iap_core.h @@ -0,0 +1,97 @@ +/*! + \file usb_iap_core.h + \brief the header file of IAP driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USB_IAP_CORE_H +#define __USB_IAP_CORE_H + +#include "usbd_enum.h" +#include "usb_hid.h" + +#define USB_SERIAL_STRING_SIZE 0x06U + +#ifdef USE_USB_FS + #define USB_DESC_LEN_IAP_REPORT 35U +#elif defined(USE_USB_HS) + #ifdef USE_ULPI_PHY + #define USB_DESC_LEN_IAP_REPORT 36U + #else + #define USB_DESC_LEN_IAP_REPORT 35U + #endif +#else + #error "please select 'USE_USB_FS' or 'USE_USB_HS'" +#endif + +#define USB_DESC_LEN_IAP_CONFIG_SET 41U + +/* special commands with download request */ +#define IAP_OPTION_BYTE1 0x01U +#define IAP_ERASE 0x02U +#define IAP_DNLOAD 0x03U +#define IAP_LEAVE 0x04U +#define IAP_GETBIN_ADDRESS 0x05U +#define IAP_OPTION_BYTE2 0x06U + +typedef struct +{ + uint8_t option_byte[IAP_IN_PACKET]; + + /* state machine variables */ + uint8_t dev_status[IAP_IN_PACKET]; + uint8_t bin_addr[IAP_IN_PACKET]; + + uint8_t report_buf[IAP_OUT_PACKET + 1U]; + + uint8_t reportID; + uint8_t flag; + + uint32_t protocol; + uint32_t idlestate; + + uint16_t transfer_times; + uint16_t page_count; + uint16_t lps; /* last packet size */ + uint32_t file_length; + uint32_t base_address; +} usbd_iap_handler; + +typedef void (*app_func) (void); + +extern usb_desc iap_desc; +extern usb_class_core iap_class; + +/* function declarations */ +/* send IAP report */ +uint8_t iap_report_send (usb_dev *udev, uint8_t *report, uint32_t len); + +#endif /* __USB_IAP_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/iap/Source/usb_iap_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/iap/Source/usb_iap_core.c new file mode 100644 index 0000000..0688b70 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/iap/Source/usb_iap_core.c @@ -0,0 +1,569 @@ +/*! + \file usb_iap_core.c + \brief IAP driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usb_iap_core.h" +#include "flash_operation.h" +#include + +#define USBD_VID 0x28E9U +#define USBD_PID 0x0228U + +/* Note:it should use the C99 standard when compiling the below codes */ +/* USB standard device descriptor */ +__ALIGN_BEGIN const usb_desc_dev iap_dev_desc __ALIGN_END = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV + }, + .bcdUSB = 0x0200U, + .bDeviceClass = 0x00U, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM +}; + +__ALIGN_BEGIN const usb_hid_desc_config_set iap_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG + }, + .wTotalLength = USB_DESC_LEN_IAP_CONFIG_SET, + .bNumInterfaces = 0x01U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0x80U, + .bMaxPower = 0x32U + }, + + .hid_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x02U, + .bInterfaceClass = USB_HID_CLASS, + .bInterfaceSubClass = 0x00U, + .bInterfaceProtocol = 0x00U, + .iInterface = 0x00U + }, + + .hid_vendor = + { + .header = + { + .bLength = sizeof(usb_desc_hid), + .bDescriptorType = USB_DESCTYPE_HID + }, + .bcdHID = 0x0111U, + .bCountryCode = 0x00U, + .bNumDescriptors = 0x01U, + .bDescriptorType = USB_DESCTYPE_REPORT, + .wDescriptorLength = USB_DESC_LEN_IAP_REPORT, + }, + + .hid_epin = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = IAP_IN_EP, + .bmAttributes = USB_EP_ATTR_INT, + .wMaxPacketSize = IAP_IN_PACKET, + .bInterval = 0x01U + }, + + .hid_epout = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = IAP_OUT_EP, + .bmAttributes = USB_EP_ATTR_INT, + .wMaxPacketSize = IAP_OUT_PACKET, + .bInterval = 0x01U + } +}; + +/* USB language ID Descriptor */ +static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR + }, + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(10U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'I', 'A', 'P'} +}; + +/* USBD serial string */ +static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(2U), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +void *const usbd_iap_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *)&usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *)&manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *)&product_string, + [STR_IDX_SERIAL] = (uint8_t *)&serial_string +}; + +usb_desc iap_desc = { + .dev_desc = (uint8_t *)&iap_dev_desc, + .config_desc = (uint8_t *)&iap_config_desc, + .strings = usbd_iap_strings +}; + +/* local function prototypes ('static') */ +static uint8_t iap_init (usb_dev *udev, uint8_t config_index); +static uint8_t iap_deinit (usb_dev *udev, uint8_t config_index); +static uint8_t iap_req_handler (usb_dev *udev, usb_req *req); +static uint8_t iap_data_out (usb_dev *udev, uint8_t ep_num); + +/* IAP requests management functions */ +static void iap_req_erase (usb_dev *udev); +static void iap_req_dnload (usb_dev *udev); +static void iap_req_optionbyte (usb_dev *udev, uint8_t option_num); +static void iap_req_leave (usb_dev *udev); +static void iap_address_send (usb_dev *udev); + +usb_class_core iap_class = { + .init = iap_init, + .deinit = iap_deinit, + .req_proc = iap_req_handler, + .data_out = iap_data_out +}; + +/* USB custom HID device report descriptor */ +__ALIGN_BEGIN const uint8_t iap_report_desc[USB_DESC_LEN_IAP_REPORT] __ALIGN_END = +{ + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop) */ + 0x09, 0x00, /* USAGE (Custom Device) */ + 0xa1, 0x01, /* COLLECTION (Application) */ + + /* IAP command and data */ + 0x85, 0x01, /* REPORT_ID (0x01) */ + 0x09, 0x01, /* USAGE (IAP command) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0xff, /* LOGICAL_MAXIMUM (255) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ +#ifdef USE_USB_FS + 0x95, REPORT_OUT_COUNT, +#else + #ifdef USE_ULPI_PHY + 0x96, BYTE_LOW(REPORT_OUT_COUNT), BYTE_HIGH(REPORT_OUT_COUNT), + #elif defined(USE_EMBEDDED_PHY) + 0x95, REPORT_OUT_COUNT, + #endif +#endif + 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */ + + /* device status and option byte */ + 0x85, 0x02, /* REPORT_ID (0x02) */ + 0x09, 0x02, /* USAGE (Status and option byte) */ + 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ + 0x25, 0xff, /* LOGICAL_MAXIMUM (255) */ + 0x75, 0x08, /* REPORT_SIZE (8) */ + 0x95, REPORT_IN_COUNT, /* REPORT_COUNT (23) */ + 0x81, 0x82, /* INPUT (Data,Var,Abs,Vol) */ + + 0xc0 /* END_COLLECTION */ +}; + +/*! + \brief send IAP report + \param[in] udev: pointer to USB device instance + \param[in] report: pointer to HID report + \param[in] len: data length + \param[out] none + \retval USB device operation status +*/ +uint8_t iap_report_send (usb_dev *udev, uint8_t *report, uint32_t len) +{ + usbd_ep_send (udev, IAP_IN_EP, report, len); + + return USBD_OK; +} + +/*! + \brief initialize the IAP device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t iap_init (usb_dev *udev, uint8_t config_index) +{ + static __ALIGN_BEGIN usbd_iap_handler iap_handler __ALIGN_END; + + /* initialize Tx endpoint */ + usbd_ep_setup(udev, &(iap_config_desc.hid_epin)); + + /* initialize Rx endpoint */ + usbd_ep_setup(udev, &(iap_config_desc.hid_epout)); + + /* unlock the internal flash */ + fmc_unlock(); + + memset((void *)&iap_handler, 0U, sizeof(usbd_iap_handler)); + + /* prepare receive data */ + usbd_ep_recev(udev, IAP_OUT_EP, iap_handler.report_buf, IAP_OUT_PACKET); + + iap_handler.base_address = APP_LOADED_ADDR; + + udev->dev.class_data[USBD_IAP_INTERFACE] = (void *)&iap_handler; + + return USBD_OK; +} + +/*! + \brief deinitialize the IAP device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t iap_deinit (usb_dev *udev, uint8_t config_index) +{ + /* deinitialize IAP endpoints */ + usbd_ep_clear (udev, IAP_IN_EP); + usbd_ep_clear (udev, IAP_OUT_EP); + + /* lock the internal flash */ + fmc_lock(); + + return USBD_OK; +} + +/*! + \brief handle the IAP class-specific requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t iap_req_handler (usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + + usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE]; + + switch (req->bRequest) { + case GET_REPORT: + /* no use for this driver */ + break; + + case GET_IDLE: + transc->xfer_buf = (uint8_t *)&iap->idlestate; + transc->remain_len = 1U; + break; + + case GET_PROTOCOL: + transc->xfer_buf = (uint8_t *)&iap->protocol; + transc->remain_len = 1U; + break; + + case SET_REPORT: + iap->reportID = (uint8_t)(req->wValue); + break; + + case SET_IDLE: + iap->idlestate = (uint8_t)(req->wValue >> 8U); + break; + + case SET_PROTOCOL: + iap->protocol = (uint8_t)(req->wValue); + break; + + case USB_GET_DESCRIPTOR: + if (USB_DESCTYPE_REPORT == (req->wValue >> 8U)) { + transc->remain_len = USB_MIN(USB_DESC_LEN_IAP_REPORT, req->wLength); + transc->xfer_buf = (uint8_t *)iap_report_desc; + } + break; + + default: + return USBD_FAIL; + } + + return USBD_OK; +} + +/*! + \brief handle data out stage + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier + \param[out] none + \retval none +*/ +static uint8_t iap_data_out (usb_dev *udev ,uint8_t ep_num) +{ + usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE]; + + if (0x01U == iap->report_buf[0]) { + switch (iap->report_buf[1]) { + case IAP_DNLOAD: + iap_req_dnload(udev); + break; + + case IAP_ERASE: + iap_req_erase(udev); + break; + + case IAP_OPTION_BYTE1: + iap_req_optionbyte(udev, 0x01U); + break; + + case IAP_LEAVE: + iap_req_leave(udev); + break; + + case IAP_GETBIN_ADDRESS: + iap_address_send(udev); + break; + + case IAP_OPTION_BYTE2: + iap_req_optionbyte(udev, 0x02U); + break; + + default: + break; + } + } + + usbd_ep_recev(udev, IAP_OUT_EP, iap->report_buf, IAP_OUT_PACKET); + + return USBD_OK; +} + +/*! + \brief handle the IAP_DNLOAD request + \param[in] udev: pointer to usb device instance + \param[out] none + \retval none +*/ +static void iap_req_dnload(usb_dev *udev) +{ + usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE]; + + if (0U != iap->transfer_times) { + if (1U == iap->transfer_times) { + if (0U == iap->lps) { + iap_data_write(&iap->report_buf[2], iap->base_address, TRANSFER_SIZE); + } else { + iap_data_write(&iap->report_buf[2], iap->base_address, iap->file_length % TRANSFER_SIZE); + iap->lps = 0U; + } + + iap->dev_status[0] = 0x02U; + iap->dev_status[1] = 0x02U; + iap_report_send (udev, iap->dev_status, IAP_IN_PACKET); + } else { + iap_data_write(&iap->report_buf[2], iap->base_address, TRANSFER_SIZE); + + iap->base_address += TRANSFER_SIZE; + } + + iap->transfer_times--; + } +} + +/*! + \brief handle the IAP_ERASE request + \param[in] udev: pointer to usb device instance + \param[out] none + \retval none +*/ +static void iap_req_erase(usb_dev *udev) +{ + uint32_t addr = 0U; + + usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE]; + + /* get base address to erase */ + iap->base_address = iap->report_buf[2]; + iap->base_address |= iap->report_buf[3] << 8U; + iap->base_address |= iap->report_buf[4] << 16U; + iap->base_address |= iap->report_buf[5] << 24U; + + /* get file length */ + iap->file_length = iap->report_buf[7]; + iap->file_length |= iap->report_buf[8] << 8U; + iap->file_length |= iap->report_buf[9] << 16U; + iap->file_length |= iap->report_buf[10] << 24U; + + iap->lps = iap->file_length % TRANSFER_SIZE; + if (0U == iap->lps) { + iap->transfer_times = iap->file_length / TRANSFER_SIZE; + } else { + iap->transfer_times = iap->file_length / TRANSFER_SIZE + 1U; + } + + /* check if the address is in protected area */ + if (IS_PROTECTED_AREA(iap->base_address)) { + return; + } + + addr = iap->base_address; + + /* unlock the flash program erase controller */ + fmc_unlock(); + + flash_erase(addr, iap->file_length, iap->report_buf); + + fmc_lock(); + + iap->dev_status[0] = 0x02U; + iap->dev_status[1] = 0x01U; + + usbd_ep_send(udev, IAP_IN_EP, iap->dev_status, IAP_IN_PACKET); +} + +/*! + \brief handle the IAP_OPTION_BYTE request + \param[in] udev: pointer to USB device instance + \param[in] option_num: number of option byte + \param[out] none + \retval none +*/ +static void iap_req_optionbyte(usb_dev *udev, uint8_t option_num) +{ + uint8_t i = 0U; + uint32_t address = 0U; + + usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE]; + + iap->option_byte[0] = 0x02U; + + if (0x01U == option_num) { + address = OPT_BYTE_ADDR1; +#ifdef OPT_BYTE_ADDR2 + } else if (0x02U == option_num) { + address = OPT_BYTE_ADDR2; +#endif + } else { + return; + } + + for (i = 1U; i < 17U; i++) { + iap->option_byte[i] = *(uint8_t *)address; + address++; + } + + iap_report_send (udev, iap->option_byte, IAP_IN_PACKET); +} + +/*! + \brief handle the IAP_LEAVE request + \param[in] udev: pointer to usb device instance + \param[out] none + \retval none +*/ +static void iap_req_leave(usb_dev *udev) +{ + /* lock the internal flash */ + fmc_lock(); + + /* generate system reset to allow jumping to the user code */ + NVIC_SystemReset(); +} + +/*! + \brief handle the IAP_SEND_ADDRESS request + \param[in] udev: pointer to usb device instance + \param[out] none + \retval none +*/ +static void iap_address_send(usb_dev *udev) +{ + usbd_iap_handler *iap = (usbd_iap_handler *)udev->dev.class_data[USBD_IAP_INTERFACE]; + + iap->bin_addr[0] = 0x02U; + + iap->bin_addr[1] = (uint8_t)(APP_LOADED_ADDR); + iap->bin_addr[2] = (uint8_t)(APP_LOADED_ADDR >> 8U); + iap->bin_addr[3] = (uint8_t)(APP_LOADED_ADDR >> 16U); + iap->bin_addr[4] = (uint8_t)(APP_LOADED_ADDR >> 24U); + + iap_report_send (udev, iap->bin_addr, IAP_IN_PACKET); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_bbb.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_bbb.h new file mode 100644 index 0000000..744be9f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_bbb.h @@ -0,0 +1,101 @@ +/*! + \file usbd_msc_bbb.h + \brief the header file of the usbd_msc_bbb.c file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBD_MSC_BBB_H +#define __USBD_MSC_BBB_H + +#include "usbd_core.h" +#include "msc_bbb.h" +#include "usbd_msc_mem.h" +#include "usbd_msc_scsi.h" + +/* MSC BBB state */ +enum msc_bbb_state { + BBB_IDLE = 0U, /*!< idle state */ + BBB_DATA_OUT, /*!< data OUT state */ + BBB_DATA_IN, /*!< data IN state */ + BBB_LAST_DATA_IN, /*!< last data IN state */ + BBB_SEND_DATA /*!< send immediate data state */ +}; + +/* MSC BBB status */ +enum msc_bbb_status { + BBB_STATUS_NORMAL = 0U, /*!< normal status */ + BBB_STATUS_RECOVERY, /*!< recovery status*/ + BBB_STATUS_ERROR /*!< error status */ +}; + +typedef struct +{ + uint8_t bbb_data[MSC_MEDIA_PACKET_SIZE]; + + uint8_t max_lun; + uint8_t bbb_state; + uint8_t bbb_status; + + uint32_t bbb_datalen; + + msc_bbb_cbw bbb_cbw; + msc_bbb_csw bbb_csw; + + uint8_t scsi_sense_head; + uint8_t scsi_sense_tail; + + uint32_t scsi_blk_size[MEM_LUN_NUM]; + uint32_t scsi_blk_nbr[MEM_LUN_NUM]; + + uint32_t scsi_blk_addr; + uint32_t scsi_blk_len; + uint32_t scsi_disk_pop; + + msc_scsi_sense scsi_sense[SENSE_LIST_DEEPTH]; +} usbd_msc_handler; + +/* function declarations */ +/* initialize the BBB process */ +void msc_bbb_init (usb_core_driver *udev); +/* reset the BBB machine */ +void msc_bbb_reset (usb_core_driver *udev); +/* deinitialize the BBB machine */ +void msc_bbb_deinit (usb_core_driver *udev); +/* handle BBB data IN stage */ +void msc_bbb_data_in (usb_core_driver *udev, uint8_t ep_num); +/* handle BBB data OUT stage */ +void msc_bbb_data_out (usb_core_driver *udev, uint8_t ep_num); +/* send the CSW(command status wrapper) */ +void msc_bbb_csw_send (usb_core_driver *udev, uint8_t csw_status); +/* complete the clear feature request */ +void msc_bbb_clrfeature (usb_core_driver *udev, uint8_t ep_num); + +#endif /* __USBD_MSC_BBB_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_core.h new file mode 100644 index 0000000..accdf21 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_core.h @@ -0,0 +1,59 @@ +/*! + \file usbd_msc_core.h + \brief the header file of USB MSC device class core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBD_MSC_CORE_H +#define __USBD_MSC_CORE_H + +#include "usbd_core.h" +#include "usb_msc.h" + +#define USB_MSC_CONFIG_DESC_SIZE 32U + +#define MSC_EPIN_SIZE MSC_DATA_PACKET_SIZE +#define MSC_EPOUT_SIZE MSC_DATA_PACKET_SIZE + +/* USB configuration descriptor structure */ +typedef struct +{ + usb_desc_config config; + + usb_desc_itf msc_itf; + usb_desc_ep msc_epin; + usb_desc_ep msc_epout; +} usb_desc_config_set; + +extern usb_desc msc_desc; +extern usb_class_core msc_class; + +#endif /* __USBD_MSC_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_mem.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_mem.h new file mode 100644 index 0000000..5ae3db4 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_mem.h @@ -0,0 +1,59 @@ +/*! + \file usbd_msc_mem.h + \brief header file for storage memory + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBD_MSC_MEM_H +#define __USBD_MSC_MEM_H + +#include "usbd_conf.h" + +#define USBD_STD_INQUIRY_LENGTH 36U + +typedef struct +{ + int8_t (*mem_init) (uint8_t lun); + int8_t (*mem_ready) (uint8_t lun); + int8_t (*mem_protected) (uint8_t lun); + int8_t (*mem_read) (uint8_t lun, uint8_t *buf, uint32_t block_addr, uint16_t block_len); + int8_t (*mem_write) (uint8_t lun, uint8_t *buf, uint32_t block_addr, uint16_t block_len); + int8_t (*mem_maxlun) (void); + + uint8_t *mem_toc_data; + uint8_t *mem_inquiry_data[MEM_LUN_NUM]; + uint32_t mem_block_size[MEM_LUN_NUM]; + uint32_t mem_block_len[MEM_LUN_NUM]; +} usbd_mem_cb; + +extern usbd_mem_cb *usbd_mem_fops; + +#endif /* __USBD_MSC_MEM_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_scsi.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_scsi.h new file mode 100644 index 0000000..f7f5b4b --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Include/usbd_msc_scsi.h @@ -0,0 +1,58 @@ +/*! + \file usbd_msc_scsi.h + \brief the header file of the usbd_msc_scsi.c file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBD_MSC_SCSI_H +#define __USBD_MSC_SCSI_H + +#include "usbd_msc_bbb.h" +#include "msc_scsi.h" + +#define SENSE_LIST_DEEPTH 4U + +#define MODE_SENSE6_LENGTH 8U +#define MODE_SENSE10_LENGTH 8U +#define INQUIRY_PAGE00_LENGTH 96U +#define FORMAT_CAPACITIES_LENGTH 20U + +extern const uint8_t msc_page00_inquiry_data[]; +extern const uint8_t msc_mode_sense6_data[]; +extern const uint8_t msc_mode_sense10_data[]; + +/* function declarations */ +/* process SCSI commands */ +int8_t scsi_process_cmd (usb_core_driver *udev, uint8_t lun, uint8_t *cmd); +/* load the last error code in the error list */ +void scsi_sense_code (usb_core_driver *udev, uint8_t lun, uint8_t skey, uint8_t asc); + +#endif /* __USBD_MSC_SCSI_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_bbb.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_bbb.c new file mode 100644 index 0000000..2a22a37 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_bbb.c @@ -0,0 +1,287 @@ +/*! + \file usbd_msc_bbb.c + \brief USB BBB(Bulk/Bulk/Bulk) protocol core functions + \note BBB means Bulk-only transport protocol for USB MSC + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbd_enum.h" +#include "usbd_msc_bbb.h" + +/* local function prototypes ('static') */ +static void msc_bbb_cbw_decode (usb_core_driver *udev); +static void msc_bbb_data_send (usb_core_driver *udev, uint8_t *pbuf, uint32_t Len); +static void msc_bbb_abort (usb_core_driver *udev); + +/*! + \brief initialize the BBB process + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +void msc_bbb_init (usb_core_driver *udev) +{ + uint8_t lun_num; + + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_state = BBB_IDLE; + msc->bbb_status = BBB_STATUS_NORMAL; + + /* initializes the storage logic unit */ + for(lun_num = 0U; lun_num < MEM_LUN_NUM; lun_num++) { + usbd_mem_fops->mem_init(lun_num); + } + + /* flush the Rx FIFO */ + usbd_fifo_flush (udev, MSC_OUT_EP); + + /* flush the Tx FIFO */ + usbd_fifo_flush (udev, MSC_IN_EP); + + /* prepare endpoint to receive the first BBB CBW */ + usbd_ep_recev (udev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH); +} + +/*! + \brief reset the BBB machine + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +void msc_bbb_reset (usb_core_driver *udev) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_state = BBB_IDLE; + msc->bbb_status = BBB_STATUS_RECOVERY; + + /* prepare endpoint to receive the first BBB command */ + usbd_ep_recev (udev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH); +} + +/*! + \brief deinitialize the BBB machine + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +void msc_bbb_deinit (usb_core_driver *udev) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_state = BBB_IDLE; +} + +/*! + \brief handle BBB data IN stage + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint number + \param[out] none + \retval none +*/ +void msc_bbb_data_in (usb_core_driver *udev, uint8_t ep_num) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + switch (msc->bbb_state) { + case BBB_DATA_IN: + if (scsi_process_cmd (udev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) { + msc_bbb_csw_send (udev, CSW_CMD_FAILED); + } + break; + + case BBB_SEND_DATA: + case BBB_LAST_DATA_IN: + msc_bbb_csw_send (udev, CSW_CMD_PASSED); + break; + + default: + break; + } +} + +/*! + \brief handle BBB data OUT stage + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint number + \param[out] none + \retval none +*/ +void msc_bbb_data_out (usb_core_driver *udev, uint8_t ep_num) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + switch (msc->bbb_state) { + case BBB_IDLE: + msc_bbb_cbw_decode (udev); + break; + + case BBB_DATA_OUT: + if (scsi_process_cmd (udev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) { + msc_bbb_csw_send (udev, CSW_CMD_FAILED); + } + break; + + default: + break; + } +} + +/*! + \brief send the CSW(command status wrapper) + \param[in] udev: pointer to USB device instance + \param[in] csw_status: CSW status + \param[out] none + \retval none +*/ +void msc_bbb_csw_send (usb_core_driver *udev, uint8_t csw_status) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_csw.dCSWSignature = BBB_CSW_SIGNATURE; + msc->bbb_csw.bCSWStatus = csw_status; + msc->bbb_state = BBB_IDLE; + + usbd_ep_send (udev, MSC_IN_EP, (uint8_t *)&msc->bbb_csw, BBB_CSW_LENGTH); + + /* prepare endpoint to receive next command */ + usbd_ep_recev (udev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH); +} + +/*! + \brief complete the clear feature request + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint number + \param[out] none + \retval none +*/ +void msc_bbb_clrfeature (usb_core_driver *udev, uint8_t ep_num) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + if (msc->bbb_status == BBB_STATUS_ERROR) { /* bad CBW signature */ + usbd_ep_stall(udev, MSC_IN_EP); + + msc->bbb_status = BBB_STATUS_NORMAL; + } else if(((ep_num & 0x80U) == 0x80U) && (msc->bbb_status != BBB_STATUS_RECOVERY)) { + msc_bbb_csw_send (udev, CSW_CMD_FAILED); + } else { + + } +} + +/*! + \brief decode the CBW command and set the BBB state machine accordingly + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +static void msc_bbb_cbw_decode (usb_core_driver *udev) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_csw.dCSWTag = msc->bbb_cbw.dCBWTag; + msc->bbb_csw.dCSWDataResidue = msc->bbb_cbw.dCBWDataTransferLength; + + if((BBB_CBW_LENGTH != usbd_rxcount_get(udev, MSC_OUT_EP)) || + (BBB_CBW_SIGNATURE != msc->bbb_cbw.dCBWSignature) || + (msc->bbb_cbw.bCBWLUN > 1U) || + (msc->bbb_cbw.bCBWCBLength < 1U) || + (msc->bbb_cbw.bCBWCBLength > 16U)) { + /* illegal command handler */ + scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB); + + msc->bbb_status = BBB_STATUS_ERROR; + + msc_bbb_abort (udev); + } else { + if (scsi_process_cmd (udev, msc->bbb_cbw.bCBWLUN, &msc->bbb_cbw.CBWCB[0]) < 0) { + msc_bbb_abort (udev); + } else if ((BBB_DATA_IN != msc->bbb_state) && + (BBB_DATA_OUT != msc->bbb_state) && + (BBB_LAST_DATA_IN != msc->bbb_state)) { /* burst xfer handled internally */ + if (msc->bbb_datalen > 0U) { + msc_bbb_data_send (udev, msc->bbb_data, msc->bbb_datalen); + } else if (0U == msc->bbb_datalen) { + msc_bbb_csw_send (udev, CSW_CMD_PASSED); + } else { + + } + } else { + + } + } +} + +/*! + \brief send the requested data + \param[in] udev: pointer to USB device instance + \param[in] buf: pointer to data buffer + \param[in] len: data length + \param[out] none + \retval none +*/ +static void msc_bbb_data_send (usb_core_driver *udev, uint8_t *buf, uint32_t len) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + len = USB_MIN (msc->bbb_cbw.dCBWDataTransferLength, len); + + msc->bbb_csw.dCSWDataResidue -= len; + msc->bbb_csw.bCSWStatus = CSW_CMD_PASSED; + msc->bbb_state = BBB_SEND_DATA; + + usbd_ep_send (udev, MSC_IN_EP, buf, len); +} + +/*! + \brief abort the current transfer + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +static void msc_bbb_abort (usb_core_driver *udev) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + if ((0U == msc->bbb_cbw.bmCBWFlags) && + (0U != msc->bbb_cbw.dCBWDataTransferLength) && + (BBB_STATUS_NORMAL == msc->bbb_status)) { + usbd_ep_stall(udev, MSC_OUT_EP); + } + + usbd_ep_stall(udev, MSC_IN_EP); + + if (msc->bbb_status == BBB_STATUS_ERROR) { + usbd_ep_recev (udev, MSC_OUT_EP, (uint8_t *)&msc->bbb_cbw, BBB_CBW_LENGTH); + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_core.c new file mode 100644 index 0000000..772a78e --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_core.c @@ -0,0 +1,404 @@ +/*! + \file usbd_msc_core.c + \brief USB MSC device class core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbd_enum.h" +#include "usbd_msc_bbb.h" +#include "usbd_msc_core.h" +#include + +#define USBD_VID 0x28E9U +#define USBD_PID 0x028FU + +/* local function prototypes ('static') */ +static uint8_t msc_core_init (usb_dev *udev, uint8_t config_index); +static uint8_t msc_core_deinit (usb_dev *udev, uint8_t config_index); +static uint8_t msc_core_req (usb_dev *udev, usb_req *req); +static uint8_t msc_core_in (usb_dev *udev, uint8_t ep_num); +static uint8_t msc_core_out (usb_dev *udev, uint8_t ep_num); + +usb_class_core msc_class = +{ + .init = msc_core_init, + .deinit = msc_core_deinit, + + .req_proc = msc_core_req, + + .data_in = msc_core_in, + .data_out = msc_core_out +}; + +/* note: it should use the C99 standard when compiling the below codes */ +/* USB standard device descriptor */ +__ALIGN_BEGIN const usb_desc_dev msc_dev_desc __ALIGN_END = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV + }, + .bcdUSB = 0x0200U, + .bDeviceClass = 0x00U, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM +}; + +/* USB device configuration descriptor */ +__ALIGN_BEGIN const usb_desc_config_set msc_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG + }, + .wTotalLength = USB_MSC_CONFIG_DESC_SIZE, + .bNumInterfaces = 0x01U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0xC0U, + .bMaxPower = 0x32U + }, + + .msc_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x02U, + .bInterfaceClass = USB_CLASS_MSC, + .bInterfaceSubClass = USB_MSC_SUBCLASS_SCSI, + .bInterfaceProtocol = USB_MSC_PROTOCOL_BBB, + .iInterface = 0x00U + }, + + .msc_epin = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = MSC_IN_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = MSC_EPIN_SIZE, + .bInterval = 0x00U + }, + + .msc_epout = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = MSC_OUT_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = MSC_EPOUT_SIZE, + .bInterval = 0x00U + } +}; + +/* USB device configuration descriptor */ +__ALIGN_BEGIN const usb_desc_config_set other_speed_msc_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_OTHER_SPD_CONFIG + }, + .wTotalLength = USB_MSC_CONFIG_DESC_SIZE, + .bNumInterfaces = 0x01U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0xC0U, + .bMaxPower = 0x32U + }, + + .msc_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x02U, + .bInterfaceClass = USB_CLASS_MSC, + .bInterfaceSubClass = USB_MSC_SUBCLASS_SCSI, + .bInterfaceProtocol = USB_MSC_PROTOCOL_BBB, + .iInterface = 0x00U + }, + + .msc_epin = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = MSC_IN_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = 64U, + .bInterval = 0x00U + }, + + .msc_epout = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = MSC_OUT_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = 64U, + .bInterval = 0x00U + } +}; + +__ALIGN_BEGIN const uint8_t usbd_qualifier_desc[10] __ALIGN_END = +{ + 0x0A, + 0x06, + 0x00, + 0x02, + 0x00, + 0x00, + 0x00, + 0x40, + 0x01, + 0x00 +}; + +/* USB language ID descriptor */ +static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR + }, + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(10U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'M', 'S', 'C'} +}; + +/* USBD serial string */ +static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12U), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +/* USB string descriptor */ +static void *const usbd_msc_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *)&usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *)&manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *)&product_string, + [STR_IDX_SERIAL] = (uint8_t *)&serial_string +}; + +usb_desc msc_desc = { + .dev_desc = (uint8_t *)&msc_dev_desc, + .config_desc = (uint8_t *)&msc_config_desc, + +#if defined(USE_USB_HS) && defined(USE_ULPI_PHY) + .other_speed_config_desc = (uint8_t *)&other_speed_msc_config_desc, + .qualifier_desc = (uint8_t *)&usbd_qualifier_desc, +#endif /* USE_USB_HS && USE_ULPI_PHY */ + + .strings = usbd_msc_strings +}; + +static __ALIGN_BEGIN uint8_t usbd_msc_maxlun __ALIGN_END = 0U ; + +/*! + \brief initialize the MSC device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t msc_core_init (usb_dev *udev, uint8_t config_index) +{ + static __ALIGN_BEGIN usbd_msc_handler msc_handler __ALIGN_END; + + memset((void *)&msc_handler, 0U, sizeof(usbd_msc_handler)); + + udev->dev.class_data[USBD_MSC_INTERFACE] = (void *)&msc_handler; + + /* configure MSC Tx endpoint */ + usbd_ep_setup (udev, &(msc_config_desc.msc_epin)); + + /* configure MSC Rx endpoint */ + usbd_ep_setup (udev, &(msc_config_desc.msc_epout)); + + /* initialize the BBB layer */ + msc_bbb_init(udev); + + return USBD_OK; +} + +/*! + \brief deinitialize the MSC device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t msc_core_deinit (usb_dev *udev, uint8_t config_index) +{ + /* clear MSC endpoints */ + usbd_ep_clear (udev, MSC_IN_EP); + usbd_ep_clear (udev, MSC_OUT_EP); + + /* deinitialize the BBB layer */ + msc_bbb_deinit(udev); + + return USBD_OK; +} + +/*! + \brief handle the MSC class-specific and standard requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t msc_core_req (usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + + switch (req->bRequest) { + case BBB_GET_MAX_LUN : + if((0U == req->wValue) && + (1U == req->wLength) && + (0x80U == (req->bmRequestType & 0x80U))) { + usbd_msc_maxlun = (uint8_t)usbd_mem_fops->mem_maxlun(); + + transc->xfer_buf = &usbd_msc_maxlun; + transc->remain_len = 1U; + } else { + return USBD_FAIL; + } + break; + + case BBB_RESET : + if((0U == req->wValue) && + (0U == req->wLength) && + (0x80U != (req->bmRequestType & 0x80U))) { + msc_bbb_reset(udev); + } else { + return USBD_FAIL; + } + break; + + case USB_CLEAR_FEATURE: + msc_bbb_clrfeature (udev, (uint8_t)req->wIndex); + break; + + default: + return USBD_FAIL; + } + + return USBD_OK; +} + +/*! + \brief handle data in stage + \param[in] udev: pointer to USB device instance + \param[in] ep_num: the endpoint number + \param[out] none + \retval none +*/ +static uint8_t msc_core_in (usb_dev *udev, uint8_t ep_num) +{ + msc_bbb_data_in (udev, ep_num); + + return USBD_OK; +} + +/*! + \brief handle data out stage + \param[in] udev: pointer to USB device instance + \param[in] ep_num: the endpoint number + \param[out] none + \retval none +*/ +static uint8_t msc_core_out (usb_dev *udev, uint8_t ep_num) +{ + msc_bbb_data_out (udev, ep_num); + + return USBD_OK; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_scsi.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_scsi.c new file mode 100644 index 0000000..fd03342 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/msc/Source/usbd_msc_scsi.c @@ -0,0 +1,761 @@ +/*! + \file usbd_msc_scsi.c + \brief USB SCSI layer functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbd_enum.h" +#include "usbd_msc_bbb.h" +#include "usbd_msc_scsi.h" + +/* USB mass storage page 0 inquiry data */ +const uint8_t msc_page00_inquiry_data[] = +{ + 0x00U, + 0x00U, + 0x00U, + 0x00U, + (INQUIRY_PAGE00_LENGTH - 4U), + 0x80U, + 0x83U, +}; + +/* USB mass storage sense 6 data */ +const uint8_t msc_mode_sense6_data[] = +{ + 0x00U, + 0x00U, + 0x00U, + 0x00U, + 0x00U, + 0x00U, + 0x00U, + 0x00U +}; + +/* USB mass storage sense 10 data */ +const uint8_t msc_mode_sense10_data[] = +{ + 0x00U, + 0x06U, + 0x00U, + 0x00U, + 0x00U, + 0x00U, + 0x00U, + 0x00U +}; + +/* local function prototypes ('static') */ +static int8_t scsi_test_unit_ready (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_mode_select6 (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_mode_select10 (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_inquiry (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_read_format_capacity (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_read_capacity10 (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_request_sense (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_mode_sense6 (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_toc_cmd_read (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_mode_sense10 (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_write10 (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_read10 (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static int8_t scsi_verify10 (usb_core_driver *udev, uint8_t lun, uint8_t *params); + +static int8_t scsi_process_read (usb_core_driver *udev, uint8_t lun); +static int8_t scsi_process_write (usb_core_driver *udev, uint8_t lun); + +static inline int8_t scsi_check_address_range (usb_core_driver *udev, uint8_t lun, uint32_t blk_offset, uint16_t blk_nbr); +static inline int8_t scsi_format_cmd (usb_core_driver *udev, uint8_t lun); +static inline int8_t scsi_start_stop_unit (usb_core_driver *udev, uint8_t lun, uint8_t *params); +static inline int8_t scsi_allow_medium_removal (usb_core_driver *udev, uint8_t lun, uint8_t *params); + +/*! + \brief process SCSI commands + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +int8_t scsi_process_cmd(usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + switch (params[0]) { + case SCSI_TEST_UNIT_READY: + return scsi_test_unit_ready (udev, lun, params); + + case SCSI_REQUEST_SENSE: + return scsi_request_sense (udev, lun, params); + + case SCSI_INQUIRY: + return scsi_inquiry (udev, lun, params); + + case SCSI_START_STOP_UNIT: + return scsi_start_stop_unit (udev, lun, params); + + case SCSI_ALLOW_MEDIUM_REMOVAL: + return scsi_allow_medium_removal (udev, lun, params); + + case SCSI_MODE_SENSE6: + return scsi_mode_sense6 (udev, lun, params); + + case SCSI_MODE_SENSE10: + return scsi_mode_sense10 (udev, lun, params); + + case SCSI_READ_FORMAT_CAPACITIES: + return scsi_read_format_capacity (udev, lun, params); + + case SCSI_READ_CAPACITY10: + return scsi_read_capacity10 (udev, lun, params); + + case SCSI_READ10: + return scsi_read10 (udev, lun, params); + + case SCSI_WRITE10: + return scsi_write10 (udev, lun, params); + + case SCSI_VERIFY10: + return scsi_verify10 (udev, lun, params); + + case SCSI_FORMAT_UNIT: + return scsi_format_cmd (udev, lun); + + case SCSI_READ_TOC_DATA: + return scsi_toc_cmd_read (udev, lun, params); + + case SCSI_MODE_SELECT6: + return scsi_mode_select6 (udev, lun, params); + + case SCSI_MODE_SELECT10: + return scsi_mode_select10 (udev, lun, params); + + default: + scsi_sense_code (udev, lun, ILLEGAL_REQUEST, INVALID_CDB); + return -1; + } +} + +/*! + \brief load the last error code in the error list + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] skey: sense key + \param[in] asc: additional sense key + \param[out] none + \retval none +*/ +void scsi_sense_code (usb_core_driver *udev, uint8_t lun, uint8_t skey, uint8_t asc) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->scsi_sense[msc->scsi_sense_tail].SenseKey = skey; + msc->scsi_sense[msc->scsi_sense_tail].ASC = asc; + msc->scsi_sense_tail++; + + if (SENSE_LIST_DEEPTH == msc->scsi_sense_tail) { + msc->scsi_sense_tail = 0U; + } +} + +/*! + \brief process SCSI Test Unit Ready command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_test_unit_ready (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + /* case 9 : Hi > D0 */ + if (0U != msc->bbb_cbw.dCBWDataTransferLength) { + scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB); + + return -1; + } + + if (0 != usbd_mem_fops->mem_ready(lun)) { + scsi_sense_code(udev, lun, NOT_READY, MEDIUM_NOT_PRESENT); + + return -1; + } + + msc->bbb_datalen = 0U; + + return 0; +} + +/*! + \brief process Inquiry command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_mode_select6 (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_datalen = 0U; + + return 0; +} + +/*! + \brief process Inquiry command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_mode_select10 (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_datalen = 0U; + + return 0; +} + +/*! + \brief process Inquiry command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_inquiry (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + uint8_t *page = NULL; + uint16_t len = 0U; + + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + if (params[1] & 0x01U) { + page = (uint8_t *)msc_page00_inquiry_data; + + len = INQUIRY_PAGE00_LENGTH; + } else { + page = (uint8_t *)usbd_mem_fops->mem_inquiry_data[lun]; + + len = (uint16_t)(page[4] + 5U); + + if (params[4] <= len) { + len = params[4]; + } + } + + msc->bbb_datalen = len; + + while (len) { + len--; + msc->bbb_data[len] = page[len]; + } + + return 0; +} + +/*! + \brief process Read Capacity 10 command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_read_capacity10 (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + uint32_t blk_num = usbd_mem_fops->mem_block_len[lun] - 1U; + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->scsi_blk_nbr[lun] = usbd_mem_fops->mem_block_len[lun]; + msc->scsi_blk_size[lun] = usbd_mem_fops->mem_block_size[lun]; + + msc->bbb_data[0] = (uint8_t)(blk_num >> 24U); + msc->bbb_data[1] = (uint8_t)(blk_num >> 16U); + msc->bbb_data[2] = (uint8_t)(blk_num >> 8U); + msc->bbb_data[3] = (uint8_t)(blk_num); + + msc->bbb_data[4] = (uint8_t)(msc->scsi_blk_size[lun] >> 24U); + msc->bbb_data[5] = (uint8_t)(msc->scsi_blk_size[lun] >> 16U); + msc->bbb_data[6] = (uint8_t)(msc->scsi_blk_size[lun] >> 8U); + msc->bbb_data[7] = (uint8_t)(msc->scsi_blk_size[lun]); + + msc->bbb_datalen = 8U; + + return 0; +} + +/*! + \brief process Read Format Capacity command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_read_format_capacity (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + uint16_t i = 0U; + uint32_t blk_size = usbd_mem_fops->mem_block_size[lun]; + uint32_t blk_num = usbd_mem_fops->mem_block_len[lun]; + uint32_t blk_nbr = blk_num - 1U; + + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + for (i = 0U; i < 12U; i++) { + msc->bbb_data[i] = 0U; + } + + msc->bbb_data[3] = 0x08U; + msc->bbb_data[4] = (uint8_t)(blk_nbr >> 24U); + msc->bbb_data[5] = (uint8_t)(blk_nbr >> 16U); + msc->bbb_data[6] = (uint8_t)(blk_nbr >> 8U); + msc->bbb_data[7] = (uint8_t)(blk_nbr); + + msc->bbb_data[8] = 0x02U; + msc->bbb_data[9] = (uint8_t)(blk_size >> 16U); + msc->bbb_data[10] = (uint8_t)(blk_size >> 8U); + msc->bbb_data[11] = (uint8_t)(blk_size); + + msc->bbb_datalen = 12U; + + return 0; +} + +/*! + \brief process Mode Sense6 command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_mode_sense6 (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + uint16_t len = 8U; + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_datalen = len; + + while (len) { + len--; + msc->bbb_data[len] = msc_mode_sense6_data[len]; + } + + return 0; +} + +/*! + \brief process Mode Sense10 command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_mode_sense10 (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + uint16_t len = 8U; + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_datalen = len; + + while (len) { + len--; + msc->bbb_data[len] = msc_mode_sense10_data[len]; + } + + return 0; +} + +/*! + \brief process Request Sense command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_request_sense (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + uint8_t i = 0U; + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + for (i = 0U; i < REQUEST_SENSE_DATA_LEN; i++) { + msc->bbb_data[i] = 0U; + } + + msc->bbb_data[0] = 0x70U; + msc->bbb_data[7] = REQUEST_SENSE_DATA_LEN - 6U; + + if ((msc->scsi_sense_head != msc->scsi_sense_tail)) { + msc->bbb_data[2] = msc->scsi_sense[msc->scsi_sense_head].SenseKey; + msc->bbb_data[12] = msc->scsi_sense[msc->scsi_sense_head].ASC; + msc->bbb_data[13] = msc->scsi_sense[msc->scsi_sense_head].ASCQ; + msc->scsi_sense_head++; + + if (msc->scsi_sense_head == SENSE_LIST_DEEPTH) { + msc->scsi_sense_head = 0U; + } + } + + msc->bbb_datalen = USB_MIN(REQUEST_SENSE_DATA_LEN, params[4]); + + return 0; +} + +/*! + \brief process Start Stop Unit command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static inline int8_t scsi_start_stop_unit (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_datalen = 0U; + msc->scsi_disk_pop = 1U; + + return 0; +} + +/*! + \brief process Allow Medium Removal command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static inline int8_t scsi_allow_medium_removal (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + msc->bbb_datalen = 0U; + + return 0; +} + +/*! + \brief process Read10 command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_read10 (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + if (msc->bbb_state == BBB_IDLE) { + /* direction is from device to host */ + if (0x80U != (msc->bbb_cbw.bmCBWFlags & 0x80U)) { + scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB); + + return -1; + } + + if (0 != usbd_mem_fops->mem_ready(lun)) { + scsi_sense_code (udev, lun, NOT_READY, MEDIUM_NOT_PRESENT); + + return -1; + } + + msc->scsi_blk_addr = (params[2] << 24U) | (params[3] << 16U) | \ + (params[4] << 8U) | params[5]; + + msc->scsi_blk_len = (params[7] << 8U) | params[8]; + + if (scsi_check_address_range (udev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) { + return -1; /* error */ + } + + msc->bbb_state = BBB_DATA_IN; + + msc->scsi_blk_addr *= msc->scsi_blk_size[lun]; + msc->scsi_blk_len *= msc->scsi_blk_size[lun]; + + /* cases 4,5 : Hi <> Dn */ + if (msc->bbb_cbw.dCBWDataTransferLength != msc->scsi_blk_len) { + scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB); + + return -1; + } + } + + msc->bbb_datalen = MSC_MEDIA_PACKET_SIZE; + + return scsi_process_read (udev, lun); +} + +/*! + \brief process Write10 command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_write10 (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + if (BBB_IDLE == msc->bbb_state) { + /* case 8 : Hi <> Do */ + if (0x80U == (msc->bbb_cbw.bmCBWFlags & 0x80U)) { + scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB); + + return -1; + } + + /* check whether media is ready */ + if (0 != usbd_mem_fops->mem_ready(lun)) { + scsi_sense_code (udev, lun, NOT_READY, MEDIUM_NOT_PRESENT); + + return -1; + } + + /* check if media is write-protected */ + if (0 != usbd_mem_fops->mem_protected(lun)) { + scsi_sense_code (udev, lun, NOT_READY, WRITE_PROTECTED); + + return -1; + } + + msc->scsi_blk_addr = (params[2] << 24U) | (params[3] << 16U) | \ + (params[4] << 8U) | params[5]; + + msc->scsi_blk_len = (params[7] << 8U) | params[8]; + + /* check if LBA address is in the right range */ + if (scsi_check_address_range (udev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) { + return -1; /* error */ + } + + msc->scsi_blk_addr *= msc->scsi_blk_size[lun]; + msc->scsi_blk_len *= msc->scsi_blk_size[lun]; + + /* cases 3,11,13 : Hn,Ho <> D0 */ + if (msc->bbb_cbw.dCBWDataTransferLength != msc->scsi_blk_len) { + scsi_sense_code (udev, msc->bbb_cbw.bCBWLUN, ILLEGAL_REQUEST, INVALID_CDB); + + return -1; + } + + /* prepare endpoint to receive first data packet */ + msc->bbb_state = BBB_DATA_OUT; + + usbd_ep_recev (udev, + MSC_OUT_EP, + msc->bbb_data, + USB_MIN (msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE)); + } else { /* write process ongoing */ + return scsi_process_write (udev, lun); + } + + return 0; +} + +/*! + \brief process Verify10 command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_verify10 (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + if (0x02U == (params[1] & 0x02U)) { + scsi_sense_code (udev, lun, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + + return -1; /* error, verify mode not supported*/ + } + + if (scsi_check_address_range (udev, lun, msc->scsi_blk_addr, (uint16_t)msc->scsi_blk_len) < 0) { + return -1; /* error */ + } + + msc->bbb_datalen = 0U; + + return 0; +} + +/*! + \brief check address range + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] blk_offset: block offset + \param[in] blk_nbr: number of block to be processed + \param[out] none + \retval status +*/ +static inline int8_t scsi_check_address_range (usb_core_driver *udev, uint8_t lun, uint32_t blk_offset, uint16_t blk_nbr) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + if ((blk_offset + blk_nbr) > msc->scsi_blk_nbr[lun]) { + scsi_sense_code (udev, lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE); + + return -1; + } + + return 0; +} + +/*! + \brief handle read process + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[out] none + \retval status +*/ +static int8_t scsi_process_read (usb_core_driver *udev, uint8_t lun) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + uint32_t len = USB_MIN(msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE); + + if (usbd_mem_fops->mem_read(lun, + msc->bbb_data, + msc->scsi_blk_addr, + (uint16_t)(len / msc->scsi_blk_size[lun])) < 0) { + scsi_sense_code(udev, lun, HARDWARE_ERROR, UNRECOVERED_READ_ERROR); + + return -1; + } + + usbd_ep_send (udev, MSC_IN_EP, msc->bbb_data, len); + + msc->scsi_blk_addr += len; + msc->scsi_blk_len -= len; + + /* case 6 : Hi = Di */ + msc->bbb_csw.dCSWDataResidue -= len; + + if (0U == msc->scsi_blk_len) { + msc->bbb_state = BBB_LAST_DATA_IN; + } + + return 0; +} + +/*! + \brief handle write process + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[out] none + \retval status +*/ +static int8_t scsi_process_write (usb_core_driver *udev, uint8_t lun) +{ + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + uint32_t len = USB_MIN(msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE); + + if (usbd_mem_fops->mem_write (lun, + msc->bbb_data, + msc->scsi_blk_addr, + (uint16_t)(len / msc->scsi_blk_size[lun])) < 0) { + scsi_sense_code(udev, lun, HARDWARE_ERROR, WRITE_FAULT); + + return -1; + } + + msc->scsi_blk_addr += len; + msc->scsi_blk_len -= len; + + /* case 12 : Ho = Do */ + msc->bbb_csw.dCSWDataResidue -= len; + + if (0U == msc->scsi_blk_len) { + msc_bbb_csw_send (udev, CSW_CMD_PASSED); + } else { + /* prepare endpoint to receive next packet */ + usbd_ep_recev (udev, + MSC_OUT_EP, + msc->bbb_data, + USB_MIN (msc->scsi_blk_len, MSC_MEDIA_PACKET_SIZE)); + } + + return 0; +} + +/*! + \brief process Format Unit command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[out] none + \retval status +*/ +static inline int8_t scsi_format_cmd (usb_core_driver *udev, uint8_t lun) +{ + return 0; +} + +/*! + \brief process Read_Toc command + \param[in] udev: pointer to USB device instance + \param[in] lun: logical unit number + \param[in] params: command parameters + \param[out] none + \retval status +*/ +static int8_t scsi_toc_cmd_read (usb_core_driver *udev, uint8_t lun, uint8_t *params) +{ + uint8_t* pPage; + uint16_t len; + + usbd_msc_handler *msc = (usbd_msc_handler *)udev->dev.class_data[USBD_MSC_INTERFACE]; + + pPage = (uint8_t *)&usbd_mem_fops->mem_toc_data[lun * READ_TOC_CMD_LEN]; + len = (uint16_t)pPage[1] + 2U; + + msc->bbb_datalen = len; + + while (len) { + len--; + msc->bbb_data[len] = pPage[len]; + } + + return 0; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/printer/Include/printer_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/printer/Include/printer_core.h new file mode 100644 index 0000000..3e4c41d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/printer/Include/printer_core.h @@ -0,0 +1,78 @@ +/*! + \file printer_core.h + \brief the header file of USB printer device class core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __PRINTER_CORE_H +#define __PRINTER_CORE_H + +#include "usbd_enum.h" +#include "usb_ch9_std.h" + +/* USB printing device class code */ +#define USB_CLASS_PRINTER 0x07U + +/* printing device subclass code */ +#define USB_SUBCLASS_PRINTER 0x01U + +/* printing device protocol code */ +#define PROTOCOL_UNIDIRECTIONAL_ITF 0x01U +#define PROTOCOL_BI_DIRECTIONAL_ITF 0x02U +#define PROTOCOL_1284_4_ITF 0x03U +#define PROTOCOL_VENDOR 0xFFU + +#define DEVICE_ID_LEN 103U + +#define USB_PRINTER_CONFIG_DESC_LEN 32U + +/* printing device specific-class request */ +#define GET_DEVICE_ID 0x00U +#define GET_PORT_STATUS 0x01U +#define SOFT_RESET 0x02U + +#pragma pack(1) + +/* USB configuration descriptor structure */ +typedef struct +{ + usb_desc_config config; + usb_desc_itf printer_itf; + usb_desc_ep printer_epin; + usb_desc_ep printer_epout; +} usb_printer_desc_config_set; + +#pragma pack() + +extern usb_desc printer_desc; +extern usb_class_core usbd_printer_cb; + +#endif /* __PRINTER_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/printer/Source/printer_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/printer/Source/printer_core.c new file mode 100644 index 0000000..8ef7984 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/printer/Source/printer_core.c @@ -0,0 +1,310 @@ +/*! + \file printer_core.c + \brief USB printer device class core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "printer_core.h" + +#define USBD_VID 0x28E9U +#define USBD_PID 0x028DU + +/* printer port status: paper not empty/selected/no error */ +static uint8_t g_port_status = 0x18U; + +uint8_t g_printer_data_buf[PRINTER_OUT_PACKET]; + +__ALIGN_BEGIN uint8_t PRINTER_DEVICE_ID[DEVICE_ID_LEN] __ALIGN_END = +{ + 0x00, 0x67, + 'M', 'A', 'N', 'U', 'F', 'A', 'C', 'T', 'U', 'R', 'E', 'R', ':', + 'G', 'I', 'G', 'A', ' ', 'D', 'E', 'V', 'I', 'C', 'E', '-', ';', + 'C', 'O', 'M', 'M', 'A', 'N', 'D', ' ', 'S', 'E', 'T', ':', + 'P', 'C', 'L', ',', 'M', 'P', 'L', ';', + 'M', 'O', 'D', 'E', 'L', ':', + 'L', 'a', 's', 'e', 'r', 'B', 'e', 'a', 'm', '?', ';', + 'C', 'O', 'M', 'M', 'E', 'N', 'T', ':', + 'G', 'o', 'o', 'd', ' ', '!', ';', + 'A', 'C', 'T', 'I', 'V', 'E', ' ', 'C', 'O', 'M', 'M', 'A', 'N', 'D', ' ', 'S', 'E', 'T', ':', + 'P', 'C', 'L', ';' +}; + +/* USB standard device descriptor */ +__ALIGN_BEGIN const usb_desc_dev printer_dev_desc __ALIGN_END = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV, + }, + .bcdUSB = 0x0200U, + .bDeviceClass = 0x00U, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM, +}; + +/* USB device configuration descriptor */ +__ALIGN_BEGIN const usb_printer_desc_config_set printer_config_desc __ALIGN_END = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG + }, + .wTotalLength = USB_PRINTER_CONFIG_DESC_LEN, + .bNumInterfaces = 0x01U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0xA0U, + .bMaxPower = 0x32U + }, + + .printer_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x02U, + .bInterfaceClass = USB_CLASS_PRINTER, + .bInterfaceSubClass = USB_SUBCLASS_PRINTER, + .bInterfaceProtocol = PROTOCOL_BI_DIRECTIONAL_ITF, + .iInterface = 0x00U + }, + + .printer_epin = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = PRINTER_IN_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = PRINTER_IN_PACKET, + .bInterval = 0x00U + }, + + .printer_epout = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = PRINTER_OUT_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = PRINTER_OUT_PACKET, + .bInterval = 0x00U + }, +}; + +/* USB language ID Descriptor */ +static __ALIGN_BEGIN const usb_desc_LANGID usbd_language_id_desc __ALIGN_END = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static __ALIGN_BEGIN const usb_desc_str manufacturer_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(10U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static __ALIGN_BEGIN const usb_desc_str product_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(16U), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'P', 'r', 'i', 'n', 't', 'e', 'r'} +}; + +/* USBD serial string */ +static __ALIGN_BEGIN usb_desc_str serial_string __ALIGN_END = +{ + .header = + { + .bLength = USB_STRING_LEN(12U), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +/* USB string descriptor */ +static void *const usbd_msc_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *)&usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *)&manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *)&product_string, + [STR_IDX_SERIAL] = (uint8_t *)&serial_string +}; + +usb_desc printer_desc = { + .dev_desc = (uint8_t *)&printer_dev_desc, + .config_desc = (uint8_t *)&printer_config_desc, + .strings = usbd_msc_strings +}; + +/* local function prototypes ('static') */ +static uint8_t printer_init (usb_dev *udev, uint8_t config_index); +static uint8_t printer_deinit (usb_dev *udev, uint8_t config_index); +static uint8_t printer_req (usb_dev *udev, usb_req *req); +static uint8_t printer_in (usb_dev *udev, uint8_t ep_num); +static uint8_t printer_out (usb_dev *udev, uint8_t ep_num); + +usb_class_core usbd_printer_cb = { + .init = printer_init, + .deinit = printer_deinit, + + .req_proc = printer_req, + + .data_in = printer_in, + .data_out = printer_out +}; + +/*! + \brief initialize the printer device + \param[in] udev: pointer to usb device instance + \param[in] config_index: configuration index + \param[out] none + \retval usb device operation status +*/ +static uint8_t printer_init (usb_dev *udev, uint8_t config_index) +{ + /* initialize the data Tx endpoint */ + usbd_ep_setup (udev, &(printer_config_desc.printer_epin)); + + /* initialize the data Rx endpoint */ + usbd_ep_setup (udev, &(printer_config_desc.printer_epout)); + + /* prepare to receive data */ + usbd_ep_recev(udev, PRINTER_OUT_EP, g_printer_data_buf, PRINTER_OUT_PACKET); + + return USBD_OK; +} + +/*! + \brief deinitialize the printer device + \param[in] udev: pointer to usb device instance + \param[in] config_index: configuration index + \param[out] none + \retval usb device operation status +*/ +static uint8_t printer_deinit (usb_dev *udev, uint8_t config_index) +{ + /* deinitialize the data Tx/Rx endpoint */ + usbd_ep_clear (udev, PRINTER_IN_EP); + usbd_ep_clear (udev, PRINTER_OUT_EP); + + return USBD_OK; +} + +/*! + \brief handle the printer class-specific requests + \param[in] udev: pointer to usb device instance + \param[in] req: device class-specific request + \param[out] none + \retval usb device operation status +*/ +static uint8_t printer_req(usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + + switch (req->bRequest) { + case GET_DEVICE_ID: + transc->xfer_buf = (uint8_t *)PRINTER_DEVICE_ID; + transc->remain_len = DEVICE_ID_LEN; + break; + + case GET_PORT_STATUS: + transc->xfer_buf = (uint8_t *)&g_port_status; + transc->remain_len = 1U; + break; + + case SOFT_RESET: + usbd_ep_recev(udev, PRINTER_OUT_EP, g_printer_data_buf, PRINTER_OUT_PACKET); + break; + + default: + return USBD_FAIL; + } + + return USBD_OK; +} + +/*! + \brief handle printer data + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint number + \param[out] none + \retval USB device operation status +*/ +static uint8_t printer_in (usb_dev *udev, uint8_t ep_num) +{ + return USBD_OK; +} + +/*! + \brief handle printer data + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint number + \param[out] none + \retval USB device operation status +*/ +static uint8_t printer_out (usb_dev *udev, uint8_t ep_num) +{ + return USBD_OK; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/rndis/Include/rndis_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/rndis/Include/rndis_core.h new file mode 100644 index 0000000..e1b4bba --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/rndis/Include/rndis_core.h @@ -0,0 +1,204 @@ +/*! + \file rndis_core.h + \brief the header file of rndis driver + + \version 2018-10-08, V1.0.0, firmware for GD32 USBFS&USBHS +*/ + +/* + Copyright (c) 2018, GigaDevice Semiconductor Inc. + + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + 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 the copyright holder 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 __RNDIS_CORE_H +#define __RNDIS_CORE_H + +#include "usbd_enum.h" +#include "usb_rndis.h" + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x00000002. */ + uint32_t MessageLength; /*!< Specifies in bytes the total length of this message, from the beginning of the message. */ + uint32_t RequestId; /*!< Specifies the Remote NDIS message ID value. This value is used to match messages sent by the host with device responses. */ + uint32_t MajorVersion; /*!< Specifies the Remote NDIS protocol version implemented by the host. The current specification uses RNDIS_MAJOR_VERSION = 1. */ + uint32_t MinorVersion; /*!< Specifies the Remote NDIS protocol version implemented by the host. The current specification uses RNDIS_MINOR_VERSION = 0. */ + uint32_t MaxTransferSize; /*!< Specifies the maximum size in bytes of any single bus data transfer that the host expects + to receive from the device. Typically, each bus data transfer accommodates a single Remote + NDIS message. However, the device may bundle several Remote NDIS messages that contain data + packets into a single transfer (see REMOTE_NDIS_PACKET_MSG). */ +}rndis_initialize_msg_struct; + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x80000002. */ + uint32_t MessageLength; /*!< Specifies in bytes the total length of this message, from the beginning of the message. */ + uint32_t RequestId; /*!< Specifies the Remote NDIS message ID value. This value is used to match messages sent by the host with device responses. */ + uint32_t Status; /*!< Specifies RNDIS_STATUS_SUCCESS if the device initialized successfully; otherwise, it specifies an error code that indicates the failure. */ + uint32_t MajorVersion; /*!< Specifies the highest Remote NDIS major protocol version supported by the device. */ + uint32_t MinorVersion; /*!< Specifies the highest Remote NDIS minor protocol version supported by the device. */ + uint32_t DeviceFlags; /*!< Specifies the miniport driver type as either connectionless or connection-oriented. This value can be one of the following: + RNDIS_DF_CONNECTIONLESS 0x00000001 RNDIS_DF_CONNECTION_ORIENTED 0x00000002 */ + uint32_t Medium; /*!< Specifies the medium supported by the device. Set to RNDIS_MEDIUM_802_3 (0x00000000) */ + uint32_t MaxPacketsPerMessage; /*!< Specifies the maximum number of Remote NDIS data messages that the device can handle in a single transfer to it. This value should be at least one. */ + uint32_t MaxTransferSize; /*!< Specifies the maximum size in bytes of any single bus data transfer that the device expects to receive from the host. */ + uint32_t PacketAlignmentFactor; /*!< Specifies the byte alignment that the device expects for each Remote NDIS message + that is part of a multimessage transfer to it. This value is specified in powers of 2. + For example, this value is set to three to indicate 8-byte alignment. This value has a + maximum setting of seven, which specifies 128-byte alignment. */ + uint32_t AFListOffset; /*!< Reserved for connection-oriented devices. Set value to zero. */ + uint32_t AFListSize; /*!< Reserved for connection-oriented devices. Set value to zero. */ +}rndis_initialize_cmplt_struct; + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x00000004. */ + uint32_t MessageLength; /*!< Specifies in bytes the total length of this message, from the beginning of the message. */ + uint32_t RequestId; /*!< Specifies the Remote NDIS message ID value. This value is used to match messages sent by the host with device responses. */ + uint32_t Oid; /*!< Specifies the NDIS OID that identifies the parameter being queried. */ + uint32_t InformationBufferLength; /*!< Specifies in bytes the length of the input data for the query. Set to zero when there is no OID input buffer. */ + uint32_t InformationBufferOffset; /*!< Specifies the byte offset, from the beginning of the RequestId field, at which input data for the query is located. Set to zero if there is no OID input buffer. */ + uint32_t DeviceVcHandle; /*!< Reserved for connection-oriented devices. Set to zero. */ +}rndis_query_msg_struct; + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x80000004. */ + uint32_t MessageLength; /*!< Specifies in bytes the total length of this message, from the beginning of the message. */ + uint32_t RequestId; /*!< Specifies the Remote NDIS message ID value. This value is used to match messages sent by the host with device responses. */ + uint32_t Status; /*!< Specifies the status of processing the OID query request. */ + uint32_t InformationBufferLength; /*!< Specifies, in bytes, the length of the response data for the query. Set to zero when there is no OID result buffer. */ + uint32_t InformationBufferOffset; /*!< Specifies the byte offset, from the beginning of the RequestId field, at which response data for the query is located. Set to zero if there is no response data. */ + uint32_t Oid_Num[28]; +}rndis_query_cmplt_struct; + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x00000005. */ + uint32_t MessageLength; /*!< Specifies, in bytes, the total length of this message, from the beginning of the message. */ + uint32_t RequestId; /*!< Specifies the Remote NDIS message ID value. This value is used to match messages sent by the host with device responses. */ + uint32_t Oid; /*!< Specifies the NDIS OID that identifies the parameter being set. */ + uint32_t InformationBufferLength; /*!< Specifies, in bytes, the length of the input data for the request. */ + uint32_t InformationBufferOffset; /*!< Specifies the byte offset, from the beginning of the RequestId field, at which input data for the request is located. */ + uint32_t DeviceVcHandle; /*!< Reserved for connection-oriented devices. Set to zero. */ +}rndis_set_msg_struct; + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x80000005. */ + uint32_t MessageLength; /*!< Specifies, in bytes, the total length of this message, from the beginning of the message. */ + uint32_t RequestId; /*!< Specifies the Remote NDIS message ID value. This value is copied from the REMOTE_NDIS_SET_MSG being responded to. */ + uint32_t Status; /*!< Specifies the status of processing the OID set request. */ + uint32_t Oid_Num[4]; +}rndis_set_cmplt_struct; + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x00000008. */ + uint32_t MessageLength; /*!< Specifies in bytes the total length of this message, from the beginning of the message. */ + uint32_t RequestId; /*!< Specifies the Remote NDIS message ID value. This value is used to match messages sent by the host with device responses. */ +}rndis_keepalive_msg_struct; + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x80000008. */ + uint32_t MessageLength; /*!< Specifies, in bytes, the total length of this message, from the beginning of the message. */ + uint32_t RequestId; /*!< Specifies the Remote NDIS message ID value. This value is used to match messages sent by the host with device responses. */ + uint32_t Status; /*!< Specifies the current status of the device. If the returned Status is not RNDIS_STATUS_SUCCESS, + the host will send an REMOTE_NDIS_RESET_MSG message to reset the device. */ +}rndis_keepalive_cmplt_struct; + +typedef struct +{ + uint32_t MessageType; /*!< Specifies the type of message being sent. Set to 0x1. */ + uint32_t MessageLength; /*!< Message length in bytes, including appended packet data, OOB data, per-packet information data, and both internal and external padding. */ + uint32_t DataOffset; /*!< Specifies the offset in bytes from the start of the DataOffset field of this message to the start of the data. This is an integer multiple of 4. */ + uint32_t DataLength; /*!< Specifies the number of bytes in the data content of this message. */ + uint32_t OOBDataOffset; /*!< Specifies the offset in bytes of the first OOB data record from the start of the DataOffset field of this message. + Set to zero if there is no OOB data. Otherwise, this is an integer multiple of 4. */ + uint32_t OOBDataLength; /*!< Specifies in bytes the total length of the OOB data. */ + uint32_t NumOOBDataElements; /*!< Specifies the number of OOB records in this message. */ + uint32_t PerPacketInfoOffset; /*!< Specifies in bytes the offset from the beginning of the DataOffset field in the REMOTE_NDIS_PACKET_MSG data message to the start of the first per-packet information data record. + Set to zero if there is no per-packet data. Otherwise, this is an integer multiple of 4. */ + uint32_t PerPacketInfoLength; /*!< Specifies in bytes the total length of the per-packet information contained in this message. */ + uint32_t VcHandle; /*!< Reserved for connection-oriented devices. Set to zero. */ + uint32_t Reserved; /*!< Reserved. Set to zero. */ +}rndis_package_msg_struct; + +typedef struct { + uint8_t packet_sent; + uint32_t usb_data_len; + uint32_t receive_length; + uint32_t USB_enet_data_length; + uint8_t usb_data_buffer[64]; + uint8_t USB_enet_data_buffer[1000]; +} USB_TO_ENET_DATA; + +typedef struct { + uint32_t ENET_receive_length; + uint8_t ENET_USB_data_buffer[2000]; +} ENET_TO_USB_DATA; + +typedef struct { + uint8_t cmd_send; + uint8_t usb_enet_response_available_buffer[8]; + uint8_t usb_enet_cmd_buffer[100]; +} USB_ENET_CMD; + +typedef struct _usbd_rndis_handler +{ + USB_ENET_CMD usb_enet_cmd; + USB_TO_ENET_DATA usb_to_enet; + ENET_TO_USB_DATA enet_to_usb; + + rndis_initialize_msg_struct *init_msg; + rndis_initialize_cmplt_struct init_cmplt; + rndis_query_msg_struct *query_msg; + rndis_query_cmplt_struct query_cmplt; + rndis_set_msg_struct *set_msg; + rndis_set_cmplt_struct set_cmplt; + rndis_keepalive_msg_struct *keepalive_msg; + rndis_keepalive_cmplt_struct keepalive_cmplt; + rndis_package_msg_struct *package_msg; + rndis_package_msg_struct package_return_msg; +}usbd_rndis_handler; + +extern usb_desc rndis_desc; +extern usb_class_core rndis_class; + +/* function declarations */ +/* send RNDIS CMD */ +void rndis_cmd_send (usb_dev *udev, uint32_t len); + +/* receive RNDIS data */ +void rndis_data_receive(usb_dev *udev); + +/* send RNDIS data */ +void rndis_data_send(usb_dev *udev, uint32_t data_len); + +#endif /* __RNDIS_CORE_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/rndis/Source/rndis_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/rndis/Source/rndis_core.c new file mode 100644 index 0000000..15f336a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/class/rndis/Source/rndis_core.c @@ -0,0 +1,786 @@ +/*! + \file rndis_core.c + \brief rndis driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "rndis_core.h" +#include "usbd_transc.h" +#include "rndis_oid.h" +#include +#include "ethernetif.h" + +#define USBD_VID 0x28E9U +#define USBD_PID 0x0801U + +/* note:it should use the C99 standard when compiling the below codes */ +/* USB standard device descriptor */ +const usb_desc_dev rndis_dev_desc = +{ + .header = + { + .bLength = USB_DEV_DESC_LEN, + .bDescriptorType = USB_DESCTYPE_DEV, + }, + .bcdUSB = 0x0200U, + .bDeviceClass = USB_CLASS_WIRELESS_CTR, + .bDeviceSubClass = 0x00U, + .bDeviceProtocol = 0x00U, + .bMaxPacketSize0 = USB_FS_EP0_MAX_LEN, + .idVendor = USBD_VID, + .idProduct = USBD_PID, + .bcdDevice = 0x0100U, + .iManufacturer = STR_IDX_MFC, + .iProduct = STR_IDX_PRODUCT, + .iSerialNumber = STR_IDX_SERIAL, + .bNumberConfigurations = USBD_CFG_MAX_NUM, +}; + +/* USB device configuration descriptor */ +const usb_rndis_desc_config_set rndis_config_desc = +{ + .config = + { + .header = + { + .bLength = sizeof(usb_desc_config), + .bDescriptorType = USB_DESCTYPE_CONFIG, + }, + .wTotalLength = USB_RNDIS_CONFIG_DESC_SIZE, + .bNumInterfaces = 0x02U, + .bConfigurationValue = 0x01U, + .iConfiguration = 0x00U, + .bmAttributes = 0x40U, + .bMaxPower = 0x01U + }, + + .cmd_itf = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF + }, + .bInterfaceNumber = 0x00U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x01U, + .bInterfaceClass = USB_CLASS_WIRELESS_CTR, + .bInterfaceSubClass = 0x01U, + .bInterfaceProtocol = 0X03U, + .iInterface = 0x00U + }, + + .rndis_header = + { + .header = + { + .bLength = sizeof(usb_desc_header_func), + .bDescriptorType = USB_DESCTYPE_CS_INTERFACE + }, + .bDescriptorSubtype = 0x00U, + .bcdCDC = 0x0110U + }, + + .rndis_call_managment = + { + .header = + { + .bLength = sizeof(usb_desc_call_managment_func), + .bDescriptorType = USB_DESCTYPE_CS_INTERFACE + }, + .bDescriptorSubtype = 0x01U, + .bmCapabilities = 0x00U, + .bDataInterface = 0x01U + }, + + .rndis_acm = + { + .header = + { + .bLength = sizeof(usb_desc_acm_func), + .bDescriptorType = USB_DESCTYPE_CS_INTERFACE + }, + .bDescriptorSubtype = 0x02U, + .bmCapabilities = 0x00U, + }, + + .rndis_union = + { + .header = + { + .bLength = sizeof(usb_desc_union_func), + .bDescriptorType = USB_DESCTYPE_CS_INTERFACE + }, + .bDescriptorSubtype = 0x06U, + .bMasterInterface = 0x00U, + .bSlaveInterface0 = 0x01U, + }, + + .rndis_cmd_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP, + }, + .bEndpointAddress = RNDIS_CMD_EP, + .bmAttributes = USB_EP_ATTR_INT, + .wMaxPacketSize = USB_RNDIS_CMD_PACKET_SIZE, + .bInterval = 0x01U + }, + + .rndis_data_interface = + { + .header = + { + .bLength = sizeof(usb_desc_itf), + .bDescriptorType = USB_DESCTYPE_ITF, + }, + .bInterfaceNumber = 0x01U, + .bAlternateSetting = 0x00U, + .bNumEndpoints = 0x02U, + .bInterfaceClass = USB_CLASS_DATA, + .bInterfaceSubClass = 0x00U, + .bInterfaceProtocol = 0x00U, + .iInterface = 0x00U + }, + + .rndis_out_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP, + }, + .bEndpointAddress = RNDIS_DATA_OUT_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = USB_RNDIS_DATA_PACKET_SIZE, + .bInterval = 0x00U + }, + + .rndis_in_endpoint = + { + .header = + { + .bLength = sizeof(usb_desc_ep), + .bDescriptorType = USB_DESCTYPE_EP + }, + .bEndpointAddress = RNDIS_DATA_IN_EP, + .bmAttributes = USB_EP_ATTR_BULK, + .wMaxPacketSize = USB_RNDIS_DATA_PACKET_SIZE, + .bInterval = 0x00U + } +}; + +/* USB language ID Descriptor */ +static const usb_desc_LANGID usbd_language_id_desc = +{ + .header = + { + .bLength = sizeof(usb_desc_LANGID), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .wLANGID = ENG_LANGID +}; + +/* USB manufacture string */ +static const usb_desc_str manufacturer_string = +{ + .header = + { + .bLength = USB_STRING_LEN(10), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'i', 'g', 'a', 'D', 'e', 'v', 'i', 'c', 'e'} +}; + +/* USB product string */ +static const usb_desc_str product_string = +{ + .header = + { + .bLength = USB_STRING_LEN(14), + .bDescriptorType = USB_DESCTYPE_STR, + }, + .unicode_string = {'G', 'D', '3', '2', '-', 'U', 'S', 'B', '_', 'R', 'N', 'D', 'I', 'S'} +}; + +/* USBD serial string */ +static usb_desc_str serial_string = +{ + .header = + { + .bLength = USB_STRING_LEN(12), + .bDescriptorType = USB_DESCTYPE_STR, + } +}; + +/* USB string descriptor */ +void *const usbd_rndis_strings[] = +{ + [STR_IDX_LANGID] = (uint8_t *)&usbd_language_id_desc, + [STR_IDX_MFC] = (uint8_t *)&manufacturer_string, + [STR_IDX_PRODUCT] = (uint8_t *)&product_string, + [STR_IDX_SERIAL] = (uint8_t *)&serial_string +}; + +usb_desc rndis_desc = { + .dev_desc = (uint8_t *)&rndis_dev_desc, + .config_desc = (uint8_t *)&rndis_config_desc, + .strings = usbd_rndis_strings +}; + +/* local function prototypes ('static') */ +static uint8_t rndis_init (usb_dev *udev, uint8_t config_index); +static uint8_t rndis_deinit (usb_dev *udev, uint8_t config_index); +static uint8_t rndis_req (usb_dev *udev, usb_req *req); +static uint8_t rndis_in (usb_dev *udev, uint8_t ep_num); +static uint8_t rndis_out (usb_dev *udev, uint8_t ep_num); + +static void rndis_msg_parser (usb_dev *udev); +static void rndis_data_msg_handle (usb_dev *udev); + +/* USB CDC device class callbacks structure */ +usb_class_core rndis_class = +{ + .command = NO_CMD, + .alter_set = 0, + + .init = rndis_init, + .deinit = rndis_deinit, + + .req_proc = rndis_req, + + .data_in = rndis_in, + .data_out = rndis_out +}; + +/*! + \brief initialize the CDC ACM device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t rndis_init (usb_dev *udev, uint8_t config_index) +{ + static usbd_rndis_handler rndis_handler; + + memset((void *)&rndis_handler, 0, sizeof(usbd_rndis_handler)); + + /* initialize the data Tx endpoint */ + usbd_ep_setup (udev, &(rndis_config_desc.rndis_in_endpoint)); + + /* initialize the data Rx endpoint */ + usbd_ep_setup (udev, &(rndis_config_desc.rndis_out_endpoint)); + + /* initialize the command Tx endpoint */ + usbd_ep_setup (udev, &(rndis_config_desc.rndis_cmd_endpoint)); + + rndis_handler.usb_enet_cmd.usb_enet_response_available_buffer[0] = 0x01; + rndis_handler.usb_enet_cmd.cmd_send = 1; + + rndis_handler.init_cmplt.MessageType = 0x80000002; + rndis_handler.keepalive_cmplt.MessageType = 0x80000008; + rndis_handler.query_cmplt.MessageType = 0x80000004; + rndis_handler.set_cmplt.MessageType = 0x80000005; + rndis_handler.package_return_msg.MessageType = 0x00000001; + rndis_handler.package_return_msg.DataOffset = 0x00000024; + + udev->dev.class_data[USBD_RNDIS_INTERFACE] = (void *)&rndis_handler; + + return USBD_OK; +} + +/*! + \brief de-initialize the CDC ACM device + \param[in] udev: pointer to USB device instance + \param[in] config_index: configuration index + \param[out] none + \retval USB device operation status +*/ +static uint8_t rndis_deinit (usb_dev *udev, uint8_t config_index) +{ + /* deinitialize the data Tx/Rx endpoint */ + usbd_ep_clear (udev, RNDIS_DATA_IN_EP); + usbd_ep_clear (udev, RNDIS_DATA_OUT_EP); + + /* deinitialize the command Tx endpoint */ + usbd_ep_clear (udev, RNDIS_CMD_EP); + + return USBD_OK; +} + +static void rndis_msg_parser (usb_dev *udev) +{ + usbd_rndis_handler *rndis = (usbd_rndis_handler *)udev->dev.class_data[USBD_RNDIS_INTERFACE]; + + if (rndis->usb_enet_cmd.usb_enet_cmd_buffer[0] == 0x02) { + rndis->init_msg = (rndis_initialize_msg_struct *)rndis->usb_enet_cmd.usb_enet_cmd_buffer; + } else if (rndis->usb_enet_cmd.usb_enet_cmd_buffer[0] == 0x04) { + rndis->query_msg = (rndis_query_msg_struct *)rndis->usb_enet_cmd.usb_enet_cmd_buffer; + } else if (rndis->usb_enet_cmd.usb_enet_cmd_buffer[0] == 0x05) { + rndis->set_msg = (rndis_set_msg_struct *)rndis->usb_enet_cmd.usb_enet_cmd_buffer; + } else if (rndis->usb_enet_cmd.usb_enet_cmd_buffer[0] == 0x08) { + rndis->keepalive_msg = (rndis_keepalive_msg_struct *)rndis->usb_enet_cmd.usb_enet_cmd_buffer; + } +} + +/*! + \brief handle the CDC ACM class-specific requests + \param[in] udev: pointer to USB device instance + \param[in] req: device class-specific request + \param[out] none + \retval USB device operation status +*/ +static uint8_t rndis_req (usb_dev *udev, usb_req *req) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + + usbd_rndis_handler *rndis = (usbd_rndis_handler *)udev->dev.class_data[USBD_RNDIS_INTERFACE]; + + switch (req->bRequest) { + case SEND_ENCAPSULATED_COMMAND: + + transc = &udev->dev.transc_out[0]; + transc->remain_len = req->wLength; + transc->xfer_buf = rndis->usb_enet_cmd.usb_enet_cmd_buffer; + usbd_ctl_recev (udev); + + rndis->usb_enet_cmd.cmd_send = 1; + + break; + + case GET_ENCAPSULATED_RESPONSE: + rndis_msg_parser(udev); + + if (rndis->init_msg->MessageType == 0x00000002) { + rndis->init_cmplt.MessageLength = 0x00000034; + rndis->init_cmplt.RequestId = rndis->init_msg->RequestId; + rndis->init_cmplt.Status = 0x00000000; + rndis->init_cmplt.MajorVersion = 0x00000001; + rndis->init_cmplt.MinorVersion = 0x00000000; + rndis->init_cmplt.DeviceFlags = 0x00000001; + rndis->init_cmplt.Medium = 0x00000000; + rndis->init_cmplt.MaxPacketsPerMessage = 0x00000001; + rndis->init_cmplt.MaxTransferSize = 0x00000616; + rndis->init_cmplt.PacketAlignmentFactor = 0x00000000; + rndis->init_cmplt.AFListOffset = 0x00000000; + rndis->init_cmplt.AFListSize = 0x00000000; + + transc->remain_len = 52; + transc->xfer_buf = (uint8_t *)&rndis->init_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_SUPPORTED_LIST) { + rndis->query_cmplt.MessageLength = 0x00000070; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000058; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = OID_GEN_SUPPORTED_LIST; + rndis->query_cmplt.Oid_Num[1] = OID_GEN_HARDWARE_STATUS; + rndis->query_cmplt.Oid_Num[2] = OID_GEN_MEDIA_SUPPORTED; + rndis->query_cmplt.Oid_Num[3] = OID_GEN_MEDIA_IN_USE; + rndis->query_cmplt.Oid_Num[4] = OID_GEN_MAXIMUM_FRAME_SIZE; + rndis->query_cmplt.Oid_Num[5] = OID_GEN_LINK_SPEED; + rndis->query_cmplt.Oid_Num[6] = OID_GEN_TRANSMIT_BLOCK_SIZE; + rndis->query_cmplt.Oid_Num[7] = OID_GEN_RECEIVE_BLOCK_SIZE; + rndis->query_cmplt.Oid_Num[8] = OID_GEN_VENDOR_ID; + rndis->query_cmplt.Oid_Num[9] = OID_GEN_VENDOR_DESCRIPTION; + rndis->query_cmplt.Oid_Num[10] = OID_GEN_VENDOR_DRIVER_VERSION; + rndis->query_cmplt.Oid_Num[11] = OID_GEN_CURRENT_PACKET_FILTER; + rndis->query_cmplt.Oid_Num[12] = OID_GEN_MAXIMUM_TOTAL_SIZE; + rndis->query_cmplt.Oid_Num[13] = OID_GEN_PROTOCOL_OPTIONS; + rndis->query_cmplt.Oid_Num[14] = OID_GEN_MAC_OPTIONS; /* Optional */ + rndis->query_cmplt.Oid_Num[15] = OID_GEN_MEDIA_CONNECT_STATUS; + rndis->query_cmplt.Oid_Num[16] = OID_GEN_MAXIMUM_SEND_PACKETS; + rndis->query_cmplt.Oid_Num[17] = OID_802_3_PERMANENT_ADDRESS; + rndis->query_cmplt.Oid_Num[18] = OID_802_3_CURRENT_ADDRESS; + rndis->query_cmplt.Oid_Num[19] = OID_802_3_MULTICAST_LIST; + rndis->query_cmplt.Oid_Num[20] = OID_802_3_MAXIMUM_LIST_SIZE; + rndis->query_cmplt.Oid_Num[21] = OID_802_3_MAC_OPTIONS; + + transc->remain_len = 112; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_VENDOR_DRIVER_VERSION) { + rndis->query_cmplt.MessageLength = 0x0000001C; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x00001000; + + transc->remain_len = 28; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_MAXIMUM_FRAME_SIZE) { + rndis->query_cmplt.MessageLength = 0x0000001C; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x000005DC; + + transc->remain_len = 28; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_LINK_SPEED) { + rndis->query_cmplt.MessageLength = 0x0000001C; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x0001D4C0; + + transc->remain_len = 28; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_802_3_MAXIMUM_LIST_SIZE) { + rndis->query_cmplt.MessageLength = 0x0000001C; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x00000001; + + transc->remain_len = 28; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_MAXIMUM_SEND_PACKETS) { + rndis->query_cmplt.MessageLength = 0x00000018; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0xC0000001; + rndis->query_cmplt.InformationBufferLength = 0x00000000; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + + transc->remain_len = 24; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + }else if (rndis->query_msg->Oid == OID_802_3_CURRENT_ADDRESS) { + rndis->query_cmplt.MessageLength = 0x0000001E; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000006; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x0E0F0A02; // Low four bits of MAC address + rndis->query_cmplt.Oid_Num[1] = 0x0000060D; // Hight two bits of MAC address + + transc->remain_len = 30; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_802_3_PERMANENT_ADDRESS) { + rndis->query_cmplt.MessageLength = 0x0000001E; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000006; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x0E0F0A02; // Low four bits of MAC address + rndis->query_cmplt.Oid_Num[1] = 0x0000060D; // Hight two bits of MAC address + + transc->remain_len = 30; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_PHYSICAL_MEDIUM) { + rndis->query_cmplt.MessageLength = 0x0000001C; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x00000000; + + transc->remain_len = 28; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_MEDIA_CONNECT_STATUS) { + rndis->query_cmplt.MessageLength = 0x0000001C; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x00000000; + + transc->remain_len = 28; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_MAC_OPTIONS) { + rndis->query_cmplt.MessageLength = 0x0000001C; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x00000000; + + transc->remain_len = 28; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_MAXIMUM_TOTAL_SIZE) { + rndis->query_cmplt.MessageLength = 0x0000001C; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x000005EA; + + transc->remain_len = 28; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_XMIT_OK) { + rndis->query_cmplt.MessageLength = 0x00000048; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x00000001; /* ?????? */ + rndis->query_cmplt.Oid_Num[1] = 0x00000000; + rndis->query_cmplt.Oid_Num[2] = 0x05809990; + rndis->query_cmplt.Oid_Num[3] = 0xFFFFF800; + rndis->query_cmplt.Oid_Num[4] = 0x07C70DA0; + rndis->query_cmplt.Oid_Num[5] = 0xFFFFFA80; + rndis->query_cmplt.Oid_Num[6] = 0x0000000A; + rndis->query_cmplt.Oid_Num[7] = 0x00000000; + rndis->query_cmplt.Oid_Num[8] = 0x00000001; + rndis->query_cmplt.Oid_Num[9] = 0x00000001; + rndis->query_cmplt.Oid_Num[10] = 0x07C70DB8; + rndis->query_cmplt.Oid_Num[11] = 0xFFFFFA80; + + transc->remain_len = 72; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->query_msg->Oid == OID_GEN_RCV_OK) { + rndis->query_cmplt.MessageLength = 0x00000048; + rndis->query_cmplt.RequestId = rndis->query_msg->RequestId; + rndis->query_cmplt.Status = 0x00000000; + rndis->query_cmplt.InformationBufferLength = 0x00000004; + rndis->query_cmplt.InformationBufferOffset = 0x00000010; + rndis->query_cmplt.Oid_Num[0] = 0x00000001; + rndis->query_cmplt.Oid_Num[1] = 0x00000000; + rndis->query_cmplt.Oid_Num[2] = 0x05809990; + rndis->query_cmplt.Oid_Num[3] = 0xFFFFF800; + rndis->query_cmplt.Oid_Num[4] = 0x07C70DA0; + rndis->query_cmplt.Oid_Num[5] = 0xFFFFFA80; + rndis->query_cmplt.Oid_Num[6] = 0x0000000A; + rndis->query_cmplt.Oid_Num[7] = 0x00000000; + rndis->query_cmplt.Oid_Num[8] = 0x00000001; + rndis->query_cmplt.Oid_Num[9] = 0x00000001; + rndis->query_cmplt.Oid_Num[10] = 0x07C70DB8; + rndis->query_cmplt.Oid_Num[11] = 0xFFFFFA80; + + transc->remain_len = 72; + transc->xfer_buf = (uint8_t *)&rndis->query_cmplt; + usbd_ctl_send (udev); + } else if (rndis->set_msg->Oid == OID_GEN_CURRENT_PACKET_FILTER) { + rndis->set_cmplt.MessageLength = 0x00000010; + rndis->set_cmplt.RequestId = rndis->set_msg->RequestId; + rndis->set_cmplt.Status = 0x00000000; + + transc->remain_len = 16; + transc->xfer_buf = (uint8_t *)&rndis->set_cmplt; + usbd_ctl_send (udev); + + rndis_data_receive(udev); + + } else if (rndis->set_msg->Oid == OID_802_3_MULTICAST_LIST) { + rndis->set_cmplt.MessageLength = 0x00000010; + rndis->set_cmplt.RequestId = rndis->set_msg->RequestId; + rndis->set_cmplt.Status = 0x00000000; + + transc->remain_len = 16; + transc->xfer_buf = (uint8_t *)&rndis->set_cmplt; + usbd_ctl_send (udev); + +// rndis_data_receive(udev); + + } else if (rndis->keepalive_msg->MessageType == 0x00000008) { + rndis->keepalive_cmplt.MessageLength = 0x00000010; + rndis->keepalive_cmplt.RequestId = rndis->keepalive_msg->RequestId; + rndis->keepalive_cmplt.Status = 0x00000000; + + transc->remain_len = 16; + transc->xfer_buf = (uint8_t *)&rndis->keepalive_cmplt; + usbd_ctl_send (udev); + } + + memset(rndis->usb_enet_cmd.usb_enet_cmd_buffer , 0x00, 20); + + break; + + case SET_COMM_FEATURE: + /* no operation for this driver */ + break; + + case GET_COMM_FEATURE: + /* no operation for this driver */ + break; + + case CLEAR_COMM_FEATURE: + /* no operation for this driver */ + break; + + case SET_LINE_CODING: + /* no operation for this driver */ + break; + + case GET_LINE_CODING: + /* no operation for this driver */ + break; + + case SET_CONTROL_LINE_STATE: + /* no operation for this driver */ + break; + + case SEND_BREAK: + /* no operation for this driver */ + break; + + default: + break; + } + + return USBD_OK; +} + +/*! + \brief handle CDC ACM data + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier + \param[out] none + \retval USB device operation status +*/ +static uint8_t rndis_in (usb_dev *udev, uint8_t ep_num) +{ + usb_transc *transc = &udev->dev.transc_in[EP_ID(ep_num)]; + usbd_rndis_handler *rndis = (usbd_rndis_handler *)udev->dev.class_data[USBD_RNDIS_INTERFACE]; + + if ((transc->xfer_len % transc->max_len == 0) && (transc->xfer_len != 0)) { + usbd_ep_send (udev, ep_num, NULL, 0); + } else { + rndis->usb_to_enet.packet_sent = 1; + } + + return USBD_OK; +} + +/*! + \brief handle CDC ACM data + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier + \param[out] none + \retval USB device operation status +*/ +static uint8_t rndis_out (usb_dev *udev, uint8_t ep_num) +{ + usbd_rndis_handler *rndis = (usbd_rndis_handler *)udev->dev.class_data[USBD_RNDIS_INTERFACE]; + + rndis->usb_to_enet.receive_length = ((usb_core_driver *)udev)->dev.transc_out[ep_num].xfer_count; + + rndis_data_receive(udev); + + return USBD_OK; +} + +/*! + \brief send RNDIS Command + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +void rndis_cmd_send (usb_dev *udev, uint32_t len) +{ + usbd_rndis_handler *rndis = (usbd_rndis_handler *)udev->dev.class_data[USBD_RNDIS_INTERFACE]; + + if (len <= USB_RNDIS_DATA_PACKET_SIZE) { + usbd_ep_send (udev, RNDIS_CMD_EP, (uint8_t*)(rndis->usb_enet_cmd.usb_enet_response_available_buffer), len); + } +} + +/*! + \brief send CDC ACM data + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +void rndis_data_send (usb_dev *udev, uint32_t len) +{ + usbd_rndis_handler *rndis = (usbd_rndis_handler *)udev->dev.class_data[USBD_RNDIS_INTERFACE]; + + rndis->usb_to_enet.packet_sent = 0; + + usbd_ep_send (udev, RNDIS_DATA_IN_EP, rndis->enet_to_usb.ENET_USB_data_buffer, len); +} + +static void rndis_data_msg_handle (usb_dev *udev) +{ + usbd_rndis_handler *rndis = (usbd_rndis_handler *)udev->dev.class_data[USBD_RNDIS_INTERFACE]; + + if (rndis->usb_to_enet.receive_length > 0) { + if ((rndis->usb_to_enet.usb_data_buffer[0] == 0x01) && (rndis->usb_to_enet.usb_data_buffer[8] == 0x24)) { + rndis->package_msg = (rndis_package_msg_struct *)rndis->usb_to_enet.usb_data_buffer; + + if ((rndis->package_msg->MessageLength - rndis->package_msg->DataLength == 0x2C)){ + rndis->usb_to_enet.usb_data_len = rndis->package_msg->DataLength; + + rndis->usb_to_enet.USB_enet_data_length = rndis->usb_to_enet.receive_length - 44; + + memcpy(rndis->usb_to_enet.USB_enet_data_buffer, &rndis->usb_to_enet.usb_data_buffer[44], rndis->usb_to_enet.USB_enet_data_length); + } + } else { + memcpy(rndis->usb_to_enet.USB_enet_data_buffer + rndis->usb_to_enet.USB_enet_data_length, rndis->usb_to_enet.usb_data_buffer, rndis->usb_to_enet.receive_length); + + rndis->usb_to_enet.USB_enet_data_length += rndis->usb_to_enet.receive_length; + } + } + + + if ((rndis->usb_to_enet.USB_enet_data_length == rndis->usb_to_enet.usb_data_len) && (rndis->usb_to_enet.USB_enet_data_length > 0)) { + low_level_output(rndis->usb_to_enet.USB_enet_data_buffer, rndis->usb_to_enet.USB_enet_data_length); + + rndis->usb_to_enet.USB_enet_data_length = 0; + + rndis->usb_to_enet.receive_length = 0; + + } +} + +/*! + \brief receive CDC ACM data + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation status +*/ +void rndis_data_receive (usb_dev *udev) +{ + usbd_rndis_handler *rndis = (usbd_rndis_handler *)udev->dev.class_data[USBD_RNDIS_INTERFACE]; + + usbd_ep_recev(udev, RNDIS_DATA_OUT_EP, (uint8_t*)(rndis->usb_to_enet.usb_data_buffer), USB_RNDIS_DATA_PACKET_SIZE); + + rndis_data_msg_handle(udev); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_core.h new file mode 100644 index 0000000..0847d17 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_core.h @@ -0,0 +1,103 @@ +/*! + \file usbd_core.h + \brief USB device mode core functions prototype + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBD_CORE_H +#define __USBD_CORE_H + +#include "drv_usb_core.h" +#include "drv_usb_dev.h" + +typedef enum +{ + USBD_OK = 0U, /*!< status OK */ + USBD_BUSY, /*!< status busy */ + USBD_FAIL /*!< status fail */ +} usbd_status; + +enum _usbd_status { + USBD_DEFAULT = 1U, /*!< default status */ + USBD_ADDRESSED = 2U, /*!< address send status */ + USBD_CONFIGURED = 3U, /*!< configured status */ + USBD_SUSPENDED = 4U /*!< suspended status */ +}; + +/* static inline function definitions */ + +/*! + \brief set USB device address + \param[in] udev: pointer to USB core instance + \param[in] addr: device address to set + \param[out] none + \retval none +*/ +__STATIC_INLINE void usbd_addr_set (usb_core_driver *udev, uint8_t addr) +{ + usb_devaddr_set(udev, addr); +} + +/*! + \brief get the received data length + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint number + \param[out] none + \retval USB device operation cur_status +*/ +__STATIC_INLINE uint16_t usbd_rxcount_get (usb_core_driver *udev, uint8_t ep_num) +{ + return (uint16_t)udev->dev.transc_out[ep_num].xfer_count; +} + +/* function declarations */ +/* initializes the USB device-mode stack and load the class driver */ +void usbd_init (usb_core_driver *udev, usb_core_enum core, usb_desc *desc, usb_class_core *class_core); +/* endpoint initialization */ +uint32_t usbd_ep_setup (usb_core_driver *udev, const usb_desc_ep *ep_desc); +/* configure the endpoint when it is disabled */ +uint32_t usbd_ep_clear (usb_core_driver *udev, uint8_t ep_addr); +/* endpoint prepare to receive data */ +uint32_t usbd_ep_recev (usb_core_driver *udev, uint8_t ep_addr, uint8_t *pbuf, uint32_t len); +/* endpoint prepare to transmit data */ +uint32_t usbd_ep_send (usb_core_driver *udev, uint8_t ep_addr, uint8_t *pbuf, uint32_t len); +/* set an endpoint to STALL status */ +uint32_t usbd_ep_stall (usb_core_driver *udev, uint8_t ep_addr); +/* clear endpoint STALLed status */ +uint32_t usbd_ep_stall_clear (usb_core_driver *udev, uint8_t ep_addr); +/* flush the endpoint FIFOs */ +uint32_t usbd_fifo_flush (usb_core_driver *udev, uint8_t ep_addr); +/* device connect */ +void usbd_connect (usb_core_driver *udev); +/* device disconnect */ +void usbd_disconnect (usb_core_driver *udev); + +#endif /* __USBD_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_enum.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_enum.h new file mode 100644 index 0000000..169edae --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_enum.h @@ -0,0 +1,105 @@ +/*! + \file usbd_enum.h + \brief USB enumeration definitions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBD_ENUM_H +#define __USBD_ENUM_H + +#include "usbd_core.h" +#include "usbd_conf.h" +#include + +#ifndef NULL + #define NULL 0U +#endif + +typedef enum _usb_reqsta { + REQ_SUPP = 0x0U, /* request support */ + REQ_NOTSUPP = 0x1U, /* request not support */ +} usb_reqsta; + +/* string descriptor index */ +enum _str_index +{ + STR_IDX_LANGID = 0x0U, /* language ID string index */ + STR_IDX_MFC = 0x1U, /* manufacturer string index */ + STR_IDX_PRODUCT = 0x2U, /* product string index */ + STR_IDX_SERIAL = 0x3U, /* serial string index */ + STR_IDX_CONFIG = 0x4U, /* configuration string index */ + STR_IDX_ITF = 0x5U, /* interface string index */ +#ifndef WINUSB_EXEMPT_DRIVER + STR_IDX_MAX = 0xAU, /* string maximum index */ +#else + STR_IDX_MAX = 0xEFU, /* string maximum index */ +#endif /* WINUSB_EXEMPT_DRIVER */ +}; + +typedef enum _usb_pwrsta { + USB_PWRSTA_SELF_POWERED = 0x1U, /* USB is in self powered status */ + USB_PWRSTA_REMOTE_WAKEUP = 0x2U, /* USB is in remote wakeup status */ +} usb_pwrsta; + +typedef enum _usb_feature +{ + USB_FEATURE_EP_HALT = 0x0U, /* USB has endpoint halt feature */ + USB_FEATURE_REMOTE_WAKEUP = 0x1U, /* USB has endpoint remote wakeup feature */ + USB_FEATURE_TEST_MODE = 0x2U, /* USB has endpoint test mode feature */ +} usb_feature; + +#define ENG_LANGID 0x0409U /* english language ID */ +#define CHN_LANGID 0x0804U /* chinese language ID */ + +/* USB device exported macros */ +#define CTL_EP(ep) (((ep) == 0x00U) || ((ep) == 0x80U)) + +#define DEVICE_ID1 (0x1FFF7A1BU) /* device ID1 */ +#define DEVICE_ID2 (0x1FFF7A1FU) /* device ID2 */ +#define DEVICE_ID3 (0x1FFF7A23U) /* device ID3 */ + +#define DEVICE_ID (0x40023D00U) + +/* function declarations */ +/* handle USB standard device request */ +usb_reqsta usbd_standard_request (usb_core_driver *udev, usb_req *req); +/* handle USB device class request */ +usb_reqsta usbd_class_request (usb_core_driver *udev, usb_req *req); +/* handle USB vendor request */ +usb_reqsta usbd_vendor_request (usb_core_driver *udev, usb_req *req); +/* handle USB enumeration error */ +void usbd_enum_error (usb_core_driver *udev, usb_req *req); +/* convert hex 32bits value into unicode char */ +void int_to_unicode (uint32_t value, uint8_t *pbuf, uint8_t len); +/* get serial string */ +void serial_string_get (uint16_t *unicode_str); + +#endif /* __USBD_ENUM_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_transc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_transc.h new file mode 100644 index 0000000..4a8368a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Include/usbd_transc.h @@ -0,0 +1,56 @@ +/*! + \file usbd_transc.h + \brief USB transaction core functions prototype + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBD_TRANSC_H +#define __USBD_TRANSC_H + +#include "usbd_core.h" + +/* function declarations */ +/* USB send data in the control transaction */ +usbd_status usbd_ctl_send (usb_core_driver *udev); +/* USB receive data in control transaction */ +usbd_status usbd_ctl_recev (usb_core_driver *udev); +/* USB send control transaction status */ +usbd_status usbd_ctl_status_send (usb_core_driver *udev); +/* USB control receive status */ +usbd_status usbd_ctl_status_recev (usb_core_driver *udev); +/* USB setup stage processing */ +uint8_t usbd_setup_transc (usb_core_driver *udev); +/* data out stage processing */ +uint8_t usbd_out_transc (usb_core_driver *udev, uint8_t ep_num); +/* data in stage processing */ +uint8_t usbd_in_transc (usb_core_driver *udev, uint8_t ep_num); + +#endif /* __USBD_TRANSC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_core.c new file mode 100644 index 0000000..5f94430 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_core.c @@ -0,0 +1,320 @@ +/*! + \file usbd_core.c + \brief USB device mode core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbd_core.h" +#include "usbd_enum.h" +#include "drv_usb_hw.h" + +/* endpoint type */ +const uint32_t ep_type[] = { + [USB_EP_ATTR_CTL] = (uint32_t)USB_EPTYPE_CTRL, + [USB_EP_ATTR_BULK] = (uint32_t)USB_EPTYPE_BULK, + [USB_EP_ATTR_INT] = (uint32_t)USB_EPTYPE_INTR, + [USB_EP_ATTR_ISO] = (uint32_t)USB_EPTYPE_ISOC +}; + +/*! + \brief initializes the USB device-mode stack and load the class driver + \param[in] udev: pointer to USB core instance + \param[in] core: USB core type + \param[in] desc: pointer to USB descriptor + \param[in] class_core: class driver + \param[out] none + \retval none +*/ +void usbd_init (usb_core_driver *udev, usb_core_enum core, usb_desc *desc, usb_class_core *class_core) +{ + udev->dev.desc = desc; + + /* class callbacks */ + udev->dev.class_core = class_core; + + /* create serial string */ + serial_string_get(udev->dev.desc->strings[STR_IDX_SERIAL]); + + /* configure USB capabilities */ + (void)usb_basic_init (&udev->bp, &udev->regs, core); + + usb_globalint_disable(&udev->regs); + + /* initializes the USB core*/ + (void)usb_core_init (udev->bp, &udev->regs); + + /* set device disconnect */ + usbd_disconnect (udev); + +#ifndef USE_OTG_MODE + usb_curmode_set(&udev->regs, DEVICE_MODE); +#endif /* USE_OTG_MODE */ + + /* initializes device mode */ + (void)usb_devcore_init (udev); + + usb_globalint_enable(&udev->regs); + + /* set device connect */ + usbd_connect (udev); + + udev->dev.cur_status = (uint8_t)USBD_DEFAULT; +} + +/*! + \brief endpoint initialization + \param[in] udev: pointer to USB core instance + \param[in] ep_desc: pointer to endpoint descriptor + \param[out] none + \retval none +*/ +uint32_t usbd_ep_setup (usb_core_driver *udev, const usb_desc_ep *ep_desc) +{ + usb_transc *transc; + + uint8_t ep_addr = ep_desc->bEndpointAddress; + uint16_t max_len = ep_desc->wMaxPacketSize; + + /* set endpoint direction */ + if (EP_DIR(ep_addr)) { + transc = &udev->dev.transc_in[EP_ID(ep_addr)]; + + transc->ep_addr.dir = 1U; + } else { + transc = &udev->dev.transc_out[ep_addr]; + + transc->ep_addr.dir = 0U; + } + + transc->ep_addr.num = EP_ID(ep_addr); + transc->max_len = max_len; + transc->ep_type = (uint8_t)ep_type[ep_desc->bmAttributes & (uint8_t)USB_EPTYPE_MASK]; + + /* active USB endpoint function */ + (void)usb_transc_active (udev, transc); + + return 0U; +} + +/*! + \brief configure the endpoint when it is disabled + \param[in] udev: pointer to USB core instance + \param[in] ep_addr: endpoint address + in this parameter: + bit0..bit6: endpoint number (0..7) + bit7: endpoint direction which can be IN(1) or OUT(0) + \param[out] none + \retval none +*/ +uint32_t usbd_ep_clear (usb_core_driver *udev, uint8_t ep_addr) +{ + usb_transc *transc; + + if (EP_DIR(ep_addr)) { + transc = &udev->dev.transc_in[EP_ID(ep_addr)]; + } else { + transc = &udev->dev.transc_out[ep_addr]; + } + + /* deactivate USB endpoint function */ + (void)usb_transc_deactivate (udev, transc); + + return 0U; +} + +/*! + \brief endpoint prepare to receive data + \param[in] udev: pointer to USB core instance + \param[in] ep_addr: endpoint address + in this parameter: + bit0..bit6: endpoint number (0..7) + bit7: endpoint direction which can be IN(1) or OUT(0) + \param[in] pbuf: user buffer address pointer + \param[in] len: buffer length + \param[out] none + \retval none +*/ +uint32_t usbd_ep_recev (usb_core_driver *udev, uint8_t ep_addr, uint8_t *pbuf, uint32_t len) +{ + usb_transc *transc = &udev->dev.transc_out[EP_ID(ep_addr)]; + + /* setup the transfer */ + transc->xfer_buf = pbuf; + transc->xfer_len = len; + transc->xfer_count = 0U; + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + transc->dma_addr = (uint32_t)pbuf; + } + + /* start the transfer */ + (void)usb_transc_outxfer (udev, transc); + + return 0U; +} + +/*! + \brief endpoint prepare to transmit data + \param[in] udev: pointer to USB core instance + \param[in] ep_addr: endpoint address + in this parameter: + bit0..bit6: endpoint number (0..7) + bit7: endpoint direction which can be IN(1) or OUT(0) + \param[in] pbuf: transmit buffer address pointer + \param[in] len: buffer length + \param[out] none + \retval none +*/ +uint32_t usbd_ep_send (usb_core_driver *udev, uint8_t ep_addr, uint8_t *pbuf, uint32_t len) +{ + usb_transc *transc = &udev->dev.transc_in[EP_ID(ep_addr)]; + + /* setup the transfer */ + transc->xfer_buf = pbuf; + transc->xfer_len = len; + transc->xfer_count = 0U; + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + transc->dma_addr = (uint32_t)pbuf; + } + + /* start the transfer */ + (void)usb_transc_inxfer (udev, transc); + + return 0U; +} + +/*! + \brief set an endpoint to STALL status + \param[in] udev: pointer to USB core instance + \param[in] ep_addr: endpoint address + in this parameter: + bit0..bit6: endpoint number (0..7) + bit7: endpoint direction which can be IN(1) or OUT(0) + \param[out] none + \retval none +*/ +uint32_t usbd_ep_stall (usb_core_driver *udev, uint8_t ep_addr) +{ + usb_transc *transc = NULL; + + if (EP_DIR(ep_addr)) { + transc = &udev->dev.transc_in[EP_ID(ep_addr)]; + } else { + transc = &udev->dev.transc_out[ep_addr]; + } + + transc->ep_stall = 1U; + + (void)usb_transc_stall (udev, transc); + + return (0U); +} + +/*! + \brief clear endpoint STALLed status + \param[in] udev: pointer to USB core instance + \param[in] ep_addr: endpoint address + in this parameter: + bit0..bit6: endpoint number (0..7) + bit7: endpoint direction which can be IN(1) or OUT(0) + \param[out] none + \retval none +*/ +uint32_t usbd_ep_stall_clear (usb_core_driver *udev, uint8_t ep_addr) +{ + usb_transc *transc = NULL; + + if (EP_DIR(ep_addr)) { + transc = &udev->dev.transc_in[EP_ID(ep_addr)]; + } else { + transc = &udev->dev.transc_out[ep_addr]; + } + + transc->ep_stall = 0U; + + (void)usb_transc_clrstall (udev, transc); + + return (0U); +} + +/*! + \brief flush the endpoint FIFOs + \param[in] udev: pointer to USB core instance + \param[in] ep_addr: endpoint address + in this parameter: + bit0..bit6: endpoint number (0..7) + bit7: endpoint direction which can be IN(1) or OUT(0) + \param[out] none + \retval none +*/ +uint32_t usbd_fifo_flush (usb_core_driver *udev, uint8_t ep_addr) +{ + if (EP_DIR(ep_addr)) { + (void)usb_txfifo_flush (&udev->regs, EP_ID(ep_addr)); + } else { + (void)usb_rxfifo_flush (&udev->regs); + } + + return (0U); +} + +/*! + \brief device connect + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +void usbd_connect (usb_core_driver *udev) +{ +#ifndef USE_OTG_MODE + /* connect device */ + usb_dev_connect (udev); + + usb_mdelay(3U); +#endif /* USE_OTG_MODE */ +} + +/*! + \brief device disconnect + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +void usbd_disconnect (usb_core_driver *udev) +{ +#ifndef USE_OTG_MODE + /* disconnect device for 3ms */ + usb_dev_disconnect (udev); + + usb_mdelay(3U); +#endif /* USE_OTG_MODE */ +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_enum.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_enum.c new file mode 100644 index 0000000..63925ed --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_enum.c @@ -0,0 +1,818 @@ +/*! + \file usbd_enum.c + \brief USB enumeration function + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbd_enum.h" +#include "usb_ch9_std.h" + +#ifdef WINUSB_EXEMPT_DRIVER + +extern usbd_status usbd_OEM_req(usb_dev *udev, usb_req *req); + +#endif /* WINUSB_EXEMPT_DRIVER */ + +/* local function prototypes ('static') */ +static usb_reqsta _usb_std_reserved (usb_core_driver *udev, usb_req *req); +static uint8_t* _usb_dev_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len); +static uint8_t* _usb_config_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len); +#if defined(USE_USB_HS) && defined(USE_ULPI_PHY) +static uint8_t* _usb_other_speed_config_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len); +static uint8_t* _usb_qualifier_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len); +#endif +static uint8_t* _usb_bos_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len); +static uint8_t* _usb_str_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len); +static usb_reqsta _usb_std_getstatus (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_clearfeature (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_setfeature (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_setaddress (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_getdescriptor (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_setdescriptor (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_getconfiguration (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_setconfiguration (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_getinterface (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_setinterface (usb_core_driver *udev, usb_req *req); +static usb_reqsta _usb_std_synchframe (usb_core_driver *udev, usb_req *req); + +static usb_reqsta (*_std_dev_req[])(usb_core_driver *udev, usb_req *req) = +{ + [USB_GET_STATUS] = _usb_std_getstatus, + [USB_CLEAR_FEATURE] = _usb_std_clearfeature, + [USB_RESERVED2] = _usb_std_reserved, + [USB_SET_FEATURE] = _usb_std_setfeature, + [USB_RESERVED4] = _usb_std_reserved, + [USB_SET_ADDRESS] = _usb_std_setaddress, + [USB_GET_DESCRIPTOR] = _usb_std_getdescriptor, + [USB_SET_DESCRIPTOR] = _usb_std_setdescriptor, + [USB_GET_CONFIGURATION] = _usb_std_getconfiguration, + [USB_SET_CONFIGURATION] = _usb_std_setconfiguration, + [USB_GET_INTERFACE] = _usb_std_getinterface, + [USB_SET_INTERFACE] = _usb_std_setinterface, + [USB_SYNCH_FRAME] = _usb_std_synchframe, +}; + +/* get standard descriptor handler */ +static uint8_t* (*std_desc_get[])(usb_core_driver *udev, uint8_t index, uint16_t *len) = { + [(uint8_t)USB_DESCTYPE_DEV - 1U] = _usb_dev_desc_get, + [(uint8_t)USB_DESCTYPE_CONFIG - 1U] = _usb_config_desc_get, + [(uint8_t)USB_DESCTYPE_STR - 1U] = _usb_str_desc_get, +#if defined(USE_USB_HS) && defined(USE_ULPI_PHY) + [(uint8_t)USB_DESCTYPE_DEV_QUALIFIER - 3U] = _usb_qualifier_desc_get, + [(uint8_t)USB_DESCTYPE_OTHER_SPD_CONFIG - 3U] = _usb_other_speed_config_desc_get, +#endif +}; + +/*! + \brief handle USB standard device request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +usb_reqsta usbd_standard_request (usb_core_driver *udev, usb_req *req) +{ + return (*_std_dev_req[req->bRequest])(udev, req); +} + +/*! + \brief handle USB device class request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device class request + \param[out] none + \retval USB device request status +*/ +usb_reqsta usbd_class_request (usb_core_driver *udev, usb_req *req) +{ + if ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) { + if (BYTE_LOW(req->wIndex) <= USBD_ITF_MAX_NUM) { + /* call device class handle function */ + return (usb_reqsta)udev->dev.class_core->req_proc(udev, req); + } + } + + return REQ_NOTSUPP; +} + +/*! + \brief handle USB vendor request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB vendor request + \param[out] none + \retval USB device request status +*/ +usb_reqsta usbd_vendor_request (usb_core_driver *udev, usb_req *req) +{ + (void)udev; + (void)req; + + /* added by user... */ +#ifdef WINUSB_EXEMPT_DRIVER + usbd_OEM_req(udev, req); +#endif + + return REQ_SUPP; +} + +/*! + \brief handle USB enumeration error + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval none +*/ +void usbd_enum_error (usb_core_driver *udev, usb_req *req) +{ + (void)req; + + (void)usbd_ep_stall (udev, 0x80U); + (void)usbd_ep_stall (udev, 0x00U); + + usb_ctlep_startout(udev); +} + +/*! + \brief convert hex 32bits value into unicode char + \param[in] value: hex 32bits value + \param[in] pbuf: buffer pointer to store unicode char + \param[in] len: value length + \param[out] none + \retval none +*/ +void int_to_unicode (uint32_t value, uint8_t *pbuf, uint8_t len) +{ + uint8_t index; + + for (index = 0U; index < len; index++) { + if ((value >> 28U) < 0x0AU) { + pbuf[2U * index] = (uint8_t)((value >> 28U) + '0'); + } else { + pbuf[2U * index] = (uint8_t)((value >> 28U) + 'A' - 10U); + } + + value = value << 4U; + + pbuf[2U * index + 1U] = 0U; + } +} + +/*! + \brief convert hex 32bits value into unicode char + \param[in] unicode_str: pointer to unicode string + \param[out] none + \retval none +*/ +void serial_string_get (uint16_t *unicode_str) +{ + if ((unicode_str[0] & 0x00FFU) != 6U) { + uint32_t DeviceSerial0, DeviceSerial1, DeviceSerial2; + + DeviceSerial0 = *(uint32_t*)DEVICE_ID1; + DeviceSerial1 = *(uint32_t*)DEVICE_ID2; + DeviceSerial2 = *(uint32_t*)DEVICE_ID3; + + DeviceSerial0 += DeviceSerial2; + + if (0U != DeviceSerial0) { + int_to_unicode(DeviceSerial0, (uint8_t*)&(unicode_str[1]), 8U); + int_to_unicode(DeviceSerial1, (uint8_t*)&(unicode_str[9]), 4U); + } + } else { + uint32_t device_serial = *(uint32_t*)DEVICE_ID; + + if(0U != device_serial) { + unicode_str[1] = (uint16_t)(device_serial & 0x0000FFFFU); + unicode_str[2] = (uint16_t)((device_serial & 0xFFFF0000U) >> 16U); + + } + } +} + +/*! + \brief no operation, just for reserved + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB vendor request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_reserved (usb_core_driver *udev, usb_req *req) +{ + (void)udev; + (void)req; + + /* no operation... */ + + return REQ_NOTSUPP; +} + +/*! + \brief get the device descriptor + \param[in] udev: pointer to USB device instance + \param[in] index: no use + \param[out] len: data length pointer + \retval descriptor buffer pointer +*/ +static uint8_t* _usb_dev_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len) +{ + (void)index; + + *len = udev->dev.desc->dev_desc[0]; + + return udev->dev.desc->dev_desc; +} + +/*! + \brief get the configuration descriptor + \brief[in] udev: pointer to USB device instance + \brief[in] index: no use + \param[out] len: data length pointer + \retval descriptor buffer pointer +*/ +static uint8_t* _usb_config_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len) +{ + (void)index; + + *len = udev->dev.desc->config_desc[2] | (udev->dev.desc->config_desc[3]<< 8U); + + return udev->dev.desc->config_desc; +} + +#if defined(USE_USB_HS) && defined(USE_ULPI_PHY) + +/*! + \brief get the other speed configuration descriptor + \brief[in] udev: pointer to USB device instance + \brief[in] index: no use + \param[out] len: data length pointer + \retval descriptor buffer pointer +*/ +static uint8_t* _usb_other_speed_config_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len) +{ + (void)index; + + *len = udev->dev.desc->other_speed_config_desc[2]; + + return udev->dev.desc->other_speed_config_desc; +} + +/*! + \brief get the other speed configuration descriptor + \brief[in] udev: pointer to USB device instance + \brief[in] index: no use + \param[out] len: data length pointer + \retval descriptor buffer pointer +*/ +static uint8_t* _usb_qualifier_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len) +{ + (void)index; + + *len = udev->dev.desc->qualifier_desc[0]; + + return udev->dev.desc->qualifier_desc; +} + +#endif /* USE_USB_HS && USE_ULPI_PHY */ + +/*! + \brief get the BOS descriptor + \brief[in] udev: pointer to USB device instance + \brief[in] index: no use + \param[out] len: data length pointer + \retval descriptor buffer pointer +*/ +static uint8_t* _usb_bos_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len) +{ + (void)index; + + *len = udev->dev.desc->bos_desc[2]; + + return udev->dev.desc->bos_desc; +} + +/*! + \brief get string descriptor + \param[in] udev: pointer to USB device instance + \param[in] index: string descriptor index + \param[out] len: pointer to string length + \retval descriptor buffer pointer +*/ +static uint8_t* _usb_str_desc_get (usb_core_driver *udev, uint8_t index, uint16_t *len) +{ + uint8_t *desc = udev->dev.desc->strings[index]; + + *len = desc[0]; + + return desc; +} + +/*! + \brief handle Get_Status request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_getstatus (usb_core_driver *udev, usb_req *req) +{ + uint8_t recp = BYTE_LOW(req->wIndex); + usb_reqsta req_status = REQ_NOTSUPP; + usb_transc *transc = &udev->dev.transc_in[0]; + + static uint8_t status[2] = {0}; + + switch(req->bmRequestType & (uint8_t)USB_RECPTYPE_MASK) { + case USB_RECPTYPE_DEV: + if (((uint8_t)USBD_ADDRESSED == udev->dev.cur_status) || \ + ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status)) { + + if (udev->dev.pm.power_mode) { + status[0] = USB_STATUS_SELF_POWERED; + } else { + status[0] = 0U; + } + + if (udev->dev.pm.dev_remote_wakeup) { + status[0] |= USB_STATUS_REMOTE_WAKEUP; + } else { + status[0] = 0U; + } + + req_status = REQ_SUPP; + } + break; + + case USB_RECPTYPE_ITF: + if (((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) && (recp <= USBD_ITF_MAX_NUM)) { + req_status = REQ_SUPP; + } + break; + + case USB_RECPTYPE_EP: + if ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) { + if (0x80U == (recp & 0x80U)) { + status[0] = udev->dev.transc_in[EP_ID(recp)].ep_stall; + } else { + status[0] = udev->dev.transc_out[recp].ep_stall; + } + + req_status = REQ_SUPP; + } + break; + + default: + break; + } + + if (REQ_SUPP == req_status) { + transc->xfer_buf = status; + transc->remain_len = 2U; + } + + return req_status; +} + +/*! + \brief handle USB Clear_Feature request + \param[in] udev: pointer to USB device instance + \param[in] req: USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_clearfeature (usb_core_driver *udev, usb_req *req) +{ + uint8_t ep = 0U; + + switch(req->bmRequestType & (uint8_t)USB_RECPTYPE_MASK) { + case USB_RECPTYPE_DEV: + if (((uint8_t)USBD_ADDRESSED == udev->dev.cur_status) || \ + ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status)) { + + /* clear device remote wakeup feature */ + if ((uint16_t)USB_FEATURE_REMOTE_WAKEUP == req->wValue) { + udev->dev.pm.dev_remote_wakeup = 0U; + + return REQ_SUPP; + } + } + break; + + case USB_RECPTYPE_ITF: + break; + + case USB_RECPTYPE_EP: + /* get endpoint address */ + ep = BYTE_LOW(req->wIndex); + + if ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) { + /* clear endpoint halt feature */ + if (((uint16_t)USB_FEATURE_EP_HALT == req->wValue) && (!CTL_EP(ep))) { + (void)usbd_ep_stall_clear (udev, ep); + + (void)udev->dev.class_core->req_proc (udev, req); + } + + return REQ_SUPP; + } + break; + + default: + break; + } + + return REQ_NOTSUPP; +} + +/*! + \brief handle USB Set_Feature request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_setfeature (usb_core_driver *udev, usb_req *req) +{ + uint8_t ep = 0U; + + switch (req->bmRequestType & (uint8_t)USB_RECPTYPE_MASK) { + case USB_RECPTYPE_DEV: + if (((uint8_t)USBD_ADDRESSED == udev->dev.cur_status) || \ + ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status)) { + /* set device remote wakeup feature */ + if ((uint16_t)USB_FEATURE_REMOTE_WAKEUP == req->wValue) { + udev->dev.pm.dev_remote_wakeup = 1U; + } + + return REQ_SUPP; + } + break; + + case USB_RECPTYPE_ITF: + break; + + case USB_RECPTYPE_EP: + /* get endpoint address */ + ep = BYTE_LOW(req->wIndex); + + if ((uint8_t)USBD_CONFIGURED == udev->dev.cur_status) { + /* set endpoint halt feature */ + if (((uint16_t)USB_FEATURE_EP_HALT == req->wValue) && (!CTL_EP(ep))) { + (void)usbd_ep_stall (udev, ep); + } + + return REQ_SUPP; + } + break; + + default: + break; + } + + return REQ_NOTSUPP; +} + +/*! + \brief handle USB Set_Address request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_setaddress (usb_core_driver *udev, usb_req *req) +{ + if ((0U == req->wIndex) && (0U == req->wLength)) { + udev->dev.dev_addr = (uint8_t)(req->wValue) & 0x7FU; + + if (udev->dev.cur_status != (uint8_t)USBD_CONFIGURED) { + usbd_addr_set (udev, udev->dev.dev_addr); + + if (udev->dev.dev_addr) { + udev->dev.cur_status = (uint8_t)USBD_ADDRESSED; + } else { + udev->dev.cur_status = (uint8_t)USBD_DEFAULT; + } + + return REQ_SUPP; + } + } + + return REQ_NOTSUPP; +} + +/*! + \brief handle USB Get_Descriptor request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_getdescriptor (usb_core_driver *udev, usb_req *req) +{ + uint8_t desc_type = 0U; + uint8_t desc_index = 0U; + + usb_reqsta status = REQ_NOTSUPP; + + usb_transc *transc = &udev->dev.transc_in[0]; + + /* get device standard descriptor */ + switch (req->bmRequestType & USB_RECPTYPE_MASK) { + case USB_RECPTYPE_DEV: + desc_type = BYTE_HIGH(req->wValue); + desc_index = BYTE_LOW(req->wValue); + + switch (desc_type) { + case USB_DESCTYPE_DEV: + transc->xfer_buf = std_desc_get[desc_type - 1U](udev, desc_index, (uint16_t *)&(transc->remain_len)); + + if (64U == req->wLength) { + transc->remain_len = 8U; + } + break; + + case USB_DESCTYPE_CONFIG: + transc->xfer_buf = std_desc_get[desc_type - 1U](udev, desc_index, (uint16_t *)&(transc->remain_len)); + break; + + case USB_DESCTYPE_STR: + if (desc_index < (uint8_t)STR_IDX_MAX) { + transc->xfer_buf = std_desc_get[desc_type - 1U](udev, desc_index, (uint16_t *)&(transc->remain_len)); + } + break; + + case USB_DESCTYPE_ITF: + case USB_DESCTYPE_EP: + break; + +#if defined(USE_USB_HS) && defined(USE_ULPI_PHY) + case USB_DESCTYPE_DEV_QUALIFIER: + transc->xfer_buf = std_desc_get[desc_type - 3U](udev, desc_index, (uint16_t *)&(transc->remain_len)); + break; + + case USB_DESCTYPE_OTHER_SPD_CONFIG: + transc->xfer_buf = std_desc_get[desc_type - 3U](udev, desc_index, (uint16_t *)&(transc->remain_len)); + break; +#endif + + case USB_DESCTYPE_ITF_POWER: + break; + + case USB_DESCTYPE_BOS: + transc->xfer_buf = _usb_bos_desc_get(udev, desc_index, (uint16_t *)&(transc->remain_len)); + break; + + default: + break; + } + break; + + case USB_RECPTYPE_ITF: + /* get device class special descriptor */ + status = (usb_reqsta)(udev->dev.class_core->req_proc(udev, req)); + break; + + case USB_RECPTYPE_EP: + break; + + default: + break; + } + + if ((0U != transc->remain_len) && (0U != req->wLength)) { + if (transc->remain_len < req->wLength) { + if ((transc->remain_len >= transc->max_len) && (0U == (transc->remain_len % transc->max_len))) { + udev->dev.control.ctl_zlp = 1U; + } + } else { + transc->remain_len = req->wLength; + } + + status = REQ_SUPP; + } + + return status; +} + +/*! + \brief handle USB Set_Descriptor request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_setdescriptor (usb_core_driver *udev, usb_req *req) +{ + (void)udev; + (void)req; + + /* no handle... */ + return REQ_SUPP; +} + +/*! + \brief handle USB Get_Configuration request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_getconfiguration (usb_core_driver *udev, usb_req *req) +{ + (void)req; + + usb_reqsta req_status = REQ_NOTSUPP; + usb_transc *transc = &udev->dev.transc_in[0]; + + switch (udev->dev.cur_status) { + case USBD_ADDRESSED: + if (USB_DEFAULT_CONFIG == udev->dev.config) { + req_status = REQ_SUPP; + } + break; + + case USBD_CONFIGURED: + if (udev->dev.config != USB_DEFAULT_CONFIG) { + req_status = REQ_SUPP; + } + break; + + default: + break; + } + + if (REQ_SUPP == req_status) { + transc->xfer_buf = &(udev->dev.config); + transc->remain_len = 1U; + } + + return req_status; +} + +/*! + \brief handle USB Set_Configuration request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_setconfiguration (usb_core_driver *udev, usb_req *req) +{ + static uint8_t config; + usb_reqsta status = REQ_NOTSUPP; + + config = (uint8_t)(req->wValue); + + if (config <= USBD_CFG_MAX_NUM) { + switch (udev->dev.cur_status) { + case USBD_ADDRESSED: + if (config){ + (void)udev->dev.class_core->init(udev, config); + + udev->dev.config = config; + udev->dev.cur_status = (uint8_t)USBD_CONFIGURED; + } + + status = REQ_SUPP; + break; + + case USBD_CONFIGURED: + if (USB_DEFAULT_CONFIG == config) { + (void)udev->dev.class_core->deinit(udev, config); + + udev->dev.config = config; + udev->dev.cur_status = (uint8_t)USBD_ADDRESSED; + } else if (config != udev->dev.config) { + /* clear old configuration */ + (void)udev->dev.class_core->deinit(udev, config); + + /* set new configuration */ + udev->dev.config = config; + + (void)udev->dev.class_core->init(udev, config); + } else { + /* no operation */ + } + + status = REQ_SUPP; + break; + + case USBD_DEFAULT: + break; + + default: + break; + } + } + + return status; +} + +/*! + \brief handle USB Get_Interface request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_getinterface (usb_core_driver *udev, usb_req *req) +{ + switch (udev->dev.cur_status) { + case USBD_DEFAULT: + break; + + case USBD_ADDRESSED: + break; + + case USBD_CONFIGURED: + if (BYTE_LOW(req->wIndex) <= USBD_ITF_MAX_NUM) { + usb_transc *transc = &udev->dev.transc_in[0]; + + transc->xfer_buf = &(udev->dev.class_core->alter_set); + transc->remain_len = 1U; + + return REQ_SUPP; + } + break; + + default: + break; + } + + return REQ_NOTSUPP; +} + +/*! + \brief handle USB Set_Interface request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_setinterface (usb_core_driver *udev, usb_req *req) +{ + switch (udev->dev.cur_status) { + case USBD_DEFAULT: + break; + + case USBD_ADDRESSED: + break; + + case USBD_CONFIGURED: + if (BYTE_LOW(req->wIndex) <= USBD_ITF_MAX_NUM) { + if (NULL != udev->dev.class_core->set_intf) { + (void)udev->dev.class_core->set_intf (udev, req); + } + + return REQ_SUPP; + } + break; + + default: + break; + } + + return REQ_NOTSUPP; +} + +/*! + \brief handle USB SynchFrame request + \param[in] udev: pointer to USB device instance + \param[in] req: pointer to USB device request + \param[out] none + \retval USB device request status +*/ +static usb_reqsta _usb_std_synchframe (usb_core_driver *udev, usb_req *req) +{ + (void)udev; + (void)req; + + /* no handle */ + return REQ_SUPP; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_transc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_transc.c new file mode 100644 index 0000000..25f0cd2 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/device/core/Source/usbd_transc.c @@ -0,0 +1,264 @@ +/*! + \file usbd_transc.c + \brief USB transaction core functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbd_enum.h" +#include "usbd_transc.h" + +/*! + \brief USB send data in the control transaction + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation cur_status +*/ +usbd_status usbd_ctl_send (usb_core_driver *udev) +{ + usb_transc *transc = &udev->dev.transc_in[0]; + + (void)usbd_ep_send(udev, 0U, transc->xfer_buf, transc->remain_len); + + if (transc->remain_len > transc->max_len) { + udev->dev.control.ctl_state = (uint8_t)USB_CTL_DATA_IN; + } else { + udev->dev.control.ctl_state = (uint8_t)USB_CTL_LAST_DATA_IN; + } + + return USBD_OK; +} + +/*! + \brief USB receive data in control transaction + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation cur_status +*/ +usbd_status usbd_ctl_recev (usb_core_driver *udev) +{ + usb_transc *transc = &udev->dev.transc_out[0]; + + (void)usbd_ep_recev (udev, 0U, transc->xfer_buf, transc->remain_len); + + if (transc->remain_len > transc->max_len) { + udev->dev.control.ctl_state = (uint8_t)USB_CTL_DATA_OUT; + } else { + udev->dev.control.ctl_state = (uint8_t)USB_CTL_LAST_DATA_OUT; + } + + return USBD_OK; +} + +/*! + \brief USB send control transaction status + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation cur_status +*/ +usbd_status usbd_ctl_status_send (usb_core_driver *udev) +{ + udev->dev.control.ctl_state = (uint8_t)USB_CTL_STATUS_IN; + + (void)usbd_ep_send (udev, 0U, NULL, 0U); + + usb_ctlep_startout(udev); + + return USBD_OK; +} + +/*! + \brief USB control receive status + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation cur_status +*/ +usbd_status usbd_ctl_status_recev (usb_core_driver *udev) +{ + udev->dev.control.ctl_state = (uint8_t)USB_CTL_STATUS_OUT; + + (void)usbd_ep_recev (udev, 0U, NULL, 0U); + + usb_ctlep_startout(udev); + + return USBD_OK; +} + +/*! + \brief USB setup stage processing + \param[in] udev: pointer to USB device instance + \param[out] none + \retval USB device operation cur_status +*/ +uint8_t usbd_setup_transc (usb_core_driver *udev) +{ + usb_reqsta reqstat = REQ_NOTSUPP; + + usb_req req = udev->dev.control.req; + + switch (req.bmRequestType & USB_REQTYPE_MASK) { + /* standard device request */ + case USB_REQTYPE_STRD: + reqstat = usbd_standard_request (udev, &req); + break; + + /* device class request */ + case USB_REQTYPE_CLASS: + reqstat = usbd_class_request (udev, &req); + break; + + /* vendor defined request */ + case USB_REQTYPE_VENDOR: + reqstat = usbd_vendor_request (udev, &req); + break; + + default: + break; + } + + if (REQ_SUPP == reqstat) { + if (0U == req.wLength) { + (void)usbd_ctl_status_send (udev); + } else { + if (req.bmRequestType & 0x80U) { + (void)usbd_ctl_send (udev); + } else { + (void)usbd_ctl_recev (udev); + } + } + } else { + usbd_enum_error (udev, &req); + } + + return (uint8_t)USBD_OK; +} + +/*! + \brief data out stage processing + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier(0..7) + \param[out] none + \retval USB device operation cur_status +*/ +uint8_t usbd_out_transc (usb_core_driver *udev, uint8_t ep_num) +{ + if (0U == ep_num) { + usb_transc *transc = &udev->dev.transc_out[0]; + + switch (udev->dev.control.ctl_state) { + case USB_CTL_DATA_OUT: + /* update transfer length */ + transc->remain_len -= transc->max_len; + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + transc->xfer_buf += transc->max_len; + } + + (void)usbd_ctl_recev (udev); + break; + + case USB_CTL_LAST_DATA_OUT: + if (udev->dev.cur_status == (uint8_t)USBD_CONFIGURED) { + if (udev->dev.class_core->ctlx_out != NULL) { + (void)udev->dev.class_core->ctlx_out (udev); + } + } + + transc->remain_len = 0U; + + (void)usbd_ctl_status_send (udev); + break; + + default: + break; + } + } else if ((udev->dev.class_core->data_out != NULL) && (udev->dev.cur_status == (uint8_t)USBD_CONFIGURED)) { + (void)udev->dev.class_core->data_out (udev, ep_num); + } else { + /* no operation */ + } + + return (uint8_t)USBD_OK; +} + +/*! + \brief data in stage processing + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier(0..7) + \param[out] none + \retval USB device operation cur_status +*/ +uint8_t usbd_in_transc (usb_core_driver *udev, uint8_t ep_num) +{ + if (0U == ep_num) { + usb_transc *transc = &udev->dev.transc_in[0]; + + switch (udev->dev.control.ctl_state) { + case USB_CTL_DATA_IN: + /* update transfer length */ + transc->remain_len -= transc->max_len; + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + transc->xfer_buf += transc->max_len; + } + + (void)usbd_ctl_send (udev); + break; + + case USB_CTL_LAST_DATA_IN: + /* last packet is MPS multiple, so send ZLP packet */ + if (udev->dev.control.ctl_zlp) { + (void)usbd_ep_send (udev, 0U, NULL, 0U); + + udev->dev.control.ctl_zlp = 0U; + } else { + if (udev->dev.cur_status == (uint8_t)USBD_CONFIGURED) { + if (udev->dev.class_core->ctlx_in != NULL) { + (void)udev->dev.class_core->ctlx_in (udev); + } + } + + transc->remain_len = 0U; + + (void)usbd_ctl_status_recev (udev); + } + break; + + default: + break; + } + } else { + if ((udev->dev.cur_status == (uint8_t)USBD_CONFIGURED) && (udev->dev.class_core->data_in != NULL)) { + (void)udev->dev.class_core->data_in (udev, ep_num); + } + } + + return (uint8_t)USBD_OK; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_core.h new file mode 100644 index 0000000..bb4e74d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_core.h @@ -0,0 +1,356 @@ +/*! + \file drv_usb_core.h + \brief USB core low level driver header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DRV_USB_CORE_H +#define __DRV_USB_CORE_H + +#include "drv_usb_regs.h" +#include "usb_ch9_std.h" + +#ifdef USE_DEVICE_MODE + #include "usbd_conf.h" +#endif /* USE_DEVICE_MODE */ + +#define USB_FS_EP0_MAX_LEN 64U /*!< maximum packet size of endpoint 0 */ +#define HC_MAX_PACKET_COUNT 140U /*!< maximum packet count */ + +#define EP_ID(x) ((uint8_t)((x) & 0x7FU)) /*!< endpoint number */ +#define EP_DIR(x) ((uint8_t)((x) >> 7)) /*!< endpoint direction */ + +enum _usb_mode { + DEVICE_MODE = 0U, /*!< device mode */ + HOST_MODE, /*!< host mode */ + OTG_MODE /*!< OTG mode */ +}; + +enum _usb_eptype { + USB_EPTYPE_CTRL = 0U, /*!< control endpoint type */ + USB_EPTYPE_ISOC = 1U, /*!< isochronous endpoint type */ + USB_EPTYPE_BULK = 2U, /*!< bulk endpoint type */ + USB_EPTYPE_INTR = 3U, /*!< interrupt endpoint type */ + USB_EPTYPE_MASK = 3U /*!< endpoint type mask */ +}; + +typedef enum +{ + USB_OTG_OK = 0U, /*!< USB OTG status OK*/ + USB_OTG_FAIL /*!< USB OTG status fail*/ +} usb_otg_status; + +typedef enum +{ + USB_OK = 0U, /*!< USB status OK*/ + USB_FAIL /*!< USB status fail*/ +} usb_status; + +typedef enum +{ + USB_USE_FIFO, /*!< USB use FIFO transfer mode */ + USB_USE_DMA /*!< USB use DMA transfer mode */ +} usb_transfer_mode; + +typedef struct +{ + uint8_t core_enum; /*!< USB core type */ + uint8_t core_speed; /*!< USB core speed */ + uint8_t num_pipe; /*!< USB host channel numbers */ + uint8_t num_ep; /*!< USB device endpoint numbers */ + uint8_t transfer_mode; /*!< USB transfer mode */ + uint8_t phy_itf; /*!< USB core PHY interface */ + uint8_t sof_enable; /*!< USB SOF output */ + uint8_t low_power; /*!< USB low power */ + uint8_t lpm_enable; /*!< USB link power mode(LPM) */ + uint8_t vbus_sensing_enable; /*!< USB VBUS sensing feature */ + uint8_t use_dedicated_ep1; /*!< USB dedicated endpoint1 interrupt */ + uint8_t use_external_vbus; /*!< enable or disable the use of the external VBUS */ + uint32_t base_reg; /*!< base register address */ +} usb_core_basic; + +#ifdef USE_DEVICE_MODE + +/* USB descriptor */ +typedef struct _usb_desc { + uint8_t *dev_desc; /*!< device descriptor */ + uint8_t *config_desc; /*!< configure descriptor */ + uint8_t *bos_desc; /*!< BOS descriptor */ + +#if defined(USE_USB_HS) && defined(USE_ULPI_PHY) + uint8_t *other_speed_config_desc; /*!< other speed configuration descriptor */ + uint8_t *qualifier_desc; /*!< qualifier descriptor */ +#endif + + void* const *strings; /*!< string descriptor */ +} usb_desc; + +/* USB power management */ +typedef struct _usb_pm { + uint8_t power_mode; /*!< power mode */ + uint8_t power_low; /*!< power low */ + uint8_t dev_remote_wakeup; /*!< remote wakeup */ + uint8_t remote_wakeup_on; /*!< remote wakeup on */ +} usb_pm; + +/* USB control information */ +typedef struct _usb_control { + usb_req req; /*!< USB standard device request */ + + uint8_t ctl_state; /*!< USB control transfer state */ + uint8_t ctl_zlp; /*!< zero length package */ +} usb_control; + +typedef struct +{ + struct { + uint8_t num: 4; /*!< the endpoint number.it can be from 0 to 6 */ + uint8_t pad: 3; /*!< padding between number and direction */ + uint8_t dir: 1; /*!< the endpoint direction */ + } ep_addr; + + uint8_t ep_type; /*!< USB endpoint type */ + uint8_t ep_stall; /*!< USB endpoint stall status */ + + uint8_t frame_num; /*!< number of frame */ + uint16_t max_len; /*!< Maximum packet length */ + + /* transaction level variables */ + uint8_t *xfer_buf; /*!< transmit buffer */ + uint32_t xfer_len; /*!< transmit buffer length */ + uint32_t xfer_count; /*!< transmit buffer count */ + + uint32_t remain_len; /*!< remain packet length */ + + uint32_t dma_addr; /*!< DMA address */ +} usb_transc; + +typedef struct _usb_core_driver usb_dev; + +typedef struct _usb_class_core +{ + uint8_t command; /*!< device class request command */ + uint8_t alter_set; /*!< alternative set */ + + uint8_t (*init) (usb_dev *udev, uint8_t config_index); /*!< initialize handler */ + uint8_t (*deinit) (usb_dev *udev, uint8_t config_index); /*!< de-initialize handler */ + + uint8_t (*req_proc) (usb_dev *udev, usb_req *req); /*!< device request handler */ + + uint8_t (*set_intf) (usb_dev *udev, usb_req *req); /*!< device set interface callback */ + + uint8_t (*ctlx_in) (usb_dev *udev); /*!< device contrl in callback */ + uint8_t (*ctlx_out) (usb_dev *udev); + + uint8_t (*data_in) (usb_dev *udev, uint8_t ep_num); /*!< device data in handler */ + uint8_t (*data_out) (usb_dev *udev, uint8_t ep_num); /*!< device data out handler */ + + uint8_t (*SOF) (usb_dev *udev); /*!< Start of frame handler */ + + uint8_t (*incomplete_isoc_in) (usb_dev *udev); /*!< Incomplete synchronization IN transfer handler */ + uint8_t (*incomplete_isoc_out) (usb_dev *udev); /*!< Incomplete synchronization OUT transfer handler */ +} usb_class_core; + +typedef struct _usb_perp_dev +{ + uint8_t config; /*!< configuration */ + uint8_t dev_addr; /*!< device address */ + + __IO uint8_t cur_status; /*!< current status */ + __IO uint8_t backup_status; /*!< backup status */ + + usb_transc transc_in[USBFS_MAX_TX_FIFOS]; /*!< endpoint IN transaction */ + usb_transc transc_out[USBFS_MAX_TX_FIFOS]; /*!< endpoint OUT transaction */ + + usb_pm pm; /*!< power management */ + usb_control control; /*!< USB control information */ + usb_desc *desc; /*!< USB descriptors pointer */ + usb_class_core *class_core; /*!< class driver */ + void *class_data[USBD_ITF_MAX_NUM]; /*!< class data pointer */ + void *user_data; /*!< user data pointer */ + void *pdata; /*!< reserved data pointer */ +} usb_perp_dev; + +#endif /* USE_DEVICE_MODE */ + +#ifdef USE_HOST_MODE + +typedef enum _usb_pipe_status +{ + PIPE_IDLE = 0U, + PIPE_XF, + PIPE_HALTED, + PIPE_NAK, + PIPE_NYET, + PIPE_STALL, + PIPE_TRACERR, + PIPE_BBERR, + PIPE_REQOVR, + PIPE_DTGERR, +} usb_pipe_staus; + +typedef enum _usb_urb_state +{ + URB_IDLE = 0U, + URB_DONE, + URB_NOTREADY, + URB_ERROR, + URB_STALL, + URB_PING +} usb_urb_state; + +typedef struct _usb_pipe +{ + uint8_t in_used; + uint8_t dev_addr; + uint32_t dev_speed; + + struct { + uint8_t num; + uint8_t dir; + uint8_t type; + uint16_t mps; + } ep; + + __IO uint8_t supp_ping; + __IO uint8_t do_ping; + __IO uint32_t DPID; + + uint8_t *xfer_buf; + uint32_t xfer_len; + uint32_t xfer_count; + + uint8_t data_toggle_in; + uint8_t data_toggle_out; + + __IO uint32_t err_count; + __IO usb_pipe_staus pp_status; + __IO usb_urb_state urb_state; +} usb_pipe; + +typedef struct _usb_host_drv +{ + __IO uint32_t connect_status; + __IO uint32_t port_enabled; + uint32_t backup_xfercount[USBFS_MAX_TX_FIFOS]; + + usb_pipe pipe[USBFS_MAX_TX_FIFOS]; + void *data; +} usb_host_drv; + +#endif /* USE_HOST_MODE */ + +typedef struct _usb_core_driver +{ + usb_core_basic bp; /*!< USB basic parameters */ + usb_core_regs regs; /*!< USB registers */ + +#ifdef USE_DEVICE_MODE + usb_perp_dev dev; /*!< USB peripheral device */ +#endif /* USE_DEVICE_MODE */ + +#ifdef USE_HOST_MODE + usb_host_drv host; +#endif /* USE_HOST_MODE */ +} usb_core_driver; + +/* static inline function definitions */ + +/*! + \brief get the global interrupts + \param[in] usb_regs: pointer to USB core registers + \param[out] none + \retval interrupt status +*/ +__STATIC_INLINE uint32_t usb_coreintr_get(usb_core_regs *usb_regs) +{ + uint32_t reg_data = usb_regs->gr->GINTEN; + + reg_data &= usb_regs->gr->GINTF; + + return reg_data; +} + +/*! + \brief set USB RX FIFO size + \param[in] usb_regs: pointer to USB core registers + \param[in] size: assigned FIFO size + \param[out] none + \retval none +*/ +__STATIC_INLINE void usb_set_rxfifo(usb_core_regs *usb_regs, uint16_t size) +{ + usb_regs->gr->GRFLEN = size; +} + +/*! + \brief enable the global interrupts + \param[in] usb_regs: pointer to USB core registers + \param[out] none + \retval none +*/ +__STATIC_INLINE void usb_globalint_enable(usb_core_regs *usb_regs) +{ + /* enable USB global interrupt */ + usb_regs->gr->GAHBCS |= GAHBCS_GINTEN; +} + +/*! + \brief disable the global interrupts + \param[in] usb_regs: pointer to USB core registers + \param[out] none + \retval none +*/ +__STATIC_INLINE void usb_globalint_disable(usb_core_regs *usb_regs) +{ + /* disable USB global interrupt */ + usb_regs->gr->GAHBCS &= ~GAHBCS_GINTEN; +} + +/* function declarations */ +/* configure core capabilities */ +usb_status usb_basic_init (usb_core_basic *usb_basic, usb_core_regs *usb_regs, usb_core_enum usb_core); +/* initializes the USB controller registers and prepares the core device mode or host mode operation */ +usb_status usb_core_init (usb_core_basic usb_basic, usb_core_regs *usb_regs); +/* write a packet into the Tx FIFO associated with the endpoint */ +usb_status usb_txfifo_write (usb_core_regs *usb_regs, uint8_t *src_buf, uint8_t fifo_num, uint16_t byte_count); +/* read a packet from the Rx FIFO associated with the endpoint */ +void *usb_rxfifo_read (usb_core_regs *usb_regs, uint8_t *dest_buf, uint16_t byte_count); +/* flush a Tx FIFO or all Tx FIFOs */ +usb_status usb_txfifo_flush (usb_core_regs *usb_regs, uint8_t fifo_num); +/* flush the entire Rx FIFO */ +usb_status usb_rxfifo_flush (usb_core_regs *usb_regs); +/* set endpoint or channel TX FIFO size */ +void usb_set_txfifo(usb_core_regs *usb_regs, uint8_t fifo, uint16_t size); +/* set USB current mode */ +void usb_curmode_set(usb_core_regs *usb_regs, uint8_t mode); + +#endif /* __DRV_USB_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_dev.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_dev.h new file mode 100644 index 0000000..49840c4 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_dev.h @@ -0,0 +1,197 @@ +/*! + \file drv_usb_dev.h + \brief USB device low level driver header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DRV_USB_DEV_H +#define __DRV_USB_DEV_H + +#include "usbd_conf.h" +#include "drv_usb_core.h" + +#define EP_IN(x) ((uint8_t)(0x80U | (x))) /*!< device IN endpoint */ +#define EP_OUT(x) ((uint8_t)(x)) /*!< device OUT endpoint */ + +enum usb_ctl_status { + USB_CTL_IDLE = 0U, /*!< USB control transfer idle state */ + USB_CTL_DATA_IN, /*!< USB control transfer data in state */ + USB_CTL_LAST_DATA_IN, /*!< USB control transfer last data in state */ + USB_CTL_DATA_OUT, /*!< USB control transfer data out state */ + USB_CTL_LAST_DATA_OUT, /*!< USB control transfer last data out state */ + USB_CTL_STATUS_IN, /*!< USB control transfer status in state*/ + USB_CTL_STATUS_OUT /*!< USB control transfer status out state */ +}; + +/* static inline function definitions */ + +/*! + \brief configure the USB device to be disconnected + \param[in] udev: pointer to USB device + \param[out] none + \retval operation status +*/ +__STATIC_INLINE void usb_dev_disconnect (usb_core_driver *udev) +{ + udev->regs.dr->DCTL |= DCTL_SD; +} + +/*! + \brief configure the USB device to be connected + \param[in] udev: pointer to USB device + \param[out] none + \retval operation status +*/ +__STATIC_INLINE void usb_dev_connect (usb_core_driver *udev) +{ + udev->regs.dr->DCTL &= ~DCTL_SD; +} + +/*! + \brief set the USB device address + \param[in] udev: pointer to USB device + \param[in] dev_addr: device address for setting + \param[out] none + \retval operation status +*/ +__STATIC_INLINE void usb_devaddr_set (usb_core_driver *udev, uint8_t dev_addr) +{ + udev->regs.dr->DCFG &= ~DCFG_DAR; + udev->regs.dr->DCFG |= (uint32_t)dev_addr << 4U; +} + +/*! + \brief read device all OUT endpoint interrupt register + \param[in] udev: pointer to USB device + \param[out] none + \retval interrupt status +*/ +__STATIC_INLINE uint32_t usb_oepintnum_read (usb_core_driver *udev) +{ + uint32_t value = udev->regs.dr->DAEPINT; + + value &= udev->regs.dr->DAEPINTEN; + + return (value & DAEPINT_OEPITB) >> 16U; +} + +/*! + \brief read device OUT endpoint interrupt flag register + \param[in] udev: pointer to USB device + \param[in] ep_num: endpoint number + \param[out] none + \retval interrupt status +*/ +__STATIC_INLINE uint32_t usb_oepintr_read (usb_core_driver *udev, uint8_t ep_num) +{ + uint32_t value = udev->regs.er_out[ep_num]->DOEPINTF; + + value &= udev->regs.dr->DOEPINTEN; + + return value; +} + +/*! + \brief read device all IN endpoint interrupt register + \param[in] udev: pointer to USB device + \param[out] none + \retval interrupt status +*/ +__STATIC_INLINE uint32_t usb_iepintnum_read (usb_core_driver *udev) +{ + uint32_t value = udev->regs.dr->DAEPINT; + + value &= udev->regs.dr->DAEPINTEN; + + return value & DAEPINT_IEPITB; +} + +/*! + \brief set remote wakeup signaling + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +__STATIC_INLINE void usb_rwkup_set (usb_core_driver *udev) +{ + if (udev->dev.pm.dev_remote_wakeup) { + /* enable remote wakeup signaling */ + udev->regs.dr->DCTL |= DCTL_RWKUP; + } +} + +/*! + \brief reset remote wakeup signaling + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +__STATIC_INLINE void usb_rwkup_reset (usb_core_driver *udev) +{ + if (udev->dev.pm.dev_remote_wakeup) { + /* disable remote wakeup signaling */ + udev->regs.dr->DCTL &= ~DCTL_RWKUP; + } +} + +/* function declarations */ +/* initialize USB core registers for device mode */ +usb_status usb_devcore_init (usb_core_driver *udev); +/* enable the USB device mode interrupts */ +usb_status usb_devint_enable (usb_core_driver *udev); +/* active the USB endpoint 0 transaction */ +usb_status usb_transc0_active (usb_core_driver *udev, usb_transc *transc); +/* active the USB transaction */ +usb_status usb_transc_active (usb_core_driver *udev, usb_transc *transc); +/* deactivate the USB transaction */ +usb_status usb_transc_deactivate (usb_core_driver *udev, usb_transc *transc); +/* configure USB transaction to start IN transfer */ +usb_status usb_transc_inxfer (usb_core_driver *udev, usb_transc *transc); +/* configure USB transaction to start OUT transfer */ +usb_status usb_transc_outxfer (usb_core_driver *udev, usb_transc *transc); +/* set the USB transaction STALL status */ +usb_status usb_transc_stall (usb_core_driver *udev, usb_transc *transc); +/* clear the USB transaction STALL status */ +usb_status usb_transc_clrstall (usb_core_driver *udev, usb_transc *transc); +/* read device IN endpoint interrupt flag register */ +uint32_t usb_iepintr_read (usb_core_driver *udev, uint8_t ep_num); +/* configures OUT endpoint 0 to receive SETUP packets */ +void usb_ctlep_startout (usb_core_driver *udev); +/* active remote wakeup signaling */ +void usb_rwkup_active (usb_core_driver *udev); +/* active USB core clock */ +void usb_clock_active (usb_core_driver *udev); +/* USB device suspend */ +void usb_dev_suspend (usb_core_driver *udev); +/* stop the device and clean up FIFOs */ +void usb_dev_stop (usb_core_driver *udev); + +#endif /* __DRV_USB_DEV_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_host.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_host.h new file mode 100644 index 0000000..ba4d16c --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_host.h @@ -0,0 +1,123 @@ +/*! + \file drv_usb_host.h + \brief USB host mode low level driver header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DRV_USB_HOST_H +#define __DRV_USB_HOST_H + +#include "drv_usb_regs.h" +#include "usb_ch9_std.h" +#include "drv_usb_core.h" + +typedef enum _usb_pipe_mode +{ + PIPE_PERIOD = 0U, + PIPE_NON_PERIOD = 1U +} usb_pipe_mode; + +/*! + \brief get USB even frame + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +__STATIC_INLINE uint8_t usb_frame_even (usb_core_driver *udev) +{ + return (uint8_t)!(udev->regs.hr->HFINFR & 0x01U); +} + +/*! + \brief configure USB clock of PHY + \param[in] udev: pointer to USB device + \param[in] clock: PHY clock + \param[out] none + \retval none +*/ +__STATIC_INLINE void usb_phyclock_config (usb_core_driver *udev, uint8_t clock) +{ + udev->regs.hr->HCTL &= ~HCTL_CLKSEL; + udev->regs.hr->HCTL |= clock; +} + +/*! + \brief read USB port + \param[in] udev: pointer to USB device + \param[out] none + \retval port status +*/ +__STATIC_INLINE uint32_t usb_port_read (usb_core_driver *udev) +{ + return *udev->regs.HPCS & ~(HPCS_PE | HPCS_PCD | HPCS_PEDC); +} + +/*! + \brief get USB current speed + \param[in] udev: pointer to USB device + \param[out] none + \retval USB current speed +*/ +__STATIC_INLINE uint32_t usb_curspeed_get (usb_core_driver *udev) +{ + return *udev->regs.HPCS & HPCS_PS; +} + +/*! + \brief get USB current frame + \param[in] udev: pointer to USB device + \param[out] none + \retval USB current frame +*/ +__STATIC_INLINE uint32_t usb_curframe_get (usb_core_driver *udev) +{ + return (udev->regs.hr->HFINFR & 0xFFFFU); +} + +/* function declarations */ +/* initializes USB core for host mode */ +usb_status usb_host_init (usb_core_driver *udev); +/* control the VBUS to power */ +void usb_portvbus_switch (usb_core_driver *udev, uint8_t state); +/* reset host port */ +uint32_t usb_port_reset (usb_core_driver *udev); +/* initialize host pipe */ +usb_status usb_pipe_init (usb_core_driver *udev, uint8_t pipe_num); +/* prepare host pipe for transferring packets */ +usb_status usb_pipe_xfer (usb_core_driver *udev, uint8_t pipe_num); +/* halt host pipe */ +usb_status usb_pipe_halt (usb_core_driver *udev, uint8_t pipe_num); +/* configure host pipe to do ping operation */ +usb_status usb_pipe_ping (usb_core_driver *udev, uint8_t pipe_num); +/* stop the USB host and clean up FIFO */ +void usb_host_stop (usb_core_driver *udev); + +#endif /* __DRV_USB_HOST_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_hw.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_hw.h new file mode 100644 index 0000000..103f352 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_hw.h @@ -0,0 +1,62 @@ +/*! + \file drv_usb_hw.h + \brief usb hardware configuration header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DRV_USB_HW_H +#define __DRV_USB_HW_H + +#include "usb_conf.h" + +/* function declarations */ +/* configure USB clock */ +void usb_rcu_config (void); +/* configure USB data line gpio */ +void usb_gpio_config (void); +/* configure USB interrupt */ +void usb_intr_config (void); +/* initializes delay unit using Timer2 */ +void usb_timer_init (void); +/* delay in micro seconds */ +void usb_udelay (const uint32_t usec); +/* delay in milliseconds */ +void usb_mdelay (const uint32_t msec); +/* configures system clock after wakeup from STOP mode */ +void system_clk_config_stop(void); +#ifdef USE_HOST_MODE +/* configure USB VBus */ +void usb_vbus_config (void); +/* drive USB VBus */ +void usb_vbus_drive (uint8_t State); +#endif /* USE_HOST_MODE */ + +#endif /* __DRV_USB_HW_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_regs.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_regs.h new file mode 100644 index 0000000..830a21f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usb_regs.h @@ -0,0 +1,665 @@ +/*! + \file drv_usb_regs.h + \brief USB cell registers definition and handle macros + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DRV_USB_REGS_H +#define __DRV_USB_REGS_H + +#include "usb_conf.h" + +#define USBHS_REG_BASE 0x40040000L /*!< base address of USBHS registers */ +#define USBFS_REG_BASE 0x50000000L /*!< base address of USBFS registers */ + +#define USBFS_MAX_TX_FIFOS 15U /*!< FIFO number */ + +#define USBFS_MAX_PACKET_SIZE 64U /*!< USBFS max packet size */ +#define USBFS_MAX_CHANNEL_COUNT 8U /*!< USBFS host channel count */ +#define USBFS_MAX_EP_COUNT 4U /*!< USBFS device endpoint count */ +#define USBFS_MAX_FIFO_WORDLEN 320U /*!< USBFS max fifo size in words */ + +#define USBHS_MAX_PACKET_SIZE 512U /*!< USBHS max packet size */ +#define USBHS_MAX_CHANNEL_COUNT 12U /*!< USBHS host channel count */ +#define USBHS_MAX_EP_COUNT 6U /*!< USBHS device endpoint count */ +#define USBHS_MAX_FIFO_WORDLEN 1280U /*!< USBHS max fifo size in words */ + +#define USB_DATA_FIFO_OFFSET 0x1000U /*!< USB data fifo offset */ +#define USB_DATA_FIFO_SIZE 0x1000U /*!< USB data fifo size */ + +typedef enum +{ + USB_CORE_ENUM_HS = 0, /*!< USB core type is HS */ + USB_CORE_ENUM_FS = 1 /*!< USB core type is FS */ +} usb_core_enum; + +enum USB_SPEED { + USB_SPEED_UNKNOWN = 0, /*!< USB speed unknown */ + USB_SPEED_LOW, /*!< USB speed low */ + USB_SPEED_FULL, /*!< USB speed full */ + USB_SPEED_HIGH, /*!< USB speed high */ +}; + +enum usb_reg_offset { + USB_REG_OFFSET_CORE = 0x0000U, /*!< global OTG control and status register */ + USB_REG_OFFSET_DEV = 0x0800U, /*!< device mode control and status registers */ + USB_REG_OFFSET_EP = 0x0020U, + USB_REG_OFFSET_EP_IN = 0x0900U, /*!< device IN endpoint 0 control register */ + USB_REG_OFFSET_EP_OUT = 0x0B00U, /*!< device OUT endpoint 0 control register */ + USB_REG_OFFSET_HOST = 0x0400U, /*!< host control register */ + USB_REG_OFFSET_CH = 0x0020U, + USB_REG_OFFSET_PORT = 0x0440U, /*!< host port control and status register */ + USB_REG_OFFSET_CH_INOUT = 0x0500U, /*!< Host channel-x control registers */ + USB_REG_OFFSET_PWRCLKCTL = 0x0E00U, /*!< power and clock register */ +}; + +typedef struct +{ + __IO uint32_t GOTGCS; /*!< USB global OTG control and status register 000h */ + __IO uint32_t GOTGINTF; /*!< USB global OTG interrupt flag register 004h */ + __IO uint32_t GAHBCS; /*!< USB global AHB control and status register 008h */ + __IO uint32_t GUSBCS; /*!< USB global USB control and status register 00Ch */ + __IO uint32_t GRSTCTL; /*!< USB global reset control register 010h */ + __IO uint32_t GINTF; /*!< USB global interrupt flag register 014h */ + __IO uint32_t GINTEN; /*!< USB global interrupt enable register 018h */ + __IO uint32_t GRSTATR; /*!< USB receive status debug read register 01Ch */ + __IO uint32_t GRSTATP; /*!< USB receive status and pop register 020h */ + __IO uint32_t GRFLEN; /*!< USB global receive FIFO length register 024h */ + __IO uint32_t DIEP0TFLEN_HNPTFLEN; /*!< USB device IN endpoint 0/host non-periodic transmit FIFO length register 028h */ + __IO uint32_t HNPTFQSTAT; /*!< USB host non-periodic FIFO/queue status register 02Ch */ + uint32_t Reserved30[2]; /*!< Reserved 030h */ + __IO uint32_t GCCFG; /*!< USB global core configuration register 038h */ + __IO uint32_t CID; /*!< USB core ID register 03Ch */ + uint32_t Reserved40[48]; /*!< Reserved 040h-0FFh */ + __IO uint32_t HPTFLEN; /*!< USB host periodic transmit FIFO length register 100h */ + __IO uint32_t DIEPTFLEN[15]; /*!< USB device IN endpoint transmit FIFO length register 104h */ +} usb_gr; + + +typedef struct +{ + __IO uint32_t HCTL; /*!< USB host control register 400h */ + __IO uint32_t HFT; /*!< USB host frame interval register 404h */ + __IO uint32_t HFINFR; /*!< USB host frame information remaining register 408h */ + uint32_t Reserved40C; /*!< Reserved 40Ch */ + __IO uint32_t HPTFQSTAT; /*!< USB host periodic transmit FIFO/queue status register 410h */ + __IO uint32_t HACHINT; /*!< USB host all channels interrupt register 414h */ + __IO uint32_t HACHINTEN; /*!< USB host all channels interrupt enable register 418h */ +} usb_hr; + +typedef struct +{ + __IO uint32_t HCHCTL; /*!< USB host channel control register 500h */ + __IO uint32_t HCHSTCTL; /*!< Reserved 504h */ + __IO uint32_t HCHINTF; /*!< USB host channel interrupt flag register 508h */ + __IO uint32_t HCHINTEN; /*!< USB host channel interrupt enable register 50Ch */ + __IO uint32_t HCHLEN; /*!< USB host channel transfer length register 510h */ + __IO uint32_t HCHDMAADDR; /*!< USB host channel-x DMA address register 514h*/ + uint32_t Reserved[2]; +} usb_pr; + +typedef struct +{ + __IO uint32_t DCFG; /*!< USB device configuration register 800h */ + __IO uint32_t DCTL; /*!< USB device control register 804h */ + __IO uint32_t DSTAT; /*!< USB device status register 808h */ + uint32_t Reserved0C; /*!< Reserved 80Ch */ + __IO uint32_t DIEPINTEN; /*!< USB device IN endpoint common interrupt enable register 810h */ + __IO uint32_t DOEPINTEN; /*!< USB device OUT endpoint common interrupt enable register 814h */ + __IO uint32_t DAEPINT; /*!< USB device all endpoints interrupt register 818h */ + __IO uint32_t DAEPINTEN; /*!< USB device all endpoints interrupt enable register 81Ch */ + uint32_t Reserved20; /*!< Reserved 820h */ + uint32_t Reserved24; /*!< Reserved 824h */ + __IO uint32_t DVBUSDT; /*!< USB device VBUS discharge time register 828h */ + __IO uint32_t DVBUSPT; /*!< USB device VBUS pulsing time register 82Ch */ + __IO uint32_t DTHRCTL; /*!< device threshold control 830h */ + __IO uint32_t DIEPFEINTEN; /*!< USB Device IN endpoint FIFO empty interrupt enable register 834h */ + __IO uint32_t DEP1INT; /*!< USB device endpoint 1 interrupt register 838h */ + __IO uint32_t DEP1INTEN; /*!< USB device endpoint 1 interrupt enable register 83Ch */ + uint32_t Reserved40; /*!< Reserved 840h */ + __IO uint32_t DIEP1INTEN; /*!< USB device IN endpoint-1 interrupt enable register 844h */ + uint32_t Reserved48[15]; /*!< Reserved 848-880h */ + __IO uint32_t DOEP1INTEN; /*!< USB device OUT endpoint-1 interrupt enable register 884h */ +} usb_dr; + +typedef struct +{ + __IO uint32_t DIEPCTL; /*!< USB device IN endpoint control register 900h + (EpNum * 20h) + 00h */ + uint32_t Reserved04; /*!< Reserved 900h + (EpNum * 20h) + 04h */ + __IO uint32_t DIEPINTF; /*!< USB device IN endpoint interrupt flag register 900h + (EpNum * 20h) + 08h */ + uint32_t Reserved0C; /*!< Reserved 900h + (EpNum * 20h) + 0Ch */ + __IO uint32_t DIEPLEN; /*!< USB device IN endpoint transfer length register 900h + (EpNum * 20h) + 10h */ + __IO uint32_t DIEPDMAADDR; /*!< Device IN endpoint-x DMA address register 900h + (EpNum * 20h) + 14h */ + __IO uint32_t DIEPTFSTAT; /*!< USB device IN endpoint transmit FIFO status register 900h + (EpNum * 20h) + 18h */ +} usb_erin; + +typedef struct +{ + __IO uint32_t DOEPCTL; /*!< USB device IN endpoint control register B00h + (EpNum * 20h) + 00h */ + uint32_t Reserved04; /*!< Reserved B00h + (EpNum * 20h) + 04h */ + __IO uint32_t DOEPINTF; /*!< USB device IN endpoint interrupt flag register B00h + (EpNum * 20h) + 08h */ + uint32_t Reserved0C; /*!< Reserved B00h + (EpNum * 20h) + 0Ch */ + __IO uint32_t DOEPLEN; /*!< USB device IN endpoint transfer length register B00h + (EpNum * 20h) + 10h */ + __IO uint32_t DOEPDMAADDR; /*!< Device OUT endpoint-x DMA address register B00h + (EpNum * 20h) + 0Ch */ +} usb_erout; + +typedef struct _usb_regs +{ + usb_gr *gr; /*!< USBFS global registers */ + usb_dr *dr; /*!< Device control and status registers */ + usb_hr *hr; /*!< Host control and status registers */ + usb_erin *er_in[6]; /*!< USB device IN endpoint register */ + usb_erout *er_out[6]; /*!< USB device OUT endpoint register */ + usb_pr *pr[15]; /*!< USB Host channel-x control register */ + + __IO uint32_t *HPCS; /*!< USB host port control and status register */ + __IO uint32_t *DFIFO[USBFS_MAX_TX_FIFOS]; + __IO uint32_t *PWRCLKCTL; /*!< USB power and clock control register */ +} usb_core_regs; + +/* global OTG control and status register bits definitions */ +#define GOTGCS_BSV BIT(19) /*!< B-Session Valid */ +#define GOTGCS_ASV BIT(18) /*!< A-session valid */ +#define GOTGCS_DI BIT(17) /*!< debounce interval */ +#define GOTGCS_IDPS BIT(16) /*!< id pin status */ +#define GOTGCS_DHNPEN BIT(11) /*!< device HNP enable */ +#define GOTGCS_HHNPEN BIT(10) /*!< host HNP enable */ +#define GOTGCS_HNPREQ BIT(9) /*!< HNP request */ +#define GOTGCS_HNPS BIT(8) /*!< HNP successes */ +#define GOTGCS_SRPREQ BIT(1) /*!< SRP request */ +#define GOTGCS_SRPS BIT(0) /*!< SRP successes */ + +/* global OTG interrupt flag register bits definitions */ +#define GOTGINTF_DF BIT(19) /*!< debounce finish */ +#define GOTGINTF_ADTO BIT(18) /*!< A-device timeout */ +#define GOTGINTF_HNPDET BIT(17) /*!< host negotiation request detected */ +#define GOTGINTF_HNPEND BIT(9) /*!< HNP end */ +#define GOTGINTF_SRPEND BIT(8) /*!< SRP end */ +#define GOTGINTF_SESEND BIT(2) /*!< session end */ + +/* global AHB control and status register bits definitions */ +#define GAHBCS_PTXFTH BIT(8) /*!< periodic Tx FIFO threshold */ +#define GAHBCS_TXFTH BIT(7) /*!< tx FIFO threshold */ +#define GAHBCS_DMAEN BIT(5) /*!< DMA function Enable */ +#define GAHBCS_BURST BITS(1, 4) /*!< the AHB burst type used by DMA */ +#define GAHBCS_GINTEN BIT(0) /*!< global interrupt enable */ + +/* global USB control and status register bits definitions */ +#define GUSBCS_FDM BIT(30) /*!< force device mode */ +#define GUSBCS_FHM BIT(29) /*!< force host mode */ +#define GUSBCS_ULPIEOI BIT(21) /*!< ULPI external over-current indicator */ +#define GUSBCS_ULPIEVD BIT(20) /*!< ULPI external VBUS driver */ +#define GUSBCS_UTT BITS(10, 13) /*!< USB turnaround time */ +#define GUSBCS_HNPCEN BIT(9) /*!< HNP capability enable */ +#define GUSBCS_SRPCEN BIT(8) /*!< SRP capability enable */ +#define GUSBCS_EMBPHY BIT(6) /*!< embedded PHY selected */ +#define GUSBCS_HS_CUR_FE BIT(4) /*!< HS current software enable */ +#define GUSBCS_TOC BITS(0, 2) /*!< timeout calibration */ + +/* global reset control register bits definitions */ +#define GRSTCTL_DMAIDL BIT(31) /*!< DMA idle state */ +#define GRSTCTL_DMABSY BIT(30) /*!< DMA busy */ +#define GRSTCTL_TXFNUM BITS(6, 10) /*!< tx FIFO number */ +#define GRSTCTL_TXFF BIT(5) /*!< tx FIFO flush */ +#define GRSTCTL_RXFF BIT(4) /*!< rx FIFO flush */ +#define GRSTCTL_HFCRST BIT(2) /*!< host frame counter reset */ +#define GRSTCTL_HCSRST BIT(1) /*!< HCLK soft reset */ +#define GRSTCTL_CSRST BIT(0) /*!< core soft reset */ + +/* global interrupt flag register bits definitions */ +#define GINTF_WKUPIF BIT(31) /*!< wakeup interrupt flag */ +#define GINTF_SESIF BIT(30) /*!< session interrupt flag */ +#define GINTF_DISCIF BIT(29) /*!< disconnect interrupt flag */ +#define GINTF_IDPSC BIT(28) /*!< id pin status change */ +#define GINTF_PTXFEIF BIT(26) /*!< periodic tx FIFO empty interrupt flag */ +#define GINTF_HCIF BIT(25) /*!< host channels interrupt flag */ +#define GINTF_HPIF BIT(24) /*!< host port interrupt flag */ +#define GINTF_PXNCIF BIT(21) /*!< periodic transfer not complete interrupt flag */ +#define GINTF_ISOONCIF BIT(21) /*!< isochronous OUT transfer not complete interrupt flag */ +#define GINTF_ISOINCIF BIT(20) /*!< isochronous IN transfer not complete interrupt flag */ +#define GINTF_OEPIF BIT(19) /*!< OUT endpoint interrupt flag */ +#define GINTF_IEPIF BIT(18) /*!< IN endpoint interrupt flag */ +#define GINTF_EOPFIF BIT(15) /*!< end of periodic frame interrupt flag */ +#define GINTF_ISOOPDIF BIT(14) /*!< isochronous OUT packet dropped interrupt flag */ +#define GINTF_ENUMFIF BIT(13) /*!< enumeration finished */ +#define GINTF_RST BIT(12) /*!< USB reset */ +#define GINTF_SP BIT(11) /*!< USB suspend */ +#define GINTF_ESP BIT(10) /*!< early suspend */ +#define GINTF_GONAK BIT(7) /*!< global OUT NAK effective */ +#define GINTF_GNPINAK BIT(6) /*!< global IN non-periodic NAK effective */ +#define GINTF_NPTXFEIF BIT(5) /*!< non-periodic tx FIFO empty interrupt flag */ +#define GINTF_RXFNEIF BIT(4) /*!< rx FIFO non-empty interrupt flag */ +#define GINTF_SOF BIT(3) /*!< start of frame */ +#define GINTF_OTGIF BIT(2) /*!< OTG interrupt flag */ +#define GINTF_MFIF BIT(1) /*!< mode fault interrupt flag */ +#define GINTF_COPM BIT(0) /*!< current operation mode */ + +/* global interrupt enable register bits definitions */ +#define GINTEN_WKUPIE BIT(31) /*!< wakeup interrupt enable */ +#define GINTEN_SESIE BIT(30) /*!< session interrupt enable */ +#define GINTEN_DISCIE BIT(29) /*!< disconnect interrupt enable */ +#define GINTEN_IDPSCIE BIT(28) /*!< id pin status change interrupt enable */ +#define GINTEN_PTXFEIE BIT(26) /*!< periodic tx FIFO empty interrupt enable */ +#define GINTEN_HCIE BIT(25) /*!< host channels interrupt enable */ +#define GINTEN_HPIE BIT(24) /*!< host port interrupt enable */ +#define GINTEN_IPXIE BIT(21) /*!< periodic transfer not complete interrupt enable */ +#define GINTEN_ISOONCIE BIT(21) /*!< isochronous OUT transfer not complete interrupt enable */ +#define GINTEN_ISOINCIE BIT(20) /*!< isochronous IN transfer not complete interrupt enable */ +#define GINTEN_OEPIE BIT(19) /*!< OUT endpoints interrupt enable */ +#define GINTEN_IEPIE BIT(18) /*!< IN endpoints interrupt enable */ +#define GINTEN_EOPFIE BIT(15) /*!< end of periodic frame interrupt enable */ +#define GINTEN_ISOOPDIE BIT(14) /*!< isochronous OUT packet dropped interrupt enable */ +#define GINTEN_ENUMFIE BIT(13) /*!< enumeration finish enable */ +#define GINTEN_RSTIE BIT(12) /*!< USB reset interrupt enable */ +#define GINTEN_SPIE BIT(11) /*!< USB suspend interrupt enable */ +#define GINTEN_ESPIE BIT(10) /*!< early suspend interrupt enable */ +#define GINTEN_GONAKIE BIT(7) /*!< global OUT NAK effective interrupt enable */ +#define GINTEN_GNPINAKIE BIT(6) /*!< global non-periodic IN NAK effective interrupt enable */ +#define GINTEN_NPTXFEIE BIT(5) /*!< non-periodic Tx FIFO empty interrupt enable */ +#define GINTEN_RXFNEIE BIT(4) /*!< receive FIFO non-empty interrupt enable */ +#define GINTEN_SOFIE BIT(3) /*!< start of frame interrupt enable */ +#define GINTEN_OTGIE BIT(2) /*!< OTG interrupt enable */ +#define GINTEN_MFIE BIT(1) /*!< mode fault interrupt enable */ + +/* global receive status read and pop register bits definitions */ +#define GRSTATRP_RPCKST BITS(17, 20) /*!< received packet status */ +#define GRSTATRP_DPID BITS(15, 16) /*!< data PID */ +#define GRSTATRP_BCOUNT BITS(4, 14) /*!< byte count */ +#define GRSTATRP_CNUM BITS(0, 3) /*!< channel number */ +#define GRSTATRP_EPNUM BITS(0, 3) /*!< endpoint number */ + +/* global receive FIFO length register bits definitions */ +#define GRFLEN_RXFD BITS(0, 15) /*!< rx FIFO depth */ + +/* host non-periodic transmit FIFO length register bits definitions */ +#define HNPTFLEN_HNPTXFD BITS(16, 31) /*!< non-periodic Tx FIFO depth */ +#define HNPTFLEN_HNPTXRSAR BITS(0, 15) /*!< non-periodic Tx RAM start address */ + +/* USB IN endpoint 0 transmit FIFO length register bits definitions */ +#define DIEP0TFLEN_IEP0TXFD BITS(16, 31) /*!< IN Endpoint 0 Tx FIFO depth */ +#define DIEP0TFLEN_IEP0TXRSAR BITS(0, 15) /*!< IN Endpoint 0 TX RAM start address */ + +/* host non-periodic transmit FIFO/queue status register bits definitions */ +#define HNPTFQSTAT_NPTXRQTOP BITS(24, 30) /*!< top entry of the non-periodic Tx request queue */ +#define HNPTFQSTAT_NPTXRQS BITS(16, 23) /*!< non-periodic Tx request queue space */ +#define HNPTFQSTAT_NPTXFS BITS(0, 15) /*!< non-periodic Tx FIFO space */ +#define HNPTFQSTAT_CNUM BITS(27, 30) /*!< channel number*/ +#define HNPTFQSTAT_EPNUM BITS(27, 30) /*!< endpoint number */ +#define HNPTFQSTAT_TYPE BITS(25, 26) /*!< token type */ +#define HNPTFQSTAT_TMF BIT(24) /*!< terminate flag */ + +/* global core configuration register bits definitions */ +#define GCCFG_VBUSIG BIT(21) /*!< vbus ignored */ +#define GCCFG_SOFOEN BIT(20) /*!< SOF output enable */ +#define GCCFG_VBUSBCEN BIT(19) /*!< the VBUS B-device comparer enable */ +#define GCCFG_VBUSACEN BIT(18) /*!< the VBUS A-device comparer enable */ +#define GCCFG_PWRON BIT(16) /*!< power on */ + +/* core ID register bits definitions */ +#define CID_CID BITS(0, 31) /*!< core ID */ + +/* host periodic transmit FIFO length register bits definitions */ +#define HPTFLEN_HPTXFD BITS(16, 31) /*!< host periodic Tx FIFO depth */ +#define HPTFLEN_HPTXFSAR BITS(0, 15) /*!< host periodic Tx RAM start address */ + +/* device IN endpoint transmit FIFO length register bits definitions */ +#define DIEPTFLEN_IEPTXFD BITS(16, 31) /*!< IN endpoint Tx FIFO x depth */ +#define DIEPTFLEN_IEPTXRSAR BITS(0, 15) /*!< IN endpoint FIFOx Tx x RAM start address */ + +/* host control register bits definitions */ +#define HCTL_SPDFSLS BIT(2) /*!< speed limited to FS and LS */ +#define HCTL_CLKSEL BITS(0, 1) /*!< clock select for USB clock */ + +/* host frame interval register bits definitions */ +#define HFT_FRI BITS(0, 15) /*!< frame interval */ + +/* host frame information remaining register bits definitions */ +#define HFINFR_FRT BITS(16, 31) /*!< frame remaining time */ +#define HFINFR_FRNUM BITS(0, 15) /*!< frame number */ + +/* host periodic transmit FIFO/queue status register bits definitions */ +#define HPTFQSTAT_PTXREQT BITS(24, 31) /*!< top entry of the periodic Tx request queue */ +#define HPTFQSTAT_PTXREQS BITS(16, 23) /*!< periodic Tx request queue space */ +#define HPTFQSTAT_PTXFS BITS(0, 15) /*!< periodic Tx FIFO space */ +#define HPTFQSTAT_OEFRM BIT(31) /*!< odd/eveb frame */ +#define HPTFQSTAT_CNUM BITS(27, 30) /*!< channel number */ +#define HPTFQSTAT_EPNUM BITS(27, 30) /*!< endpoint number */ +#define HPTFQSTAT_TYPE BITS(25, 26) /*!< token type */ +#define HPTFQSTAT_TMF BIT(24) /*!< terminate flag */ + +#define TFQSTAT_TXFS BITS(0, 15) +#define TFQSTAT_CNUM BITS(27, 30) + +/* host all channels interrupt register bits definitions */ +#define HACHINT_HACHINT BITS(0, 11) /*!< host all channel interrupts */ + +/* host all channels interrupt enable register bits definitions */ +#define HACHINTEN_CINTEN BITS(0, 11) /*!< channel interrupt enable */ + +/* host port control and status register bits definitions */ +#define HPCS_PS BITS(17, 18) /*!< port speed */ +#define HPCS_PTEST BITS(13, 16) /*!< port test control */ +#define HPCS_PP BIT(12) /*!< port power */ +#define HPCS_PLST BITS(10, 11) /*!< port line status */ +#define HPCS_PRST BIT(8) /*!< port reset */ +#define HPCS_PSP BIT(7) /*!< port suspend */ +#define HPCS_PREM BIT(6) /*!< port resume */ +#define HPCS_PEDC BIT(3) /*!< port enable/disable change */ +#define HPCS_PE BIT(2) /*!< port enable */ +#define HPCS_PCD BIT(1) /*!< port connect detected */ +#define HPCS_PCST BIT(0) /*!< port connect status */ + +/* host channel-x control register bits definitions */ +#define HCHCTL_CEN BIT(31) /*!< channel enable */ +#define HCHCTL_CDIS BIT(30) /*!< channel disable */ +#define HCHCTL_ODDFRM BIT(29) /*!< odd frame */ +#define HCHCTL_DAR BITS(22, 28) /*!< device address */ +#define HCHCTL_MPC BITS(20, 21) /*!< multiple packet count */ +#define HCHCTL_EPTYPE BITS(18, 19) /*!< endpoint type */ +#define HCHCTL_LSD BIT(17) /*!< low-speed device */ +#define HCHCTL_EPDIR BIT(15) /*!< endpoint direction */ +#define HCHCTL_EPNUM BITS(11, 14) /*!< endpoint number */ +#define HCHCTL_MPL BITS(0, 10) /*!< maximum packet length */ + +/* host channel-x split transaction register bits definitions */ +#define HCHSTCTL_SPLEN BIT(31) /*!< enable high-speed split transaction */ +#define HCHSTCTL_CSPLT BIT(16) /*!< complete-split enable */ +#define HCHSTCTL_ISOPCE BITS(14, 15) /*!< isochronous OUT payload continuation encoding */ +#define HCHSTCTL_HADDR BITS(7, 13) /*!< HUB address */ +#define HCHSTCTL_PADDR BITS(0, 6) /*!< port address */ + +/* host channel-x interrupt flag register bits definitions */ +#define HCHINTF_DTER BIT(10) /*!< data toggle error */ +#define HCHINTF_REQOVR BIT(9) /*!< request queue overrun */ +#define HCHINTF_BBER BIT(8) /*!< babble error */ +#define HCHINTF_USBER BIT(7) /*!< USB bus Error */ +#define HCHINTF_NYET BIT(6) /*!< NYET */ +#define HCHINTF_ACK BIT(5) /*!< ACK */ +#define HCHINTF_NAK BIT(4) /*!< NAK */ +#define HCHINTF_STALL BIT(3) /*!< STALL */ +#define HCHINTF_DMAER BIT(2) /*!< DMA error */ +#define HCHINTF_CH BIT(1) /*!< channel halted */ +#define HCHINTF_TF BIT(0) /*!< transfer finished */ + +/* host channel-x interrupt enable register bits definitions */ +#define HCHINTEN_DTERIE BIT(10) /*!< data toggle error interrupt enable */ +#define HCHINTEN_REQOVRIE BIT(9) /*!< request queue overrun interrupt enable */ +#define HCHINTEN_BBERIE BIT(8) /*!< babble error interrupt enable */ +#define HCHINTEN_USBERIE BIT(7) /*!< USB bus error interrupt enable */ +#define HCHINTEN_NYETIE BIT(6) /*!< NYET interrupt enable */ +#define HCHINTEN_ACKIE BIT(5) /*!< ACK interrupt enable */ +#define HCHINTEN_NAKIE BIT(4) /*!< NAK interrupt enable */ +#define HCHINTEN_STALLIE BIT(3) /*!< STALL interrupt enable */ +#define HCHINTEN_DMAERIE BIT(2) /*!< DMA error interrupt enable */ +#define HCHINTEN_CHIE BIT(1) /*!< channel halted interrupt enable */ +#define HCHINTEN_TFIE BIT(0) /*!< transfer finished interrupt enable */ + +/* host channel-x transfer length register bits definitions */ +#define HCHLEN_PING BIT(31) /*!< PING token request */ +#define HCHLEN_DPID BITS(29, 30) /*!< data PID */ +#define HCHLEN_PCNT BITS(19, 28) /*!< packet count */ +#define HCHLEN_TLEN BITS(0, 18) /*!< transfer length */ + +/* host channel-x DMA address register bits definitions */ +#define HCHDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */ + +#define PORT_SPEED(x) (((uint32_t)(x) << 17U) & HPCS_PS) /*!< Port speed */ + +#define PORT_SPEED_HIGH PORT_SPEED(0U) /*!< high speed */ +#define PORT_SPEED_FULL PORT_SPEED(1U) /*!< full speed */ +#define PORT_SPEED_LOW PORT_SPEED(2U) /*!< low speed */ + +#define PIPE_CTL_DAR(x) (((uint32_t)(x) << 22U) & HCHCTL_DAR) /*!< device address */ +#define PIPE_CTL_EPTYPE(x) (((uint32_t)(x) << 18U) & HCHCTL_EPTYPE) /*!< endpoint type */ +#define PIPE_CTL_EPNUM(x) (((uint32_t)(x) << 11U) & HCHCTL_EPNUM) /*!< endpoint number */ +#define PIPE_CTL_EPDIR(x) (((uint32_t)(x) << 15U) & HCHCTL_EPDIR) /*!< endpoint direction */ +#define PIPE_CTL_EPMPL(x) (((uint32_t)(x) << 0U) & HCHCTL_MPL) /*!< maximum packet length */ +#define PIPE_CTL_LSD(x) (((uint32_t)(x) << 17U) & HCHCTL_LSD) /*!< low-Speed device */ + +#define PIPE_XFER_PCNT(x) (((uint32_t)(x) << 19U) & HCHLEN_PCNT) /*!< packet count */ +#define PIPE_XFER_DPID(x) (((uint32_t)(x) << 29U) & HCHLEN_DPID) /*!< data PID */ + +#define PIPE_DPID_DATA0 PIPE_XFER_DPID(0) /*!< DATA0 */ +#define PIPE_DPID_DATA1 PIPE_XFER_DPID(2) /*!< DATA1 */ +#define PIPE_DPID_DATA2 PIPE_XFER_DPID(1) /*!< DATA2 */ +#define PIPE_DPID_SETUP PIPE_XFER_DPID(3) /*!< MDATA (non-control)/SETUP (control) */ + +extern const uint32_t PIPE_DPID[2]; + +/* device configuration registers bits definitions */ +#define DCFG_EOPFT BITS(11, 12) /*!< end of periodic frame time */ +#define DCFG_DAR BITS(4, 10) /*!< device address */ +#define DCFG_NZLSOH BIT(2) /*!< non-zero-length status OUT handshake */ +#define DCFG_DS BITS(0, 1) /*!< device speed */ + +/* device control registers bits definitions */ +#define DCTL_POIF BIT(11) /*!< power-on initialization finished */ +#define DCTL_CGONAK BIT(10) /*!< clear global OUT NAK */ +#define DCTL_SGONAK BIT(9) /*!< set global OUT NAK */ +#define DCTL_CGINAK BIT(8) /*!< clear global IN NAK */ +#define DCTL_SGINAK BIT(7) /*!< set global IN NAK */ +#define DCTL_DTEST BITS(4, 6) /*!< device test control */ +#define DCTL_GONS BIT(3) /*!< global OUT NAK status */ +#define DCTL_GINS BIT(2) /*!< global IN NAK status */ +#define DCTL_SD BIT(1) /*!< soft disconnect */ +#define DCTL_RWKUP BIT(0) /*!< remote wakeup */ + +/* device status registers bits definitions */ +#define DSTAT_FNRSOF BITS(8, 21) /*!< the frame number of the received SOF. */ +#define DSTAT_ES BITS(1, 2) /*!< enumerated speed */ +#define DSTAT_SPST BIT(0) /*!< suspend status */ + +/* device IN endpoint common interrupt enable registers bits definitions */ +#define DIEPINTEN_NAKEN BIT(13) /*!< NAK handshake sent by USBHS interrupt enable bit */ +#define DIEPINTEN_TXFEEN BIT(7) /*!< transmit FIFO empty interrupt enable bit */ +#define DIEPINTEN_IEPNEEN BIT(6) /*!< IN endpoint NAK effective interrupt enable bit */ +#define DIEPINTEN_EPTXFUDEN BIT(4) /*!< endpoint Tx FIFO underrun interrupt enable bit */ +#define DIEPINTEN_CITOEN BIT(3) /*!< control In Timeout interrupt enable bit */ +#define DIEPINTEN_EPDISEN BIT(1) /*!< endpoint disabled interrupt enable bit */ +#define DIEPINTEN_TFEN BIT(0) /*!< transfer finished interrupt enable bit */ + +/* device OUT endpoint common interrupt enable registers bits definitions */ +#define DOEPINTEN_NYETEN BIT(14) /*!< NYET handshake is sent interrupt enable bit */ +#define DOEPINTEN_BTBSTPEN BIT(6) /*!< back-to-back SETUP packets interrupt enable bit */ +#define DOEPINTEN_EPRXFOVREN BIT(4) /*!< endpoint Rx FIFO overrun interrupt enable bit */ +#define DOEPINTEN_STPFEN BIT(3) /*!< SETUP phase finished interrupt enable bit */ +#define DOEPINTEN_EPDISEN BIT(1) /*!< endpoint disabled interrupt enable bit */ +#define DOEPINTEN_TFEN BIT(0) /*!< transfer finished interrupt enable bit */ + +/* device all endpoints interrupt registers bits definitions */ +#define DAEPINT_OEPITB BITS(16, 21) /*!< device all OUT endpoint interrupt bits */ +#define DAEPINT_IEPITB BITS(0, 5) /*!< device all IN endpoint interrupt bits */ + +/* device all endpoints interrupt enable registers bits definitions */ +#define DAEPINTEN_OEPIE BITS(16, 21) /*!< OUT endpoint interrupt enable */ +#define DAEPINTEN_IEPIE BITS(0, 3) /*!< IN endpoint interrupt enable */ + +/* device VBUS discharge time registers bits definitions */ +#define DVBUSDT_DVBUSDT BITS(0, 15) /*!< device VBUS discharge time */ + +/* device VBUS pulsing time registers bits definitions */ +#define DVBUSPT_DVBUSPT BITS(0, 11) /*!< device VBUS pulsing time */ + +/* device IN endpoint FIFO empty interrupt enable register bits definitions */ +#define DIEPFEINTEN_IEPTXFEIE BITS(0, 5) /*!< IN endpoint Tx FIFO empty interrupt enable bits */ + +/* device endpoint 0 control register bits definitions */ +#define DEP0CTL_EPEN BIT(31) /*!< endpoint enable */ +#define DEP0CTL_EPD BIT(30) /*!< endpoint disable */ +#define DEP0CTL_SNAK BIT(27) /*!< set NAK */ +#define DEP0CTL_CNAK BIT(26) /*!< clear NAK */ +#define DIEP0CTL_TXFNUM BITS(22, 25) /*!< tx FIFO number */ +#define DEP0CTL_STALL BIT(21) /*!< STALL handshake */ +#define DOEP0CTL_SNOOP BIT(20) /*!< snoop mode */ +#define DEP0CTL_EPTYPE BITS(18, 19) /*!< endpoint type */ +#define DEP0CTL_NAKS BIT(17) /*!< NAK status */ +#define DEP0CTL_EPACT BIT(15) /*!< endpoint active */ +#define DEP0CTL_MPL BITS(0, 1) /*!< maximum packet length */ + +/* device endpoint x control register bits definitions */ +#define DEPCTL_EPEN BIT(31) /*!< endpoint enable */ +#define DEPCTL_EPD BIT(30) /*!< endpoint disable */ +#define DEPCTL_SODDFRM BIT(29) /*!< set odd frame */ +#define DEPCTL_SD1PID BIT(29) /*!< set DATA1 PID */ +#define DEPCTL_SEVNFRM BIT(28) /*!< set even frame */ +#define DEPCTL_SD0PID BIT(28) /*!< set DATA0 PID */ +#define DEPCTL_SNAK BIT(27) /*!< set NAK */ +#define DEPCTL_CNAK BIT(26) /*!< clear NAK */ +#define DIEPCTL_TXFNUM BITS(22, 25) /*!< tx FIFO number */ +#define DEPCTL_STALL BIT(21) /*!< STALL handshake */ +#define DOEPCTL_SNOOP BIT(20) /*!< snoop mode */ +#define DEPCTL_EPTYPE BITS(18, 19) /*!< endpoint type */ +#define DEPCTL_NAKS BIT(17) /*!< NAK status */ +#define DEPCTL_EOFRM BIT(16) /*!< even/odd frame */ +#define DEPCTL_DPID BIT(16) /*!< endpoint data PID */ +#define DEPCTL_EPACT BIT(15) /*!< endpoint active */ +#define DEPCTL_MPL BITS(0, 10) /*!< maximum packet length */ + +/* device IN endpoint-x interrupt flag register bits definitions */ +#define DIEPINTF_NAK BIT(13) /*!< NAK handshake sent by USBHS */ +#define DIEPINTF_TXFE BIT(7) /*!< transmit FIFO empty */ +#define DIEPINTF_IEPNE BIT(6) /*!< IN endpoint NAK effective */ +#define DIEPINTF_EPTXFUD BIT(4) /*!< endpoint Tx FIFO underrun */ +#define DIEPINTF_CITO BIT(3) /*!< control In Timeout interrupt */ +#define DIEPINTF_EPDIS BIT(1) /*!< endpoint disabled */ +#define DIEPINTF_TF BIT(0) /*!< transfer finished */ + +/* device OUT endpoint-x interrupt flag register bits definitions */ +#define DOEPINTF_NYET BIT(14) /*!< NYET handshake is sent */ +#define DOEPINTF_BTBSTP BIT(6) /*!< back-to-back SETUP packets */ +#define DOEPINTF_EPRXFOVR BIT(4) /*!< endpoint Rx FIFO overrun */ +#define DOEPINTF_STPF BIT(3) /*!< SETUP phase finished */ +#define DOEPINTF_EPDIS BIT(1) /*!< endpoint disabled */ +#define DOEPINTF_TF BIT(0) /*!< transfer finished */ + +/* device IN endpoint 0 transfer length register bits definitions */ +#define DIEP0LEN_PCNT BITS(19, 20) /*!< packet count */ +#define DIEP0LEN_TLEN BITS(0, 6) /*!< transfer length */ + +/* device OUT endpoint 0 transfer length register bits definitions */ +#define DOEP0LEN_STPCNT BITS(29, 30) /*!< SETUP packet count */ +#define DOEP0LEN_PCNT BIT(19) /*!< packet count */ +#define DOEP0LEN_TLEN BITS(0, 6) /*!< transfer length */ + +/* device OUT endpoint-x transfer length register bits definitions */ +#define DOEPLEN_RXDPID BITS(29, 30) /*!< received data PID */ +#define DOEPLEN_STPCNT BITS(29, 30) /*!< SETUP packet count */ +#define DIEPLEN_MCNT BITS(29, 30) /*!< multi count */ +#define DEPLEN_PCNT BITS(19, 28) /*!< packet count */ +#define DEPLEN_TLEN BITS(0, 18) /*!< transfer length */ + +/* device IN endpoint-x DMA address register bits definitions */ +#define DIEPDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */ + +/* device OUT endpoint-x DMA address register bits definitions */ +#define DOEPDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */ + +/* device IN endpoint-x transmit FIFO status register bits definitions */ +#define DIEPTFSTAT_IEPTFS BITS(0, 15) /*!< IN endpoint Tx FIFO space remaining */ + +/* USB power and clock registers bits definition */ +#define PWRCLKCTL_SHCLK BIT(1) /*!< stop HCLK */ +#define PWRCLKCTL_SUCLK BIT(0) /*!< stop the USB clock */ + +#define RSTAT_GOUT_NAK 1U /* global OUT NAK (triggers an interrupt) */ +#define RSTAT_DATA_UPDT 2U /* OUT data packet received */ +#define RSTAT_XFER_COMP 3U /* OUT transfer completed (triggers an interrupt) */ +#define RSTAT_SETUP_COMP 4U /* SETUP transaction completed (triggers an interrupt) */ +#define RSTAT_SETUP_UPDT 6U /* SETUP data packet received */ + +#define DSTAT_EM_HS_PHY_30MHZ_60MHZ 0U /* USB enumerate speed use high-speed PHY clock in 30MHz or 60MHz */ +#define DSTAT_EM_FS_PHY_30MHZ_60MHZ 1U /* USB enumerate speed use full-speed PHY clock in 30MHz or 60MHz */ +#define DSTAT_EM_LS_PHY_6MHZ 2U /* USB enumerate speed use low-speed PHY clock in 6MHz */ +#define DSTAT_EM_FS_PHY_48MHZ 3U /* USB enumerate speed use full-speed PHY clock in 48MHz */ + +#define DPID_DATA0 0U /* device endpoint data PID is DATA0 */ +#define DPID_DATA1 2U /* device endpoint data PID is DATA1 */ +#define DPID_DATA2 1U /* device endpoint data PID is DATA2 */ +#define DPID_MDATA 3U /* device endpoint data PID is MDATA */ + +#define GAHBCS_DMAINCR(regval) (GAHBCS_BURST & ((regval) << 1U)) /*!< AHB burst type used by DMA*/ + +#define DMA_INCR0 GAHBCS_DMAINCR(0U) /*!< single burst type used by DMA*/ +#define DMA_INCR1 GAHBCS_DMAINCR(1U) /*!< 4-beat incrementing burst type used by DMA*/ +#define DMA_INCR4 GAHBCS_DMAINCR(3U) /*!< 8-beat incrementing burst type used by DMA*/ +#define DMA_INCR8 GAHBCS_DMAINCR(5U) /*!< 16-beat incrementing burst type used by DMA*/ +#define DMA_INCR16 GAHBCS_DMAINCR(7U) /*!< 32-beat incrementing burst type used by DMA*/ + +#define DCFG_PFRI(regval) (DCFG_EOPFT & ((regval) << 11U)) /*!< end of periodic frame time configuration */ + +#define FRAME_INTERVAL_80 DCFG_PFRI(0U) /*!< 80% of the frame time */ +#define FRAME_INTERVAL_85 DCFG_PFRI(1U) /*!< 85% of the frame time */ +#define FRAME_INTERVAL_90 DCFG_PFRI(2U) /*!< 90% of the frame time */ +#define FRAME_INTERVAL_95 DCFG_PFRI(3U) /*!< 95% of the frame time */ + +#define DCFG_DEVSPEED(regval) (DCFG_DS & ((regval) << 0U)) /*!< device speed configuration */ + +#define USB_SPEED_EXP_HIGH DCFG_DEVSPEED(0U) /*!< device external PHY high speed */ +#define USB_SPEED_EXP_FULL DCFG_DEVSPEED(1U) /*!< device external PHY full speed */ +#define USB_SPEED_INP_FULL DCFG_DEVSPEED(3U) /*!< device internal PHY full speed */ + +#define DEP0_MPL(regval) (DEP0CTL_MPL & ((regval) << 0U)) /*!< maximum packet length configuration */ + +#define EP0MPL_64 DEP0_MPL(0U) /*!< maximum packet length 64 bytes */ +#define EP0MPL_32 DEP0_MPL(1U) /*!< maximum packet length 32 bytes */ +#define EP0MPL_16 DEP0_MPL(2U) /*!< maximum packet length 16 bytes */ +#define EP0MPL_8 DEP0_MPL(3U) /*!< maximum packet length 8 bytes */ + +#define DOEP0_TLEN(regval) (DOEP0LEN_TLEN & ((regval) << 0)) /*!< transfer length */ +#define DOEP0_PCNT(regval) (DOEP0LEN_PCNT & ((regval) << 19)) /*!< packet count */ +#define DOEP0_STPCNT(regval) (DOEP0LEN_STPCNT & ((regval) << 29)) /*!< SETUP packet count */ + +#define USB_ULPI_PHY 1U /*!< ULPI interface external PHY */ +#define USB_EMBEDDED_PHY 2U /*!< embedded PHY */ + +#define GRXSTS_PKTSTS_IN 2U +#define GRXSTS_PKTSTS_IN_XFER_COMP 3U +#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5U +#define GRXSTS_PKTSTS_CH_HALTED 7U + +#define HCTL_30_60MHZ 0U /*!< USB clock 30-60MHZ */ +#define HCTL_48MHZ 1U /*!< USB clock 48MHZ */ +#define HCTL_6MHZ 2U /*!< USB clock 6MHZ */ + +#define EP0_OUT ((uint8_t)0x00U) /*!< endpoint out 0 */ +#define EP0_IN ((uint8_t)0x80U) /*!< endpoint in 0 */ +#define EP1_OUT ((uint8_t)0x01U) /*!< endpoint out 1 */ +#define EP1_IN ((uint8_t)0x81U) /*!< endpoint in 1 */ +#define EP2_OUT ((uint8_t)0x02U) /*!< endpoint out 2 */ +#define EP2_IN ((uint8_t)0x82U) /*!< endpoint in 2 */ +#define EP3_OUT ((uint8_t)0x03U) /*!< endpoint out 3 */ +#define EP3_IN ((uint8_t)0x83U) /*!< endpoint in 3 */ +#define EP4_OUT ((uint8_t)0x04U) /*!< endpoint out 4 */ +#define EP4_IN ((uint8_t)0x84U) /*!< endpoint in 4 */ +#define EP5_OUT ((uint8_t)0x05U) /*!< endpoint out 5 */ +#define EP5_IN ((uint8_t)0x85U) /*!< endpoint in 5 */ + +#endif /* __DRV_USB_REGS_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usbd_int.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usbd_int.h new file mode 100644 index 0000000..3967ca0 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usbd_int.h @@ -0,0 +1,52 @@ +/*! + \file drv_usbd_int.h + \brief USB device mode interrupt header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DRV_USBD_INT_H +#define __DRV_USBD_INT_H + +#include "drv_usb_core.h" +#include "drv_usb_dev.h" + +/* function declarations */ +/* USB device-mode interrupts global service routine handler */ +void usbd_isr (usb_core_driver *udev); + +#ifdef USB_HS_DEDICATED_EP1_ENABLED +/* USB dedicated IN endpoint 1 interrupt service routine handler */ +uint32_t usbd_int_dedicated_ep1in (usb_core_driver *udev); +/* USB dedicated OUT endpoint 1 interrupt service routine handler */ +uint32_t usbd_int_dedicated_ep1out (usb_core_driver *udev); +#endif /* USB_HS_DEDICATED_EP1_ENABLED */ + +#endif /* __DRV_USBD_INT_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usbh_int.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usbh_int.h new file mode 100644 index 0000000..3bda76d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Include/drv_usbh_int.h @@ -0,0 +1,54 @@ +/*! + \file drv_usbh_int.h.h + \brief USB host mode interrupt management header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __DRV_USBH_INT_H +#define __DRV_USBH_INT_H + +#include "drv_usb_host.h" +#include "usbh_core.h" + +typedef struct _usbh_ev_cb +{ + uint8_t (*connect) (usbh_host *uhost); + uint8_t (*disconnect) (usbh_host *uhost); + uint8_t (*SOF) (usbh_host *uhost); +} usbh_ev_cb; + +extern usbh_ev_cb *usbh_int_fop; + +/* function declarations */ +/* handle global host interrupt */ +uint32_t usbh_isr (usb_core_driver *udev); + +#endif /* __DRV_USBH_INT_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_core.c new file mode 100644 index 0000000..2f3a73e --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_core.c @@ -0,0 +1,372 @@ +/*! + \file drv_usb_core.c + \brief USB core driver which can operate in host and device mode + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "drv_usb_core.h" +#include "drv_usb_hw.h" + +/* local function prototypes ('static') */ +static void usb_core_reset (usb_core_regs *usb_regs); + +/*! + \brief configure USB core basic + \param[in] usb_basic: pointer to USB capabilities + \param[in] usb_regs: USB core registers + \param[in] usb_core: USB core + \param[out] none + \retval operation status +*/ +usb_status usb_basic_init (usb_core_basic *usb_basic, + usb_core_regs *usb_regs, + usb_core_enum usb_core) +{ + /* configure USB default transfer mode as FIFO mode */ + usb_basic->transfer_mode = (uint8_t)USB_USE_FIFO; + + /* USB default speed is full-speed */ + usb_basic->core_speed = (uint8_t)USB_SPEED_FULL; + + usb_basic->core_enum = (uint8_t)usb_core; + + switch (usb_core) { + case USB_CORE_ENUM_HS: + usb_basic->base_reg = (uint32_t)USBHS_REG_BASE; + + /* set the host channel numbers */ + usb_basic->num_pipe = USBHS_MAX_CHANNEL_COUNT; + + /* set the device endpoint numbers */ + usb_basic->num_ep = USBHS_MAX_EP_COUNT; + +#ifdef USB_ULPI_PHY_ENABLED + usb_basic->phy_itf = USB_ULPI_PHY; +#else + usb_basic->phy_itf = USB_EMBEDDED_PHY; +#endif /* USB_ULPI_PHY_ENABLED */ + +#ifdef USB_HS_INTERNAL_DMA_ENABLED + usb_basic->transfer_mode = USB_USE_DMA; +#endif /* USB_HS_INTERNAL_DMA_ENABLED */ + +#ifdef USB_HS_CORE + /* configure the SOF output and the low power support */ + usb_basic->sof_enable = USBHS_SOF_OUTPUT; + usb_basic->low_power = USBHS_LOW_POWER; +#endif /* USB_HS_CORE */ + break; + + case USB_CORE_ENUM_FS: + usb_basic->base_reg = (uint32_t)USBFS_REG_BASE; + + /* set the host channel numbers */ + usb_basic->num_pipe = USBFS_MAX_CHANNEL_COUNT; + + /* set the device endpoint numbers */ + usb_basic->num_ep = USBFS_MAX_EP_COUNT; + + /* USBFS core use embedded physical layer */ + usb_basic->phy_itf = USB_EMBEDDED_PHY; + +#ifdef USB_FS_CORE + /* configure the SOF output and the low power support */ + usb_basic->sof_enable = USBFS_SOF_OUTPUT; + usb_basic->low_power = USBFS_LOW_POWER; +#endif /* USB_FS_CORE */ + break; + + default: + return USB_FAIL; + } + + /* assign main registers address */ + *usb_regs = (usb_core_regs) { + .gr = (usb_gr*) (usb_basic->base_reg + USB_REG_OFFSET_CORE), + .hr = (usb_hr*) (usb_basic->base_reg + USB_REG_OFFSET_HOST), + .dr = (usb_dr*) (usb_basic->base_reg + USB_REG_OFFSET_DEV), + + .HPCS = (uint32_t*) (usb_basic->base_reg + USB_REG_OFFSET_PORT), + .PWRCLKCTL = (uint32_t*) (usb_basic->base_reg + USB_REG_OFFSET_PWRCLKCTL) + }; + + /* assign device endpoint registers address */ + for (uint8_t i = 0U; i < usb_basic->num_ep; i++) { + usb_regs->er_in[i] = (usb_erin *) \ + (usb_basic->base_reg + USB_REG_OFFSET_EP_IN + (i * USB_REG_OFFSET_EP)); + + usb_regs->er_out[i] = (usb_erout *)\ + (usb_basic->base_reg + USB_REG_OFFSET_EP_OUT + (i * USB_REG_OFFSET_EP)); + } + + /* assign host pipe registers address */ + for (uint8_t i = 0U; i < usb_basic->num_pipe; i++) { + usb_regs->pr[i] = (usb_pr *) \ + (usb_basic->base_reg + USB_REG_OFFSET_CH_INOUT + (i * USB_REG_OFFSET_CH)); + + usb_regs->DFIFO[i] = (uint32_t *) \ + (usb_basic->base_reg + USB_DATA_FIFO_OFFSET + (i * USB_DATA_FIFO_SIZE)); + } + + return USB_OK; +} + +/*! + \brief initializes the USB controller registers and + prepares the core device mode or host mode operation + \param[in] usb_basic: pointer to USB capabilities + \param[in] usb_regs: pointer to USB core registers + \param[out] none + \retval operation status +*/ +usb_status usb_core_init (usb_core_basic usb_basic, usb_core_regs *usb_regs) +{ + if (USB_ULPI_PHY == usb_basic.phy_itf) { + usb_regs->gr->GCCFG &= ~GCCFG_PWRON; + + if (usb_basic.sof_enable) { + usb_regs->gr->GCCFG |= GCCFG_SOFOEN; + } + + /* initialize the ULPI interface */ + usb_regs->gr->GUSBCS &= ~(GUSBCS_EMBPHY | GUSBCS_ULPIEOI); + +#ifdef USBHS_EXTERNAL_VBUS_ENABLED + /* use external VBUS driver */ + usb_regs->gr->GUSBCS |= GUSBCS_ULPIEVD; +#else + /* use internal VBUS driver */ + usb_regs->gr->GUSBCS &= ~GUSBCS_ULPIEVD; +#endif /* USBHS_EXTERNAL_VBUS_ENABLED */ + + /* soft reset the core */ + usb_core_reset (usb_regs); + } else { + usb_regs->gr->GUSBCS |= GUSBCS_EMBPHY; + + /* soft reset the core */ + usb_core_reset (usb_regs); + + /* active the transceiver and enable VBUS sensing */ + usb_regs->gr->GCCFG |= GCCFG_PWRON | GCCFG_VBUSACEN | GCCFG_VBUSBCEN; + +#ifndef VBUS_SENSING_ENABLED + usb_regs->gr->GCCFG |= GCCFG_VBUSIG; +#endif /* VBUS_SENSING_ENABLED */ + + /* enable SOF output */ + if (usb_basic.sof_enable) { + usb_regs->gr->GCCFG |= GCCFG_SOFOEN; + } + + usb_mdelay(20U); + } + + if ((uint8_t)USB_USE_DMA == usb_basic.transfer_mode) { + usb_regs->gr->GAHBCS &= ~GAHBCS_BURST; + usb_regs->gr->GAHBCS |= DMA_INCR8 | GAHBCS_DMAEN; + } + +#ifdef USE_OTG_MODE + + /* enable USB OTG features */ + usb_regs->gr->GUSBCS |= GUSBCS_HNPCEN | GUSBCS_SRPCEN; + + /* enable the USB wakeup and suspend interrupts */ + usb_regs->gr->GINTF = 0xBFFFFFFFU; + + usb_regs->gr->GINTEN = GINTEN_WKUPIE | GINTEN_SPIE | \ + GINTEN_OTGIE | GINTEN_SESIE | GINTEN_CIDPSCIE; + +#endif /* USE_OTG_MODE */ + + return USB_OK; +} + +/*! + \brief write a packet into the Tx FIFO associated with the endpoint + \param[in] usb_regs: pointer to USB core registers + \param[in] src_buf: pointer to source buffer + \param[in] fifo_num: FIFO number which is in (0..3 or 0..5) + \param[in] byte_count: packet byte count + \param[out] none + \retval operation status +*/ +usb_status usb_txfifo_write (usb_core_regs *usb_regs, + uint8_t *src_buf, + uint8_t fifo_num, + uint16_t byte_count) +{ + uint32_t word_count = (byte_count + 3U) / 4U; + + __IO uint32_t *fifo = usb_regs->DFIFO[fifo_num]; + + while (word_count-- > 0U) { + *fifo = *((uint32_t *)src_buf); + + src_buf += 4U; + } + + return USB_OK; +} + +/*! + \brief read a packet from the Rx FIFO associated with the endpoint + \param[in] usb_regs: pointer to USB core registers + \param[in] dest_buf: pointer to destination buffer + \param[in] byte_count: packet byte count + \param[out] none + \retval void type pointer +*/ +void *usb_rxfifo_read (usb_core_regs *usb_regs, uint8_t *dest_buf, uint16_t byte_count) +{ + uint32_t word_count = (byte_count + 3U) / 4U; + + __IO uint32_t *fifo = usb_regs->DFIFO[0]; + + while (word_count-- > 0U) { + *(uint32_t *)dest_buf = *fifo; + + dest_buf += 4U; + } + + return ((void *)dest_buf); +} + +/*! + \brief flush a Tx FIFO or all Tx FIFOs + \param[in] usb_regs: pointer to USB core registers + \param[in] fifo_num: FIFO number which is in (0..3 or 0..5) + \param[out] none + \retval operation status +*/ +usb_status usb_txfifo_flush (usb_core_regs *usb_regs, uint8_t fifo_num) +{ + usb_regs->gr->GRSTCTL = ((uint32_t)fifo_num << 6U) | GRSTCTL_TXFF; + + /* wait for Tx FIFO flush bit is set */ + while (usb_regs->gr->GRSTCTL & GRSTCTL_TXFF) { + /* no operation */ + } + + /* wait for 3 PHY clocks*/ + usb_udelay(3U); + + return USB_OK; +} + +/*! + \brief flush the entire Rx FIFO + \param[in] usb_regs: pointer to USB core registers + \param[out] none + \retval operation status +*/ +usb_status usb_rxfifo_flush (usb_core_regs *usb_regs) +{ + usb_regs->gr->GRSTCTL = GRSTCTL_RXFF; + + /* wait for Rx FIFO flush bit is set */ + while (usb_regs->gr->GRSTCTL & GRSTCTL_RXFF) { + /* no operation */ + } + + /* wait for 3 PHY clocks */ + usb_udelay(3U); + + return USB_OK; +} + +/*! + \brief set endpoint or channel TX FIFO size + \param[in] usb_regs: pointer to USB core registers + \param[in] fifo: TX FIFO number + \param[in] size: assigned TX FIFO size + \param[out] none + \retval none +*/ +void usb_set_txfifo(usb_core_regs *usb_regs, uint8_t fifo, uint16_t size) +{ + uint32_t tx_offset; + + tx_offset = usb_regs->gr->GRFLEN; + + if(0U == fifo) { + usb_regs->gr->DIEP0TFLEN_HNPTFLEN = ((uint32_t)size << 16) | tx_offset; + } else { + tx_offset += (usb_regs->gr->DIEP0TFLEN_HNPTFLEN) >> 16; + + for (uint8_t i = 0U; i < (fifo - 1U); i++) { + tx_offset += (usb_regs->gr->DIEPTFLEN[i] >> 16); + } + + /* multiply Tx_Size by 2 to get higher performance */ + usb_regs->gr->DIEPTFLEN[fifo - 1U] = ((uint32_t)size << 16) | tx_offset; + } +} + +/*! + \brief set USB current mode + \param[in] usb_regs: pointer to USB core registers + \param[out] none + \retval none +*/ +void usb_curmode_set(usb_core_regs *usb_regs, uint8_t mode) +{ + usb_regs->gr->GUSBCS &= ~(GUSBCS_FDM | GUSBCS_FHM); + + if (DEVICE_MODE == mode) { + usb_regs->gr->GUSBCS |= GUSBCS_FDM; + } else if (HOST_MODE == mode) { + usb_regs->gr->GUSBCS |= GUSBCS_FHM; + } else { + /* OTG mode and other mode can not be here! */ + } +} + +/*! + \brief configure USB core to soft reset + \param[in] usb_regs: pointer to USB core registers + \param[out] none + \retval none +*/ +static void usb_core_reset (usb_core_regs *usb_regs) +{ + /* enable core soft reset */ + usb_regs->gr->GRSTCTL |= GRSTCTL_CSRST; + + /* wait for the core to be soft reset */ + while (usb_regs->gr->GRSTCTL & GRSTCTL_CSRST) { + /* no operation */ + } + + /* wait for additional 3 PHY clocks */ + usb_udelay(3U); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_dev.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_dev.c new file mode 100644 index 0000000..d292862 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_dev.c @@ -0,0 +1,664 @@ +/*! + \file drv_usb_dev.c + \brief USB device mode low level driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "drv_usb_hw.h" +#include "drv_usb_core.h" +#include "drv_usb_dev.h" + +/* endpoint 0 max packet length */ +static const uint8_t EP0_MAXLEN[4] = { + [DSTAT_EM_HS_PHY_30MHZ_60MHZ] = EP0MPL_64, + [DSTAT_EM_FS_PHY_30MHZ_60MHZ] = EP0MPL_64, + [DSTAT_EM_FS_PHY_48MHZ] = EP0MPL_64, + [DSTAT_EM_LS_PHY_6MHZ] = EP0MPL_8 +}; + +#ifdef USB_FS_CORE + +/* USB endpoint Tx FIFO size */ +static uint16_t USBFS_TX_FIFO_SIZE[USBFS_MAX_EP_COUNT] = +{ + (uint16_t)TX0_FIFO_FS_SIZE, + (uint16_t)TX1_FIFO_FS_SIZE, + (uint16_t)TX2_FIFO_FS_SIZE, + (uint16_t)TX3_FIFO_FS_SIZE +}; + +#endif /* USBFS_CORE */ + +#ifdef USB_HS_CORE + +uint16_t USBHS_TX_FIFO_SIZE[USBHS_MAX_EP_COUNT] = +{ + (uint16_t)TX0_FIFO_HS_SIZE, + (uint16_t)TX1_FIFO_HS_SIZE, + (uint16_t)TX2_FIFO_HS_SIZE, + (uint16_t)TX3_FIFO_HS_SIZE, + (uint16_t)TX4_FIFO_HS_SIZE, + (uint16_t)TX5_FIFO_HS_SIZE +}; + +#endif /* USBHS_CORE */ + +/*! + \brief initialize USB core registers for device mode + \param[in] udev: pointer to USB device + \param[out] none + \retval operation status +*/ +usb_status usb_devcore_init (usb_core_driver *udev) +{ + uint8_t i; + + /* restart the PHY clock (maybe don't need to...) */ + *udev->regs.PWRCLKCTL = 0U; + + /* configure periodic frame interval to default value */ + udev->regs.dr->DCFG &= ~DCFG_EOPFT; + udev->regs.dr->DCFG |= FRAME_INTERVAL_80; + + udev->regs.dr->DCFG &= ~DCFG_DS; + +#ifdef USB_FS_CORE + if (udev->bp.core_enum == (uint8_t)USB_CORE_ENUM_FS) { + /* set full-speed PHY */ + udev->regs.dr->DCFG |= USB_SPEED_INP_FULL; + + /* set Rx FIFO size */ + usb_set_rxfifo(&udev->regs, RX_FIFO_FS_SIZE); + + /* set endpoint 0 to 3's Tx FIFO length and RAM address */ + for (i = 0U; i < USBFS_MAX_EP_COUNT; i++) { + usb_set_txfifo(&udev->regs, i, USBFS_TX_FIFO_SIZE[i]); + } + } +#endif /* USB_FS_CORE */ + +#ifdef USB_HS_CORE + if (udev->bp.core_enum == USB_CORE_ENUM_HS) { + if (udev->bp.phy_itf == USB_ULPI_PHY) { + udev->regs.dr->DCFG |= USB_SPEED_EXP_HIGH; + } else {/* set High speed PHY in Full speed mode */ + udev->regs.dr->DCFG |= USB_SPEED_EXP_FULL; + } + + /* Set Rx FIFO size */ + usb_set_rxfifo(&udev->regs, RX_FIFO_HS_SIZE); + + /* Set endpoint 0 to 6's TX FIFO length and RAM address */ + for (i = 0; i < USBHS_MAX_EP_COUNT; i++) { + usb_set_txfifo(&udev->regs, i, USBHS_TX_FIFO_SIZE[i]); + } + } +#endif /* USB_FS_CORE */ + + /* make sure all FIFOs are flushed */ + + /* flush all Tx FIFOs */ + (void)usb_txfifo_flush (&udev->regs, 0x10U); + + /* flush entire Rx FIFO */ + (void)usb_rxfifo_flush (&udev->regs); + + /* clear all pending device interrupts */ + udev->regs.dr->DIEPINTEN = 0U; + udev->regs.dr->DOEPINTEN = 0U; + udev->regs.dr->DAEPINT = 0xFFFFFFFFU; + udev->regs.dr->DAEPINTEN = 0U; + + /* configure all IN/OUT endpoints */ + for (i = 0U; i < udev->bp.num_ep; i++) { + if (udev->regs.er_in[i]->DIEPCTL & DEPCTL_EPEN) { + udev->regs.er_in[i]->DIEPCTL |= DEPCTL_EPD | DEPCTL_SNAK; + } else { + udev->regs.er_in[i]->DIEPCTL = 0U; + } + + /* set IN endpoint transfer length to 0 */ + udev->regs.er_in[i]->DIEPLEN = 0U; + + /* clear all pending IN endpoint interrupts */ + udev->regs.er_in[i]->DIEPINTF = 0xFFU; + + if (udev->regs.er_out[i]->DOEPCTL & DEPCTL_EPEN) { + udev->regs.er_out[i]->DOEPCTL |= DEPCTL_EPD | DEPCTL_SNAK; + } else { + udev->regs.er_out[i]->DOEPCTL = 0U; + } + + /* set OUT endpoint transfer length to 0 */ + udev->regs.er_out[i]->DOEPLEN = 0U; + + /* clear all pending OUT endpoint interrupts */ + udev->regs.er_out[i]->DOEPINTF = 0xFFU; + } + + udev->regs.dr->DIEPINTEN |= DIEPINTEN_EPTXFUDEN; + + (void)usb_devint_enable (udev); + + return USB_OK; +} + +/*! + \brief enable the USB device mode interrupts + \param[in] udev: pointer to USB device + \param[out] none + \retval operation status +*/ +usb_status usb_devint_enable (usb_core_driver *udev) +{ + /* clear any pending USB OTG interrupts */ + udev->regs.gr->GOTGINTF = 0xFFFFFFFFU; + + /* clear any pending interrupts */ + udev->regs.gr->GINTF = 0xBFFFFFFFU; + + /* enable the USB wakeup and suspend interrupts */ + udev->regs.gr->GINTEN = GINTEN_WKUPIE | GINTEN_SPIE; + + /* enable device_mode-related interrupts */ + if ((uint8_t)USB_USE_FIFO == udev->bp.transfer_mode) { + udev->regs.gr->GINTEN |= GINTEN_RXFNEIE; + } + + udev->regs.gr->GINTEN |= GINTEN_RSTIE | GINTEN_ENUMFIE | GINTEN_IEPIE |\ + GINTEN_OEPIE | GINTEN_SOFIE | GINTEN_ISOONCIE | GINTEN_ISOINCIE; + +#ifdef VBUS_SENSING_ENABLED + udev->regs.gr->GINTEN |= GINTEN_SESIE | GINTEN_OTGIE; +#endif /* VBUS_SENSING_ENABLED */ + + return USB_OK; +} + +/*! + \brief active the USB endpoint0 transaction + \param[in] udev: pointer to USB device + \param[in] transc: the USB endpoint0 transaction + \param[out] none + \retval operation status +*/ +usb_status usb_transc0_active (usb_core_driver *udev, usb_transc *transc) +{ + __IO uint32_t *reg_addr = NULL; + + uint8_t enum_speed = udev->regs.dr->DSTAT & DSTAT_ES; + + /* get the endpoint number */ + uint8_t ep_num = transc->ep_addr.num; + + if (ep_num) { + /* not endpoint 0 */ + return USB_FAIL; + } + + if (transc->ep_addr.dir) { + reg_addr = &udev->regs.er_in[0]->DIEPCTL; + } else { + reg_addr = &udev->regs.er_out[0]->DOEPCTL; + } + + /* endpoint 0 is activated after USB clock is enabled */ + *reg_addr &= ~(DEPCTL_MPL | DEPCTL_EPTYPE | DIEPCTL_TXFNUM); + + /* set endpoint 0 maximum packet length */ + *reg_addr |= EP0_MAXLEN[enum_speed]; + + /* activate endpoint */ + *reg_addr |= ((uint32_t)transc->ep_type << 18U) | ((uint32_t)ep_num << 22U) | DEPCTL_SD0PID | DEPCTL_EPACT; + + return USB_OK; +} + +/*! + \brief active the USB transaction + \param[in] udev: pointer to USB device + \param[in] transc: the USB transaction + \param[out] none + \retval status +*/ +usb_status usb_transc_active (usb_core_driver *udev, usb_transc *transc) +{ + __IO uint32_t *reg_addr = NULL; + uint32_t epinten = 0U; + uint8_t enum_speed = udev->regs.dr->DSTAT & DSTAT_ES; + + /* get the endpoint number */ + uint8_t ep_num = transc->ep_addr.num; + + /* enable endpoint interrupt number */ + if (transc->ep_addr.dir) { + reg_addr = &udev->regs.er_in[ep_num]->DIEPCTL; + + epinten = 1U << ep_num; + } else { + reg_addr = &udev->regs.er_out[ep_num]->DOEPCTL; + + epinten = 1U << (16U + ep_num); + } + + /* if the endpoint is not active, need change the endpoint control register */ + if (!(*reg_addr & DEPCTL_EPACT)) { + *reg_addr &= ~(DEPCTL_MPL | DEPCTL_EPTYPE | DIEPCTL_TXFNUM); + + /* set endpoint maximum packet length */ + if (0U == ep_num) { + *reg_addr |= EP0_MAXLEN[enum_speed]; + } else { + *reg_addr |= transc->max_len; + } + + /* activate endpoint */ + *reg_addr |= ((uint32_t)transc->ep_type << 18U) | ((uint32_t)ep_num << 22U) | DEPCTL_SD0PID | DEPCTL_EPACT; + } + +#ifdef USB_HS_DEDICATED_EP1_ENABLED + if ((ep_num == 1U) && (udev->bp.core_enum == USB_CORE_ENUM_HS)) { + udev->regs.dr->DEP1INTEN |= epinten; + } + else +#endif /* USB_HS_DEDICATED_EP1_ENABLED */ + { + /* enable the interrupts for this endpoint */ + udev->regs.dr->DAEPINTEN |= epinten; + } + + return USB_OK; +} + +/*! + \brief deactivate the USB transaction + \param[in] udev: pointer to USB device + \param[in] transc: the USB transaction + \param[out] none + \retval status +*/ +usb_status usb_transc_deactivate(usb_core_driver *udev, usb_transc *transc) +{ + uint32_t epinten = 0U; + + uint8_t ep_num = transc->ep_addr.num; + + /* disable endpoint interrupt number */ + if (transc->ep_addr.dir) { + epinten = 1U << ep_num; + + udev->regs.er_in[ep_num]->DIEPCTL &= ~DEPCTL_EPACT; + } else { + epinten = 1U << (ep_num + 16U); + + udev->regs.er_out[ep_num]->DOEPCTL &= ~DEPCTL_EPACT; + } + +#ifdef USB_HS_DEDICATED_EP1_ENABLED + if ((ep_num == 1U) && (udev->bp.core_enum == USB_CORE_ENUM_HS)) { + udev->regs.dr->DEP1INTEN &= ~epinten; + } + else +#endif /* USB_HS_DEDICATED_EP1_ENABLED */ + { + /* disable the interrupts for this endpoint */ + udev->regs.dr->DAEPINTEN &= ~epinten; + } + + return USB_OK; +} + +/*! + \brief configure USB transaction to start IN transfer + \param[in] udev: pointer to USB device + \param[in] transc: the USB IN transaction + \param[out] none + \retval operation status +*/ +usb_status usb_transc_inxfer (usb_core_driver *udev, usb_transc *transc) +{ + usb_status status = USB_OK; + + uint8_t ep_num = transc->ep_addr.num; + + __IO uint32_t epctl = udev->regs.er_in[ep_num]->DIEPCTL; + __IO uint32_t eplen = udev->regs.er_in[ep_num]->DIEPLEN; + + eplen &= ~(DEPLEN_TLEN | DEPLEN_PCNT); + + /* zero length packet or endpoint 0 */ + if (0U == transc->xfer_len) { + /* set transfer packet count to 1 */ + eplen |= 1U << 19U; + } else { + /* set transfer packet count */ + if (0U == ep_num) { + transc->xfer_len = USB_MIN(transc->xfer_len, transc->max_len); + + eplen |= 1U << 19U; + } else { + eplen |= (((transc->xfer_len - 1U) + transc->max_len) / transc->max_len) << 19U; + } + + /* set endpoint transfer length */ + eplen |= transc->xfer_len; + + if (transc->ep_type == (uint8_t)USB_EPTYPE_ISOC) { + eplen |= DIEPLEN_MCNT & (1U << 29U); + } + } + + udev->regs.er_in[ep_num]->DIEPLEN = eplen; + + if (transc->ep_type == (uint8_t)USB_EPTYPE_ISOC) { + if (((udev->regs.dr->DSTAT & DSTAT_FNRSOF) >> 8U) & 0x01U) { + epctl |= DEPCTL_SEVNFRM; + } else { + epctl |= DEPCTL_SODDFRM; + } + } + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + udev->regs.er_in[ep_num]->DIEPDMAADDR = transc->dma_addr; + } + + /* enable the endpoint and clear the NAK */ + epctl |= DEPCTL_CNAK | DEPCTL_EPEN; + + udev->regs.er_in[ep_num]->DIEPCTL = epctl; + + if ((uint8_t)USB_USE_FIFO == udev->bp.transfer_mode) { + if (transc->ep_type != (uint8_t)USB_EPTYPE_ISOC) { + /* enable the Tx FIFO empty interrupt for this endpoint */ + if (transc->xfer_len > 0U) { + udev->regs.dr->DIEPFEINTEN |= 1U << ep_num; + } + } else { + (void)usb_txfifo_write (&udev->regs, transc->xfer_buf, ep_num, (uint16_t)transc->xfer_len); + } + } + + return status; +} + +/*! + \brief configure USB transaction to start OUT transfer + \param[in] udev: pointer to USB device + \param[in] transc: the USB OUT transaction + \param[out] none + \retval status +*/ +usb_status usb_transc_outxfer (usb_core_driver *udev, usb_transc *transc) +{ + usb_status status = USB_OK; + + uint8_t ep_num = transc->ep_addr.num; + + uint32_t epctl = udev->regs.er_out[ep_num]->DOEPCTL; + uint32_t eplen = udev->regs.er_out[ep_num]->DOEPLEN; + + eplen &= ~(DEPLEN_TLEN | DEPLEN_PCNT); + + /* zero length packet or endpoint 0 */ + if ((0U == transc->xfer_len) || (0U == ep_num)) { + /* set the transfer length to max packet size */ + eplen |= transc->max_len; + + /* set the transfer packet count to 1 */ + eplen |= 1U << 19U; + } else { + /* configure the transfer size and packet count as follows: + * pktcnt = N + * xfersize = N * maxpacket + */ + uint32_t packet_count = (transc->xfer_len + transc->max_len - 1U) / transc->max_len; + + eplen |= packet_count << 19U; + eplen |= packet_count * transc->max_len; + +#ifdef INT_HIGH_BW + if (transc->ep_type == (uint8_t)USB_EPTYPE_INTR) { + eplen |= DIEPLEN_MCNT & (3U << 29U); + } +#endif /* INT_HIGH_BW */ + } + + udev->regs.er_out[ep_num]->DOEPLEN = eplen; + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + udev->regs.er_out[ep_num]->DOEPDMAADDR = transc->dma_addr; + } + + if (transc->ep_type == (uint8_t)USB_EPTYPE_ISOC) { + if (transc->frame_num) { + epctl |= DEPCTL_SD1PID; + } else { + epctl |= DEPCTL_SD0PID; + } + } + + /* enable the endpoint and clear the NAK */ + epctl |= DEPCTL_EPEN | DEPCTL_CNAK; + + udev->regs.er_out[ep_num]->DOEPCTL = epctl; + + return status; +} + +/*! + \brief set the USB transaction STALL status + \param[in] udev: pointer to USB device + \param[in] transc: the USB transaction + \param[out] none + \retval status +*/ +usb_status usb_transc_stall (usb_core_driver *udev, usb_transc *transc) +{ + __IO uint32_t *reg_addr = NULL; + + uint8_t ep_num = transc->ep_addr.num; + + if (transc->ep_addr.dir) { + reg_addr = &(udev->regs.er_in[ep_num]->DIEPCTL); + + /* set the endpoint disable bit */ + if (*reg_addr & DEPCTL_EPEN) { + *reg_addr |= DEPCTL_EPD; + } + } else { + /* set the endpoint stall bit */ + reg_addr = &(udev->regs.er_out[ep_num]->DOEPCTL); + } + + /* set the endpoint stall bit */ + *reg_addr |= DEPCTL_STALL; + + return USB_OK; +} + +/*! + \brief clear the USB transaction STALL status + \param[in] udev: pointer to USB device + \param[in] transc: the USB transaction + \param[out] none + \retval operation status +*/ +usb_status usb_transc_clrstall(usb_core_driver *udev, usb_transc *transc) +{ + __IO uint32_t *reg_addr = NULL; + + uint8_t ep_num = transc->ep_addr.num; + + if (transc->ep_addr.dir) { + reg_addr = &(udev->regs.er_in[ep_num]->DIEPCTL); + } else { + reg_addr = &(udev->regs.er_out[ep_num]->DOEPCTL); + } + + /* clear the endpoint stall bits */ + *reg_addr &= ~DEPCTL_STALL; + + /* reset data PID of the periodic endpoints */ + if ((transc->ep_type == (uint8_t)USB_EPTYPE_INTR) || (transc->ep_type == (uint8_t)USB_EPTYPE_BULK)) { + *reg_addr |= DEPCTL_SD0PID; + } + + return USB_OK; +} + +/*! + \brief read device IN endpoint interrupt flag register + \param[in] udev: pointer to USB device + \param[in] ep_num: endpoint number + \param[out] none + \retval interrupt value +*/ +uint32_t usb_iepintr_read (usb_core_driver *udev, uint8_t ep_num) +{ + uint32_t value = 0U, fifoemptymask, commonintmask; + + commonintmask = udev->regs.dr->DIEPINTEN; + fifoemptymask = udev->regs.dr->DIEPFEINTEN; + + /* check FIFO empty interrupt enable bit */ + commonintmask |= ((fifoemptymask >> ep_num) & 0x1U) << 7; + + value = udev->regs.er_in[ep_num]->DIEPINTF & commonintmask; + + return value; +} + +/*! + \brief configures OUT endpoint 0 to receive SETUP packets + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +void usb_ctlep_startout (usb_core_driver *udev) +{ + /* set OUT endpoint 0 receive length to 24 bytes, 1 packet and 3 setup packets */ + udev->regs.er_out[0]->DOEPLEN = DOEP0_TLEN(8U * 3U) | DOEP0_PCNT(1U) | DOEP0_STPCNT(3U); + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + udev->regs.er_out[0]->DOEPDMAADDR = (uint32_t)&udev->dev.control.req; + + /* endpoint enable */ + udev->regs.er_out[0]->DOEPCTL |= DEPCTL_EPACT | DEPCTL_EPEN; + } +} + +/*! + \brief active remote wakeup signaling + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +void usb_rwkup_active (usb_core_driver *udev) +{ + if (udev->dev.pm.dev_remote_wakeup) { + if (udev->regs.dr->DSTAT & DSTAT_SPST) { + if (udev->bp.low_power) { + /* ungate USB core clock */ + *udev->regs.PWRCLKCTL &= ~(PWRCLKCTL_SHCLK | PWRCLKCTL_SUCLK); + } + + /* active remote wakeup signaling */ + udev->regs.dr->DCTL |= DCTL_RWKUP; + + usb_mdelay(5U); + + udev->regs.dr->DCTL &= ~DCTL_RWKUP; + } + } +} + +/*! + \brief active USB core clock + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +void usb_clock_active (usb_core_driver *udev) +{ + if (udev->bp.low_power) { + if (udev->regs.dr->DSTAT & DSTAT_SPST) { + /* ungate USB Core clock */ + *udev->regs.PWRCLKCTL &= ~(PWRCLKCTL_SHCLK | PWRCLKCTL_SUCLK); + } + } +} + +/*! + \brief USB device suspend + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +void usb_dev_suspend (usb_core_driver *udev) +{ + __IO uint32_t devstat = udev->regs.dr->DSTAT; + + if ((udev->bp.low_power) && (devstat & DSTAT_SPST)) { + /* switch-off the USB clocks */ + *udev->regs.PWRCLKCTL |= PWRCLKCTL_SHCLK; + + /* enter DEEP_SLEEP mode with LDO in low power mode */ + pmu_to_deepsleepmode (PMU_LDO_LOWPOWER,PMU_LOWDRIVER_DISABLE,WFI_CMD); + } +} + +/*! + \brief stop the device and clean up FIFOs + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +void usb_dev_stop (usb_core_driver *udev) +{ + uint32_t i; + + udev->dev.cur_status = 1U; + + /* clear all interrupt flag and enable bits */ + for (i = 0U; i < udev->bp.num_ep; i++) { + udev->regs.er_in[i]->DIEPINTF = 0xFFU; + udev->regs.er_out[i]->DOEPINTF = 0xFFU; + } + + udev->regs.dr->DIEPINTEN = 0U; + udev->regs.dr->DOEPINTEN = 0U; + udev->regs.dr->DAEPINTEN = 0U; + udev->regs.dr->DAEPINT = 0xFFFFFFFFU; + + /* flush the FIFO */ + (void)usb_rxfifo_flush (&udev->regs); + (void)usb_txfifo_flush (&udev->regs, 0x10U); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_host.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_host.c new file mode 100644 index 0000000..7b4326f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usb_host.c @@ -0,0 +1,475 @@ +/*! + \file drv_usb_host.c + \brief USB host mode low level driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "drv_usb_hw.h" +#include "drv_usb_core.h" +#include "drv_usb_host.h" + +const uint32_t PIPE_DPID[2] = { + PIPE_DPID_DATA0, + PIPE_DPID_DATA1 +}; + +/*! + \brief initializes USB core for host mode + \param[in] udev: pointer to selected USB host + \param[out] none + \retval operation status +*/ +usb_status usb_host_init (usb_core_driver *udev) +{ + uint32_t i = 0U, inten = 0U; + + uint32_t nptxfifolen = 0U; + uint32_t ptxfifolen = 0U; + + /* restart the PHY Clock */ + *udev->regs.PWRCLKCTL = 0U; + + /* initialize host configuration register */ + if (USB_ULPI_PHY == udev->bp.phy_itf) { + usb_phyclock_config (udev, HCTL_30_60MHZ); + } else { + usb_phyclock_config (udev, HCTL_48MHZ); + } + + /* support FS/LS only */ + udev->regs.hr->HCTL &= ~HCTL_SPDFSLS; + + /* configure data FIFOs size */ +#ifdef USB_FS_CORE + if (USB_CORE_ENUM_FS == udev->bp.core_enum) { + /* set Rx FIFO size */ + udev->regs.gr->GRFLEN = USB_RX_FIFO_FS_SIZE; + + /* set non-periodic Tx FIFO size and address */ + nptxfifolen |= USB_RX_FIFO_FS_SIZE; + nptxfifolen |= USB_HTX_NPFIFO_FS_SIZE << 16U; + udev->regs.gr->DIEP0TFLEN_HNPTFLEN = nptxfifolen; + + /* set periodic Tx FIFO size and address */ + ptxfifolen |= USB_RX_FIFO_FS_SIZE + USB_HTX_NPFIFO_FS_SIZE; + ptxfifolen |= USB_HTX_PFIFO_FS_SIZE << 16U; + udev->regs.gr->HPTFLEN = ptxfifolen; + } +#endif /* USB_FS_CORE */ + +#ifdef USB_HS_CORE + if (USB_CORE_ENUM_HS == udev->bp.core_enum) { + /* set Rx FIFO size */ + udev->regs.gr->GRFLEN = USB_RX_FIFO_HS_SIZE; + + /* set non-periodic Tx FIFO size and address */ + nptxfifolen |= USB_RX_FIFO_HS_SIZE; + nptxfifolen |= USB_HTX_NPFIFO_HS_SIZE << 16U; + udev->regs.gr->DIEP0TFLEN_HNPTFLEN = nptxfifolen; + + /* set periodic Tx FIFO size and address */ + ptxfifolen |= USB_RX_FIFO_HS_SIZE + USB_HTX_NPFIFO_HS_SIZE; + ptxfifolen |= USB_HTX_PFIFO_HS_SIZE << 16U; + udev->regs.gr->HPTFLEN = ptxfifolen; + } +#endif /* USB_HS_CORE */ + +#ifdef USE_OTG_MODE + + /* clear host set HNP enable in the usb_otg control register */ + udev->regs.gr->GOTGCS &= ~GOTGCS_HHNPEN; + +#endif /* USE_OTG_MODE */ + + /* make sure the FIFOs are flushed */ + + /* flush all Tx FIFOs in device or host mode */ + usb_txfifo_flush (&udev->regs, 0x10U); + + /* flush the entire Rx FIFO */ + usb_rxfifo_flush (&udev->regs); + + /* disable all interrupts */ + udev->regs.gr->GINTEN = 0U; + + /* clear any pending USB OTG interrupts */ + udev->regs.gr->GOTGINTF = 0xFFFFFFFFU; + + /* enable the USB wakeup and suspend interrupts */ + udev->regs.gr->GINTF = 0xBFFFFFFFU; + + /* clear all pending host channel interrupts */ + for (i = 0U; i < udev->bp.num_pipe; i++) { + udev->regs.pr[i]->HCHINTF = 0xFFFFFFFFU; + udev->regs.pr[i]->HCHINTEN = 0U; + } + +#ifndef USE_OTG_MODE + usb_portvbus_switch (udev, 1U); +#endif /* USE_OTG_MODE */ + + udev->regs.gr->GINTEN = GINTEN_WKUPIE | GINTEN_SPIE; + + /* enable host_mode-related interrupts */ + if (USB_USE_FIFO == udev->bp.transfer_mode) { + inten = GINTEN_RXFNEIE; + } + + inten |= GINTEN_SESIE | GINTEN_HPIE | GINTEN_HCIE | GINTEN_ISOINCIE; + + udev->regs.gr->GINTEN |= inten; + + inten = GINTEN_DISCIE | GINTEN_SOFIE; + + udev->regs.gr->GINTEN &= ~inten; + + return USB_OK; +} + +/*! + \brief control the VBUS to power + \param[in] udev: pointer to selected usb host + \param[in] state: VBUS state + \param[out] none + \retval none +*/ +void usb_portvbus_switch (usb_core_driver *udev, uint8_t state) +{ + uint32_t port = 0U; + + /* enable or disable the external charge pump */ + usb_vbus_drive (state); + + /* turn on the host port power. */ + port = usb_port_read (udev); + + if (!(port & HPCS_PP) && (1U == state)) { + port |= HPCS_PP; + } + + if ((port & HPCS_PP) && (0U == state)) { + port &= ~HPCS_PP; + } + + *udev->regs.HPCS = port; + + usb_mdelay (200U); +} + +/*! + \brief reset host port + \param[in] udev: pointer to USB device + \param[out] none + \retval operation status +*/ +uint32_t usb_port_reset (usb_core_driver *udev) +{ + __IO uint32_t port = usb_port_read (udev); + + *udev->regs.HPCS = port | HPCS_PRST; + + usb_mdelay(20U); /* see note */ + + *udev->regs.HPCS = port & ~HPCS_PRST; + + usb_mdelay(20U); + + return 1U; +} + +/*! + \brief initialize host pipe + \param[in] udev: pointer to USB device + \param[in] pipe_num: host pipe number which is in (0..7) + \param[out] none + \retval operation status +*/ +usb_status usb_pipe_init (usb_core_driver *udev, uint8_t pipe_num) +{ + usb_status status = USB_OK; + + __IO uint32_t pp_ctl = 0U; + __IO uint32_t pp_inten = HCHINTEN_TFIE; + + usb_pipe *pp = &udev->host.pipe[pipe_num]; + + /* clear old interrupt conditions for this host channel */ + udev->regs.pr[pipe_num]->HCHINTF = 0xFFFFFFFFU; + + if (USB_USE_DMA == udev->bp.transfer_mode) { + pp_inten |= HCHINTEN_DMAERIE; + } + + if (pp->ep.dir) { + pp_inten |= HCHINTEN_BBERIE; + } + + /* enable channel interrupts required for this transfer */ + switch (pp->ep.type) { + case USB_EPTYPE_CTRL: + case USB_EPTYPE_BULK: + pp_inten |= HCHINTEN_STALLIE | HCHINTEN_USBERIE \ + | HCHINTEN_DTERIE | HCHINTEN_NAKIE; + + if (!pp->ep.dir) { + if (PORT_SPEED_HIGH == pp->dev_speed) { + pp_inten |= HCHINTEN_NYETIE; + pp_inten |= HCHINTEN_ACKIE; + } + } + break; + + case USB_EPTYPE_INTR: + pp_inten |= HCHINTEN_STALLIE | HCHINTEN_USBERIE | HCHINTEN_DTERIE \ + | HCHINTEN_NAKIE | HCHINTEN_REQOVRIE; + break; + + case USB_EPTYPE_ISOC: + pp_inten |= HCHINTEN_REQOVRIE | HCHINTEN_ACKIE; + + if (pp->ep.dir) { + pp_inten |= HCHINTEN_USBERIE; + } + break; + + default: + break; + } + + udev->regs.pr[pipe_num]->HCHINTEN = pp_inten; + + /* enable the top level host channel interrupt */ + udev->regs.hr->HACHINTEN |= 1U << pipe_num; + + /* make sure host channel interrupts are enabled */ + udev->regs.gr->GINTEN |= GINTEN_HCIE; + + /* program the host channel control register */ + pp_ctl |= PIPE_CTL_DAR(pp->dev_addr); + pp_ctl |= PIPE_CTL_EPNUM(pp->ep.num); + pp_ctl |= PIPE_CTL_EPDIR(pp->ep.dir); + pp_ctl |= PIPE_CTL_EPTYPE(pp->ep.type); + pp_ctl |= PIPE_CTL_LSD(pp->dev_speed == PORT_SPEED_LOW); + + pp_ctl |= pp->ep.mps; + pp_ctl |= ((uint32_t)(pp->ep.type == USB_EPTYPE_INTR) << 29U) & HCHCTL_ODDFRM; + + udev->regs.pr[pipe_num]->HCHCTL = pp_ctl; + + return status; +} + +/*! + \brief prepare host channel for transferring packets + \param[in] udev: pointer to USB device + \param[in] pipe_num: host pipe number which is in (0..7) + \param[out] none + \retval operation status +*/ +usb_status usb_pipe_xfer (usb_core_driver *udev, uint8_t pipe_num) +{ + usb_status status = USB_OK; + + uint16_t dword_len = 0U; + uint16_t packet_count = 0U; + + __IO uint32_t pp_ctl = 0U; + + usb_pipe *pp = &udev->host.pipe[pipe_num]; + + uint16_t max_packet_len = pp->ep.mps; + + /* compute the expected number of packets associated to the transfer */ + if (pp->xfer_len > 0U) { + packet_count = (uint16_t)((pp->xfer_len + max_packet_len - 1U) / max_packet_len); + + if (packet_count > HC_MAX_PACKET_COUNT) { + packet_count = HC_MAX_PACKET_COUNT; + pp->xfer_len = (uint16_t)(packet_count * max_packet_len); + } + } else { + packet_count = 1U; + } + + if (pp->ep.dir) { + pp->xfer_len = (uint16_t)(packet_count * max_packet_len); + } + + /* initialize the host channel transfer information */ + udev->regs.pr[pipe_num]->HCHLEN = pp->xfer_len | pp->DPID | PIPE_XFER_PCNT(packet_count); + + if (USB_USE_DMA == udev->bp.transfer_mode) { + udev->regs.pr[pipe_num]->HCHDMAADDR = (unsigned int)pp->xfer_buf; + } + + pp_ctl = udev->regs.pr[pipe_num]->HCHCTL; + + if (usb_frame_even(udev)) { + pp_ctl |= HCHCTL_ODDFRM; + } else { + pp_ctl &= ~HCHCTL_ODDFRM; + } + + /* set host channel enabled */ + pp_ctl |= HCHCTL_CEN; + pp_ctl &= ~HCHCTL_CDIS; + + udev->regs.pr[pipe_num]->HCHCTL = pp_ctl; + + if (USB_USE_FIFO == udev->bp.transfer_mode) { + if ((0U == pp->ep.dir) && (pp->xfer_len > 0U)) { + switch (pp->ep.type) { + /* non-periodic transfer */ + case USB_EPTYPE_CTRL: + case USB_EPTYPE_BULK: + dword_len = (uint16_t)((pp->xfer_len + 3U) / 4U); + + /* check if there is enough space in FIFO space */ + if (dword_len > (udev->regs.gr->HNPTFQSTAT & HNPTFQSTAT_NPTXFS)) { + /* need to process data in nptxfempty interrupt */ + udev->regs.gr->GINTEN |= GINTEN_NPTXFEIE; + } + break; + + /* periodic transfer */ + case USB_EPTYPE_INTR: + case USB_EPTYPE_ISOC: + dword_len = (uint16_t)((pp->xfer_len + 3U) / 4U); + + /* check if there is enough space in fifo space */ + if (dword_len > (udev->regs.hr->HPTFQSTAT & HPTFQSTAT_PTXFS)) { + /* need to process data in ptxfempty interrupt */ + udev->regs.gr->GINTEN |= GINTEN_PTXFEIE; + } + break; + + default: + break; + } + + /* write packet into the Tx fifo. */ + usb_txfifo_write (&udev->regs, pp->xfer_buf, pipe_num, (uint16_t)pp->xfer_len); + } + } + + return status; +} + +/*! + \brief halt pipe + \param[in] udev: pointer to USB device + \param[in] pipe_num: host pipe number which is in (0..7) + \param[out] none + \retval operation status +*/ +usb_status usb_pipe_halt (usb_core_driver *udev, uint8_t pipe_num) +{ + __IO uint32_t pp_ctl = udev->regs.pr[pipe_num]->HCHCTL; + + uint8_t ep_type = (uint8_t)((pp_ctl & HCHCTL_EPTYPE) >> 18U); + + pp_ctl |= HCHCTL_CEN | HCHCTL_CDIS; + + switch (ep_type) { + case USB_EPTYPE_CTRL: + case USB_EPTYPE_BULK: + if (0U == (udev->regs.gr->HNPTFQSTAT & HNPTFQSTAT_NPTXFS)) { + pp_ctl &= ~HCHCTL_CEN; + } + break; + + case USB_EPTYPE_INTR: + case USB_EPTYPE_ISOC: + if (0U == (udev->regs.hr->HPTFQSTAT & HPTFQSTAT_PTXFS)) { + pp_ctl &= ~HCHCTL_CEN; + } + break; + + default: + break; + } + + udev->regs.pr[pipe_num]->HCHCTL = pp_ctl; + + return USB_OK; +} + +/*! + \brief configure host pipe to do ping operation + \param[in] udev: pointer to USB device + \param[in] pipe_num: host pipe number which is in (0..7) + \param[out] none + \retval operation status +*/ +usb_status usb_pipe_ping (usb_core_driver *udev, uint8_t pipe_num) +{ + uint32_t pp_ctl = 0U; + + udev->regs.pr[pipe_num]->HCHLEN = HCHLEN_PING; + + pp_ctl = udev->regs.pr[pipe_num]->HCHCTL; + + pp_ctl |= HCHCTL_CEN; + pp_ctl &= ~HCHCTL_CDIS; + + udev->regs.pr[pipe_num]->HCHCTL = pp_ctl; + + return USB_OK; +} + +/*! + \brief stop the USB host and clean up FIFO + \param[in] udev: pointer to USB device + \param[out] none + \retval none +*/ +void usb_host_stop (usb_core_driver *udev) +{ + uint32_t i; + __IO uint32_t pp_ctl = 0U; + + udev->regs.hr->HACHINTEN = 0x0U; + udev->regs.hr->HACHINT = 0xFFFFFFFFU; + + /* flush out any leftover queued requests. */ + for (i = 0U; i < udev->bp.num_pipe; i++) { + pp_ctl = udev->regs.pr[i]->HCHCTL; + + pp_ctl &= ~(HCHCTL_CEN | HCHCTL_EPDIR); + pp_ctl |= HCHCTL_CDIS; + + udev->regs.pr[i]->HCHCTL = pp_ctl; + } + + /* flush the FIFO */ + usb_rxfifo_flush (&udev->regs); + usb_txfifo_flush (&udev->regs, 0x10U); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usbd_int.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usbd_int.c new file mode 100644 index 0000000..c388472 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usbd_int.c @@ -0,0 +1,576 @@ +/*! + \file drv_usbd_int.c + \brief USB device mode interrupt routines + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbd_conf.h" +#include "drv_usbd_int.h" +#include "usbd_transc.h" + +/* local function prototypes ('static') */ +static uint32_t usbd_int_epout (usb_core_driver *udev); +static uint32_t usbd_int_epin (usb_core_driver *udev); +static uint32_t usbd_int_rxfifo (usb_core_driver *udev); +static uint32_t usbd_int_reset (usb_core_driver *udev); +static uint32_t usbd_int_enumfinish (usb_core_driver *udev); +static uint32_t usbd_int_suspend (usb_core_driver *udev); +static uint32_t usbd_emptytxfifo_write (usb_core_driver *udev, uint32_t ep_num); + +static const uint8_t USB_SPEED[4] = { + [DSTAT_EM_HS_PHY_30MHZ_60MHZ] = (uint8_t)USB_SPEED_HIGH, + [DSTAT_EM_FS_PHY_30MHZ_60MHZ] = (uint8_t)USB_SPEED_FULL, + [DSTAT_EM_FS_PHY_48MHZ] = (uint8_t)USB_SPEED_FULL, + [DSTAT_EM_LS_PHY_6MHZ] = (uint8_t)USB_SPEED_LOW +}; + +/*! + \brief USB device-mode interrupts global service routine handler + \param[in] udev: pointer to USB device instance + \param[out] none + \retval none +*/ +void usbd_isr (usb_core_driver *udev) +{ + if (HOST_MODE != (udev->regs.gr->GINTF & GINTF_COPM)) { + uint32_t intr = udev->regs.gr->GINTF; + intr &= udev->regs.gr->GINTEN; + + /* there are no interrupts, avoid spurious interrupt */ + if (!intr) { + return; + } + + /* OUT endpoints interrupts */ + if (intr & GINTF_OEPIF) { + (void)usbd_int_epout (udev); + } + + /* IN endpoints interrupts */ + if (intr & GINTF_IEPIF) { + (void)usbd_int_epin (udev); + } + + /* suspend interrupt */ + if (intr & GINTF_SP) { + (void)usbd_int_suspend (udev); + } + + /* wakeup interrupt */ + if (intr & GINTF_WKUPIF) { + if(USBD_SUSPENDED == udev->dev.cur_status){ + /* inform upper layer by the resume event */ + udev->dev.cur_status = udev->dev.backup_status; + } + + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_WKUPIF; + } + + /* start of frame interrupt */ + if (intr & GINTF_SOF) { + if (udev->dev.class_core->SOF) { + (void)udev->dev.class_core->SOF(udev); + } + + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_SOF; + } + + /* receive FIFO not empty interrupt */ + if (intr & GINTF_RXFNEIF) { + (void)usbd_int_rxfifo (udev); + } + + /* USB reset interrupt */ + if (intr & GINTF_RST) { + (void)usbd_int_reset (udev); + } + + /* enumeration has been done interrupt */ + if (intr & GINTF_ENUMFIF) { + (void)usbd_int_enumfinish (udev); + } + + /* incomplete synchronization IN transfer interrupt*/ + if (intr & GINTF_ISOINCIF) { + if (NULL != udev->dev.class_core->incomplete_isoc_in) { + (void)udev->dev.class_core->incomplete_isoc_in(udev); + } + + /* Clear interrupt */ + udev->regs.gr->GINTF = GINTF_ISOINCIF; + } + + /* incomplete synchronization OUT transfer interrupt*/ + if (intr & GINTF_ISOONCIF) { + if (NULL != udev->dev.class_core->incomplete_isoc_out) { + (void)udev->dev.class_core->incomplete_isoc_out(udev); + } + + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_ISOONCIF; + } + +#ifdef VBUS_SENSING_ENABLED + /* session request interrupt */ + if (intr & GINTF_SESIF) { + udev->regs.gr->GINTF = GINTF_SESIF; + } + + /* OTG mode interrupt */ + if (intr & GINTF_OTGIF) { + if(udev->regs.gr->GOTGINTF & GOTGINTF_SESEND) { + + } + + /* clear OTG interrupt */ + udev->regs.gr->GINTF = GINTF_OTGIF; + } +#endif /* VBUS_SENSING_ENABLED */ + } +} + +#ifdef USB_HS_DEDICATED_EP1_ENABLED + +/*! + \brief USB dedicated OUT endpoint 1 interrupt service routine handler + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +uint32_t usbd_int_dedicated_ep1out (usb_core_driver *udev) +{ + uint32_t oepintr = 0U; + uint32_t oeplen = 0U; + + oepintr = udev->regs.er_out[1]->DOEPINTF; + oepintr &= udev->regs.dr->DOEP1INTEN; + + /* transfer complete */ + if(oepintr & DOEPINTF_TF){ + /* clear the bit in DOEPINTn for this interrupt */ + udev->regs.er_out[1]->DOEPINTF = DOEPINTF_TF; + + if(USB_USE_DMA == udev->bp.transfer_mode){ + usb_transc *transc = &udev->dev.transc_out[1]; + uint32_t set_len = ((transc->xfer_len + transc->max_len - 1U) / transc->max_len) * transc->max_len; + oeplen = udev->regs.er_out[1]->DOEPLEN; + + /* to do : handle more than one single max packet size packet */ + udev->dev.transc_out[1].xfer_count = set_len - (oeplen & DEPLEN_TLEN); + } + + /* rx complete */ + usbd_out_transc (udev, 1U); + } + + return 1U; +} + +/*! + \brief USB dedicated IN endpoint 1 interrupt service routine handler + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +uint32_t usbd_int_dedicated_ep1in (usb_core_driver *udev) +{ + uint32_t inten, intr, emptyen; + + inten = udev->regs.dr->DIEP1INTEN; + emptyen = udev->regs.dr->DIEPFEINTEN; + + inten |= ((emptyen >> 1 ) & 0x1) << 7; + + intr = udev->regs.er_in[1]->DIEPINTF & inten; + + if(intr & DIEPINTF_TF){ + udev->regs.dr->DIEPFEINTEN &= ~(0x1 << 1); + + udev->regs.er_in[1]->DIEPINTF = DIEPINTF_TF; + + /* TX complete */ + usbd_in_transc (udev, 1); + } + + if(intr & DIEPINTF_TXFE){ + usbd_emptytxfifo_write(udev, 1); + + udev->regs.er_in[1]->DIEPINTF = DIEPINTF_TXFE; + } + + return 1; +} + +#endif /* USB_HS_DEDICATED_EP1_ENABLED */ + +/*! + \brief indicates that an OUT endpoint has a pending interrupt + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +static uint32_t usbd_int_epout (usb_core_driver *udev) +{ + uint32_t epintnum = 0U; + uint8_t ep_num = 0U; + + for (epintnum = usb_oepintnum_read (udev); epintnum; epintnum >>= 1, ep_num++) { + if (epintnum & 0x01U) { + __IO uint32_t oepintr = usb_oepintr_read (udev, ep_num); + + /* transfer complete interrupt */ + if (oepintr & DOEPINTF_TF) { + /* clear the bit in DOEPINTF for this interrupt */ + udev->regs.er_out[ep_num]->DOEPINTF = DOEPINTF_TF; + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + usb_transc *transc = &udev->dev.transc_out[ep_num]; + __IO uint32_t eplen = udev->regs.er_out[ep_num]->DOEPLEN; + uint32_t set_len = ((transc->xfer_len + transc->max_len - 1U) / transc->max_len) * transc->max_len; + + udev->dev.transc_out[ep_num].xfer_count = set_len - (eplen & DEPLEN_TLEN); + } + + /* inform upper layer: data ready */ + (void)usbd_out_transc (udev, ep_num); + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + if ((0U == ep_num) && ((uint8_t)USB_CTL_STATUS_OUT == udev->dev.control.ctl_state)) { + usb_ctlep_startout (udev); + } + } + } + + /* setup phase finished interrupt (control endpoints) */ + if (oepintr & DOEPINTF_STPF) { + /* inform the upper layer that a setup packet is available */ + (void)usbd_setup_transc (udev); + + udev->regs.er_out[ep_num]->DOEPINTF = DOEPINTF_STPF; + } + } + } + + return 1U; +} + +/*! + \brief indicates that an IN endpoint has a pending interrupt + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +static uint32_t usbd_int_epin (usb_core_driver *udev) +{ + uint32_t epintnum = 0U; + uint8_t ep_num = 0U; + + for (epintnum = usb_iepintnum_read (udev); epintnum; epintnum >>= 1, ep_num++) { + if (epintnum & 0x1U) { + __IO uint32_t iepintr = usb_iepintr_read (udev, ep_num); + + if (iepintr & DIEPINTF_TF) { + udev->regs.er_in[ep_num]->DIEPINTF = DIEPINTF_TF; + + /* data transmission is completed */ + (void)usbd_in_transc (udev, ep_num); + + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + if ((0U == ep_num) && ((uint8_t)USB_CTL_STATUS_IN == udev->dev.control.ctl_state)) { + usb_ctlep_startout (udev); + } + } + } + + if (iepintr & DIEPINTF_TXFE) { + usbd_emptytxfifo_write (udev, (uint32_t)ep_num); + + udev->regs.er_in[ep_num]->DIEPINTF = DIEPINTF_TXFE; + } + } + } + + return 1U; +} + +/*! + \brief handle the RX status queue level interrupt + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +static uint32_t usbd_int_rxfifo (usb_core_driver *udev) +{ + usb_transc *transc = NULL; + + uint8_t data_PID = 0U; + uint32_t bcount = 0U; + + __IO uint32_t devrxstat = 0U; + + /* disable the Rx status queue non-empty interrupt */ + udev->regs.gr->GINTEN &= ~GINTEN_RXFNEIE; + + /* get the status from the top of the FIFO */ + devrxstat = udev->regs.gr->GRSTATP; + + uint8_t ep_num = (uint8_t)(devrxstat & GRSTATRP_EPNUM); + + transc = &udev->dev.transc_out[ep_num]; + + bcount = (devrxstat & GRSTATRP_BCOUNT) >> 4U; + data_PID = (uint8_t)((devrxstat & GRSTATRP_DPID) >> 15U); + + switch ((devrxstat & GRSTATRP_RPCKST) >> 17U) { + case RSTAT_GOUT_NAK: + break; + + case RSTAT_DATA_UPDT: + if (bcount > 0U) { + (void)usb_rxfifo_read (&udev->regs, transc->xfer_buf, (uint16_t)bcount); + + transc->xfer_buf += bcount; + transc->xfer_count += bcount; + } + break; + + case RSTAT_XFER_COMP: + /* trigger the OUT endpoint interrupt */ + break; + + case RSTAT_SETUP_COMP: + /* trigger the OUT endpoint interrupt */ + break; + + case RSTAT_SETUP_UPDT: + if ((0U == transc->ep_addr.num) && (8U == bcount) && (DPID_DATA0 == data_PID)) { + /* copy the setup packet received in FIFO into the setup buffer in RAM */ + (void)usb_rxfifo_read (&udev->regs, (uint8_t *)&udev->dev.control.req, (uint16_t)bcount); + + transc->xfer_count += bcount; + } + break; + + default: + break; + } + + /* enable the Rx status queue level interrupt */ + udev->regs.gr->GINTEN |= GINTEN_RXFNEIE; + + return 1U; +} + +/*! + \brief handle USB reset interrupt + \param[in] udev: pointer to USB device instance + \param[out] none + \retval status +*/ +static uint32_t usbd_int_reset (usb_core_driver *udev) +{ + uint32_t i; + + /* clear the remote wakeup signaling */ + udev->regs.dr->DCTL &= ~DCTL_RWKUP; + + /* flush the Tx FIFO */ + (void)usb_txfifo_flush (&udev->regs, 0U); + + for (i = 0U; i < udev->bp.num_ep; i++) { + udev->regs.er_in[i]->DIEPINTF = 0xFFU; + udev->regs.er_out[i]->DOEPINTF = 0xFFU; + } + + /* clear all pending device endpoint interrupts */ + udev->regs.dr->DAEPINT = 0xFFFFFFFFU; + + /* enable endpoint 0 interrupts */ + udev->regs.dr->DAEPINTEN = 1U | (1U << 16U); + + /* enable OUT endpoint interrupts */ + udev->regs.dr->DOEPINTEN = DOEPINTEN_STPFEN | DOEPINTEN_TFEN; + +#ifdef USB_HS_DEDICATED_EP1_ENABLED + udev->regs.dr->DOEP1INTEN = DOEPINTEN_STPFEN | DOEPINTEN_TFEN; +#endif /* USB_HS_DEDICATED_EP1_ENABLED */ + + /* enable IN endpoint interrupts */ + udev->regs.dr->DIEPINTEN = DIEPINTEN_TFEN; + +#ifdef USB_HS_DEDICATED_EP1_ENABLED + udev->regs.dr->DIEP1INTEN = DIEPINTEN_TFEN; +#endif /* USB_HS_DEDICATED_EP1_ENABLED */ + + /* reset device address */ + udev->regs.dr->DCFG &= ~DCFG_DAR; + + /* configure endpoint 0 to receive SETUP packets */ + usb_ctlep_startout (udev); + + /* clear USB reset interrupt */ + udev->regs.gr->GINTF = GINTF_RST; + + udev->dev.transc_out[0] = (usb_transc) { + .ep_type = USB_EPTYPE_CTRL, + .max_len = USB_FS_EP0_MAX_LEN + }; + + (void)usb_transc_active (udev, &udev->dev.transc_out[0]); + + udev->dev.transc_in[0] = (usb_transc) { + .ep_addr = { + .dir = 1U + }, + + .ep_type = USB_EPTYPE_CTRL, + .max_len = USB_FS_EP0_MAX_LEN + }; + + (void)usb_transc_active (udev, &udev->dev.transc_in[0]); + + /* upon reset call user call back */ + udev->dev.cur_status = (uint8_t)USBD_DEFAULT; + + return 1U; +} + +/*! + \brief handle USB speed enumeration finish interrupt + \param[in] udev: pointer to USB device instance + \param[out] none + \retval status +*/ +static uint32_t usbd_int_enumfinish (usb_core_driver *udev) +{ + uint8_t enum_speed = (uint8_t)((udev->regs.dr->DSTAT & DSTAT_ES) >> 1U); + + udev->regs.dr->DCTL &= ~DCTL_CGINAK; + udev->regs.dr->DCTL |= DCTL_CGINAK; + + udev->regs.gr->GUSBCS &= ~GUSBCS_UTT; + + /* set USB turn-around time based on device speed and PHY interface */ + if (USB_SPEED[enum_speed] == (uint8_t)USB_SPEED_HIGH) { + udev->bp.core_speed = (uint8_t)USB_SPEED_HIGH; + + udev->regs.gr->GUSBCS |= 0x09U << 10U; + } else { + udev->bp.core_speed = (uint8_t)USB_SPEED_FULL; + + udev->regs.gr->GUSBCS |= 0x05U << 10U; + } + + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_ENUMFIF; + + return 1U; +} + +/*! + \brief USB suspend interrupt handler + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +static uint32_t usbd_int_suspend (usb_core_driver *udev) +{ + __IO uint8_t low_power = udev->bp.low_power; + __IO uint8_t suspend = (uint8_t)(udev->regs.dr->DSTAT & DSTAT_SPST); + __IO uint8_t is_configured = (udev->dev.cur_status == (uint8_t)USBD_CONFIGURED) ? 1U : 0U; + + udev->dev.backup_status = udev->dev.cur_status; + udev->dev.cur_status = (uint8_t)USBD_SUSPENDED; + + if (low_power && suspend && is_configured) { + /* switch-off the OTG clocks */ + *udev->regs.PWRCLKCTL |= PWRCLKCTL_SUCLK | PWRCLKCTL_SHCLK; + + /* enter DEEP_SLEEP mode with LDO in low power mode */ + pmu_to_deepsleepmode (PMU_LDO_LOWPOWER, PMU_LOWDRIVER_DISABLE, WFI_CMD); + } + + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_SP; + + return 1U; +} + +/*! + \brief check FIFO for the next packet to be loaded + \param[in] udev: pointer to USB device instance + \param[in] ep_num: endpoint identifier which is in (0..3) + \param[out] none + \retval status +*/ +static uint32_t usbd_emptytxfifo_write (usb_core_driver *udev, uint32_t ep_num) +{ + uint32_t len; + uint32_t word_count; + + usb_transc *transc = &udev->dev.transc_in[ep_num]; + + len = transc->xfer_len - transc->xfer_count; + + /* get the data length to write */ + if (len > transc->max_len) { + len = transc->max_len; + } + + word_count = (len + 3U) / 4U; + + while (((udev->regs.er_in[ep_num]->DIEPTFSTAT & DIEPTFSTAT_IEPTFS) >= word_count) && \ + (transc->xfer_count < transc->xfer_len)) { + len = transc->xfer_len - transc->xfer_count; + + if (len > transc->max_len) { + len = transc->max_len; + } + + /* write FIFO in word(4bytes) */ + word_count = (len + 3U) / 4U; + + /* write the FIFO */ + (void)usb_txfifo_write (&udev->regs, transc->xfer_buf, (uint8_t)ep_num, (uint16_t)len); + + transc->xfer_buf += len; + transc->xfer_count += len; + + if (transc->xfer_count == transc->xfer_len) { + /* disable the device endpoint FIFO empty interrupt */ + udev->regs.dr->DIEPFEINTEN &= ~(0x01U << ep_num); + } + } + + return 1U; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usbh_int.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usbh_int.c new file mode 100644 index 0000000..6f729a8 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/driver/Source/drv_usbh_int.c @@ -0,0 +1,639 @@ +/*! + \file drv_usbh_int.c + \brief USB host mode interrupt handler file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "drv_usbh_int.h" + +#if defined (__CC_ARM) /*!< ARM compiler */ + #pragma O0 +#elif defined (__GNUC__) /*!< GNU compiler */ + #pragma GCC optimize ("O0") +#elif defined (__TASKING__) /*!< TASKING compiler */ + #pragma optimize=0 +#endif /* __CC_ARM */ + +/* local function prototypes ('static') */ +static uint32_t usbh_int_port (usb_core_driver *udev); +static uint32_t usbh_int_pipe (usb_core_driver *udev); +static uint32_t usbh_int_pipe_in (usb_core_driver *udev, uint32_t pp_num); +static uint32_t usbh_int_pipe_out (usb_core_driver *udev, uint32_t pp_num); +static uint32_t usbh_int_rxfifonoempty (usb_core_driver *udev); +static uint32_t usbh_int_txfifoempty (usb_core_driver *udev, usb_pipe_mode pp_mode); + +/*! + \brief handle global host interrupt + \param[in] udev: pointer to USB core instance + \param[out] none + \retval operation status +*/ +uint32_t usbh_isr (usb_core_driver *udev) +{ + uint32_t retval = 0U; + + __IO uint32_t intr = 0U; + + /* check if host mode */ + if (HOST_MODE == (udev->regs.gr->GINTF & GINTF_COPM)) { + intr = usb_coreintr_get(&udev->regs); + + if (!intr) { + return 0U; + } + + if (intr & GINTF_SOF) { + usbh_int_fop->SOF(udev->host.data); + + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_SOF; + } + + if (intr & GINTF_RXFNEIF) { + retval |= usbh_int_rxfifonoempty (udev); + } + + if (intr & GINTF_NPTXFEIF) { + retval |= usbh_int_txfifoempty (udev, PIPE_NON_PERIOD); + } + + if (intr & GINTF_PTXFEIF) { + retval |= usbh_int_txfifoempty (udev, PIPE_PERIOD); + } + + if (intr & GINTF_HCIF) { + retval |= usbh_int_pipe (udev); + } + + if (intr & GINTF_HPIF) { + retval |= usbh_int_port (udev); + } + + if (intr & GINTF_DISCIF) { + usbh_int_fop->disconnect(udev->host.data); + + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_DISCIF; + } + + if (intr & GINTF_ISOONCIF) { + udev->regs.pr[0]->HCHCTL |= HCHCTL_CEN | HCHCTL_CDIS; + + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_ISOONCIF; + } + + if (intr & GINTF_SESIF) { + usb_portvbus_switch (udev, 1U); + + udev->regs.gr->GINTF = GINTF_SESIF; + } + + if (intr & GINTF_WKUPIF) { + /* clear interrupt */ + udev->regs.gr->GINTF = GINTF_WKUPIF; + } + } + + return retval; +} + +/*! + \brief handle USB pipe halt + \param[in] udev: pointer to USB core instance + \param[in] pp_num: pp_num: host channel number which is in (0..7) + \param[in] pp_int: pipe interrupt + \param[in] pp_status: pipe status + \param[out] none + \retval none +*/ +static inline void usb_pp_halt (usb_core_driver *udev, + uint8_t pp_num, + uint32_t pp_int, + usb_pipe_staus pp_status) +{ + udev->regs.pr[pp_num]->HCHINTEN |= HCHINTEN_CHIE; + + usb_pipe_halt(udev, pp_num); + + udev->regs.pr[pp_num]->HCHINTF = pp_int; + + udev->host.pipe[pp_num].pp_status = pp_status; +} + +/*! + \brief handle the host port interrupt + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +#if defined (__ICCARM__) /*!< IAR compiler */ + #pragma optimize = none +#endif /* __ICCARM */ +static uint32_t usbh_int_port (usb_core_driver *udev) +{ + uint32_t retval = 0U; + + /* note: when the USB PHY use USB HS PHY, the flag is needed */ + uint8_t port_reset = 0U; + + __IO uint32_t port_state = *udev->regs.HPCS; + + /* clear the interrupt bit in GINTF */ + port_state &= ~(HPCS_PE | HPCS_PCD | HPCS_PEDC); + + /* port connect detected */ + if (*udev->regs.HPCS & HPCS_PCD) { + port_state |= HPCS_PCD; + + usbh_int_fop->connect(udev->host.data); + + retval |= 1U; + } + + /* port enable changed */ + if (*udev->regs.HPCS & HPCS_PEDC) { + port_state |= HPCS_PEDC; + + if (*udev->regs.HPCS & HPCS_PE) { + uint32_t port_speed = usb_curspeed_get(udev); + uint32_t clock_type = udev->regs.hr->HCTL & HCTL_CLKSEL; + + udev->host.connect_status = 1U; + + if (PORT_SPEED_LOW == port_speed) { + udev->regs.hr->HFT = 6000U; + + if (HCTL_6MHZ != clock_type) { + if (USB_EMBEDDED_PHY == udev->bp.phy_itf) { + usb_phyclock_config (udev, HCTL_6MHZ); + } + + port_reset = 1U; + } + } else if (PORT_SPEED_FULL == port_speed) { + udev->regs.hr->HFT = 48000U; + + if (HCTL_48MHZ != clock_type) { + if (USB_EMBEDDED_PHY == udev->bp.phy_itf) { + usb_phyclock_config (udev, HCTL_48MHZ); + } + + port_reset = 1U; + } + } else { + /* for high speed device and others */ + port_reset = 1U; + } + + udev->host.port_enabled = 1; + + udev->regs.gr->GINTEN |= GINTEN_DISCIE | GINTEN_SOFIE; + } else { + udev->host.port_enabled = 0; + } + } + + if (port_reset) { + usb_port_reset(udev); + } + + /* clear port interrupts */ + *udev->regs.HPCS = port_state; + + return retval; +} + +/*! + \brief handle all host channels interrupt + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +static uint32_t usbh_int_pipe (usb_core_driver *udev) +{ + uint32_t pp_num = 0U; + uint32_t retval = 0U; + + for (pp_num = 0U; pp_num < udev->bp.num_pipe; pp_num++) { + if ((udev->regs.hr->HACHINT & HACHINT_HACHINT) & (1UL << pp_num)) { + if (udev->regs.pr[pp_num]->HCHCTL & HCHCTL_EPDIR) { + retval |= usbh_int_pipe_in (udev, pp_num); + } else { + retval |= usbh_int_pipe_out (udev, pp_num); + } + } + } + + return retval; +} + +/*! + \brief handle the IN channel interrupt + \param[in] udev: pointer to USB device instance + \param[in] pp_num: host channel number which is in (0..7) + \param[out] none + \retval operation status +*/ +#if defined (__ICCARM__) /*!< IAR compiler */ + #pragma optimize = none +#endif /* __ICCARM */ +static uint32_t usbh_int_pipe_in (usb_core_driver *udev, uint32_t pp_num) +{ + usb_pr *pp_reg = udev->regs.pr[pp_num]; + + usb_pipe *pp = &udev->host.pipe[pp_num]; + + uint32_t intr_pp = pp_reg->HCHINTF; + intr_pp &= pp_reg->HCHINTEN; + + uint8_t ep_type = (uint8_t)((pp_reg->HCHCTL & HCHCTL_EPTYPE) >> 18U); + + if (intr_pp & HCHINTF_ACK) { + pp_reg->HCHINTF = HCHINTF_ACK; + } else if (intr_pp & HCHINTF_STALL) { + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_STALL, PIPE_STALL); + pp_reg->HCHINTF = HCHINTF_NAK; + + /* note: When there is a 'STALL', reset also NAK, + else, the udev->host.pp_status = HC_STALL + will be overwritten by 'NAK' in code below */ + intr_pp &= ~HCHINTF_NAK; + } else if (intr_pp & HCHINTF_DTER) { + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_DTER, PIPE_DTGERR); + pp_reg->HCHINTF = HCHINTF_NAK; + } else { + /* no operation */ + } + + if (intr_pp & HCHINTF_REQOVR) { + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_REQOVR, PIPE_REQOVR); + } else if (intr_pp & HCHINTF_TF) { + if ((uint8_t)USB_USE_DMA == udev->bp.transfer_mode) { + udev->host.backup_xfercount[pp_num] = pp->xfer_len - (pp_reg->HCHLEN & HCHLEN_TLEN); + } + + pp->pp_status = PIPE_XF; + pp->err_count = 0U; + + pp_reg->HCHINTF = HCHINTF_TF; + + switch (ep_type) { + case USB_EPTYPE_CTRL: + case USB_EPTYPE_BULK: + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_NAK, PIPE_XF); + + pp->data_toggle_in ^= 1U; + break; + + case USB_EPTYPE_INTR: + case USB_EPTYPE_ISOC: + pp_reg->HCHCTL |= HCHCTL_ODDFRM; + pp->urb_state = URB_DONE; + break; + + default: + break; + } + } else if (intr_pp & HCHINTF_CH) { + pp_reg->HCHINTEN &= ~HCHINTEN_CHIE; + + switch (pp->pp_status) { + case PIPE_XF: + pp->urb_state = URB_DONE; + break; + + case PIPE_STALL: + pp->urb_state = URB_STALL; + break; + + case PIPE_TRACERR: + case PIPE_DTGERR: + pp->err_count = 0U; + pp->urb_state = URB_ERROR; + + pp->data_toggle_in ^= 1U; + break; + + case PIPE_IDLE: + case PIPE_HALTED: + case PIPE_NAK: + case PIPE_NYET: + case PIPE_BBERR: + case PIPE_REQOVR: + default: + if((uint8_t)USB_EPTYPE_INTR == ep_type) { + pp->data_toggle_in ^= 1U; + } + break; + } + + pp_reg->HCHINTF = HCHINTF_CH; + } else if (intr_pp & HCHINTF_USBER) { + pp->err_count++; + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_USBER, PIPE_TRACERR); + } else if (intr_pp & HCHINTF_NAK) { + switch (ep_type) { + case USB_EPTYPE_CTRL: + case USB_EPTYPE_BULK: + /* re-activate the channel */ + pp_reg->HCHCTL = (pp_reg->HCHCTL | HCHCTL_CEN) & ~HCHCTL_CDIS; + break; + + case USB_EPTYPE_INTR: + pp_reg->HCHINTEN |= HCHINTEN_CHIE; + + (void)usb_pipe_halt(udev, (uint8_t)pp_num); + break; + + default: + break; + } + + pp->pp_status = PIPE_NAK; + + pp_reg->HCHINTF = HCHINTF_NAK; + } else { + /* no operation */ + } + + return 1U; +} + +/*! + \brief handle the OUT channel interrupt + \param[in] udev: pointer to USB device instance + \param[in] pp_num: host channel number which is in (0..7) + \param[out] none + \retval operation status +*/ +#if defined (__ICCARM__) /*!< IAR compiler */ + #pragma optimize = none +#endif /* __ICCARM */ +static uint32_t usbh_int_pipe_out (usb_core_driver *udev, uint32_t pp_num) +{ + usbh_host *uhost = udev->host.data; + usb_pr *pp_reg = udev->regs.pr[pp_num]; + usb_pipe *pp = &udev->host.pipe[pp_num]; + uint32_t intr_pp = pp_reg->HCHINTF; + intr_pp &= pp_reg->HCHINTEN; + + if (intr_pp & HCHINTF_ACK) { + if (1U == udev->host.pipe[pp_num].do_ping) { + udev->host.pipe[pp_num].do_ping = 0; + pp->err_count = 0U; + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_ACK, PIPE_NAK); + } + + pp_reg->HCHINTF = HCHINTF_ACK; + } else if (intr_pp & HCHINTF_STALL) { + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_STALL, PIPE_STALL); + } else if (intr_pp & HCHINTF_DTER) { + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_DTER, PIPE_DTGERR); + pp_reg->HCHINTF = HCHINTF_NAK; + } else if (intr_pp & HCHINTF_REQOVR) { + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_REQOVR, PIPE_REQOVR); + } else if (intr_pp & HCHINTF_TF) { + pp->err_count = 0U; + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_TF, PIPE_XF); + } else if (intr_pp & HCHINTF_NAK) { + if (0U == udev->host.pipe[pp_num].do_ping) { + if (1U == udev->host.pipe[pp_num].supp_ping) { + udev->host.pipe[pp_num].do_ping = 1; + } + } + + pp->err_count = 0U; + if(USB_USE_FIFO == udev->bp.transfer_mode) { + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_NAK, PIPE_NAK); + } else { + pp_reg->HCHINTF = HCHINTF_NAK; + } + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_NAK, PIPE_NAK); + } else if (intr_pp & HCHINTF_USBER) { + pp->err_count++; + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_USBER, PIPE_TRACERR); + } else if (intr_pp & HCHINTF_NYET) { + if (CTL_STATUS_OUT != uhost->control.ctl_state) { + if (0U == udev->host.pipe[pp_num].do_ping) { + if (1U == udev->host.pipe[pp_num].supp_ping) { + udev->host.pipe[pp_num].do_ping = 1; + } + } + + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_NYET, PIPE_NYET); + } else { + usb_pp_halt (udev, (uint8_t)pp_num, HCHINTF_NYET, PIPE_XF); + } + + pp->err_count = 0U; + } else if (intr_pp & HCHINTF_CH) { + udev->regs.pr[pp_num]->HCHINTEN &= ~HCHINTEN_CHIE; + + switch (pp->pp_status) { + case PIPE_XF: + pp->urb_state = URB_DONE; + + if ((uint8_t)USB_EPTYPE_BULK == ((pp_reg->HCHCTL & HCHCTL_EPTYPE) >> 18U)) { + pp->data_toggle_out ^= 1U; + } + break; + + case PIPE_NAK: + pp->urb_state = URB_NOTREADY; + break; + case PIPE_NYET: + pp->urb_state = URB_DONE; + + if ((uint8_t)USB_EPTYPE_BULK == ((pp_reg->HCHCTL & HCHCTL_EPTYPE) >> 18U)) { + pp->data_toggle_out ^= 1U; + } + break; + + case PIPE_STALL: + pp->urb_state = URB_STALL; + break; + + case PIPE_TRACERR: + if (3U == pp->err_count) { + pp->urb_state = URB_ERROR; + pp->err_count = 0U; + } + break; + + case PIPE_IDLE: + case PIPE_HALTED: + case PIPE_BBERR: + case PIPE_REQOVR: + case PIPE_DTGERR: + default: + break; + } + + pp_reg->HCHINTF = HCHINTF_CH; + } else { + /* no operation */ + } + + return 1U; +} + +/*! + \brief handle the RX FIFO non-empty interrupt + \param[in] udev: pointer to USB device instance + \param[out] none + \retval operation status +*/ +#if defined (__ICCARM__) /*!< IAR compiler */ + #pragma optimize = none +#endif /* __ICCARM */ +static uint32_t usbh_int_rxfifonoempty (usb_core_driver *udev) +{ + uint32_t count = 0U, xfer_count = 0U; + + __IO uint8_t pp_num = 0U; + __IO uint32_t rx_stat = 0U; + + /* disable the RX status queue level interrupt */ + udev->regs.gr->GINTEN &= ~GINTEN_RXFNEIE; + + rx_stat = udev->regs.gr->GRSTATP; + pp_num = (uint8_t)(rx_stat & GRSTATRP_CNUM); + + switch ((rx_stat & GRSTATRP_RPCKST) >> 17U) { + case GRXSTS_PKTSTS_IN: + count = (rx_stat & GRSTATRP_BCOUNT) >> 4U; + + /* read the data into the host buffer. */ + if ((count > 0U) && (NULL != udev->host.pipe[pp_num].xfer_buf)) { + (void)usb_rxfifo_read (&udev->regs, udev->host.pipe[pp_num].xfer_buf, (uint16_t)count); + + /* manage multiple transfer packet */ + udev->host.pipe[pp_num].xfer_buf += count; + udev->host.pipe[pp_num].xfer_count += count; + + xfer_count = udev->host.pipe[pp_num].xfer_count; + + udev->host.backup_xfercount[pp_num] = xfer_count; + + if (udev->regs.pr[pp_num]->HCHLEN & HCHLEN_PCNT) { + /* re-activate the channel when more packets are expected */ + uint32_t pp_ctl = udev->regs.pr[pp_num]->HCHCTL; + + pp_ctl |= HCHCTL_CEN; + pp_ctl &= ~HCHCTL_CDIS; + + udev->regs.pr[pp_num]->HCHCTL = pp_ctl; + } + } + break; + + case GRXSTS_PKTSTS_IN_XFER_COMP: + break; + + case GRXSTS_PKTSTS_DATA_TOGGLE_ERR: + count = (rx_stat & GRSTATRP_BCOUNT) >> 4U; + + while (count > 0U) { + rx_stat = udev->regs.gr->GRSTATP; + count--; + } + break; + + case GRXSTS_PKTSTS_CH_HALTED: + break; + + default: + break; + } + + /* enable the RX status queue level interrupt */ + udev->regs.gr->GINTEN |= GINTEN_RXFNEIE; + + return 1U; +} + +/*! + \brief handle the TX FIFO empty interrupt + \param[in] udev: pointer to USB device instance + \param[in] pp_mode: pipe mode + \param[out] none + \retval operation status +*/ +#if defined (__ICCARM__) /*!< IAR compiler */ + #pragma optimize = none +#endif /* __ICCARM */ +static uint32_t usbh_int_txfifoempty (usb_core_driver *udev, usb_pipe_mode pp_mode) +{ + uint8_t pp_num = 0U; + uint16_t word_count = 0U, len = 0U; + __IO uint32_t *txfiforeg = 0U, txfifostate = 0U; + + if (PIPE_NON_PERIOD == pp_mode) { + txfiforeg = &udev->regs.gr->HNPTFQSTAT; + } else if (PIPE_PERIOD == pp_mode) { + txfiforeg = &udev->regs.hr->HPTFQSTAT; + } else { + return 0U; + } + + txfifostate = *txfiforeg; + + pp_num = (uint8_t)((txfifostate & TFQSTAT_CNUM) >> 27U); + + word_count = (uint16_t)(udev->host.pipe[pp_num].xfer_len + 3U) / 4U; + + while (((txfifostate & TFQSTAT_TXFS) >= word_count) && (0U != udev->host.pipe[pp_num].xfer_len)) { + len = (uint16_t)(txfifostate & TFQSTAT_TXFS) * 4U; + + if (len > udev->host.pipe[pp_num].xfer_len) { + /* last packet */ + len = (uint16_t)udev->host.pipe[pp_num].xfer_len; + + if (PIPE_NON_PERIOD == pp_mode) { + udev->regs.gr->GINTEN &= ~GINTEN_NPTXFEIE; + } else { + udev->regs.gr->GINTEN &= ~GINTEN_PTXFEIE; + } + } + + word_count = (uint16_t)((udev->host.pipe[pp_num].xfer_len + 3U) / 4U); + usb_txfifo_write (&udev->regs, udev->host.pipe[pp_num].xfer_buf, pp_num, len); + + udev->host.pipe[pp_num].xfer_buf += len; + udev->host.pipe[pp_num].xfer_len -= len; + udev->host.pipe[pp_num].xfer_count += len; + + txfifostate = *txfiforeg; + } + + return 1U; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Include/usbh_hid_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Include/usbh_hid_core.h new file mode 100644 index 0000000..22c7f12 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Include/usbh_hid_core.h @@ -0,0 +1,120 @@ +/*! + \file usbh_hid_core.h + \brief header file for the usbh_hid_core.c + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_HID_CORE_H +#define __USBH_HID_CORE_H + +#include "usb_hid.h" +#include "usbh_enum.h" +#include "usbh_transc.h" + +#define HID_MIN_POLL 10U +#define HID_REPORT_SIZE 16U +#define HID_QUEUE_SIZE 10U + +#define USB_HID_DESC_SIZE 9U + +/* states for HID state machine */ +typedef enum { + HID_INIT = 0U, + HID_IDLE, + HID_SEND_DATA, + HID_BUSY, + HID_GET_DATA, + HID_SYNC, + HID_POLL, + HID_ERROR, +} hid_state; + +typedef enum { + HID_REQ_INIT = 0U, + HID_REQ_IDLE, + HID_REQ_GET_REPORT_DESC, + HID_REQ_GET_HID_DESC, + HID_REQ_SET_IDLE, + HID_REQ_SET_PROTOCOL, + HID_REQ_SET_REPORT, +} hid_ctlstate; + +typedef enum +{ + HID_MOUSE = 0x01U, + HID_KEYBOARD = 0x02U, + HID_UNKNOWN = 0xFFU, +} hid_type; + +typedef struct +{ + uint8_t *buf; + uint16_t head; + uint16_t tail; + uint16_t size; + uint8_t lock; +} data_fifo; + +/* structure for HID process */ +typedef struct _hid_process +{ + uint8_t pipe_in; + uint8_t pipe_out; + uint8_t ep_addr; + uint8_t ep_in; + uint8_t ep_out; + uint8_t *pdata; + __IO uint8_t data_ready; + uint16_t len; + uint16_t poll; + + __IO uint32_t timer; + usb_desc_hid hid_desc; + + hid_state state; + hid_ctlstate ctl_state; + + usbh_status (*init)(usb_core_driver *udev, usbh_host *uhost); + usbh_status (*decode)(uint8_t *data); +} usbh_hid_handler; + +extern usbh_class usbh_hid; + +/* function declarations */ +/* set HID report */ +usbh_status usbh_set_report (usb_core_driver *udev, + usbh_host *uhost, + uint8_t report_type, + uint8_t report_ID, + uint8_t report_len, + uint8_t *report_buf); + +#endif /* __USBH_HID_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Include/usbh_standard_hid.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Include/usbh_standard_hid.h new file mode 100644 index 0000000..e46a91a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Include/usbh_standard_hid.h @@ -0,0 +1,99 @@ +/*! + \file usbh_standard_hid.h + \brief header file for usbh_standard_hid.c + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_STANDARD_HID_H +#define __USBH_STANDARD_HID_H + +#include "usb_conf.h" +#include "usbh_hid_core.h" + +//#define AZERTY_KEYBOARD +#define QWERTY_KEYBOARD + +#define MOUSE_BUTTON_1 0x01U +#define MOUSE_BUTTON_2 0x02U +#define MOUSE_BUTTON_3 0x04U + +#define KBD_LEFT_CTRL 0x01U +#define KBD_LEFT_SHIFT 0x02U +#define KBD_LEFT_ALT 0x04U +#define KBD_LEFT_GUI 0x08U +#define KBD_RIGHT_CTRL 0x10U +#define KBD_RIGHT_SHIFT 0x20U +#define KBD_RIGHT_ALT 0x40U +#define KBD_RIGHT_GUI 0x80U + +#define KBD_PRESSED_MAX_NUM 6U + +typedef struct _hid_mouse_info +{ + uint8_t x; + uint8_t y; + uint8_t buttons[3]; +} hid_mouse_info; + +typedef struct +{ + uint8_t state; + uint8_t lctrl; + uint8_t lshift; + uint8_t lalt; + uint8_t lgui; + uint8_t rctrl; + uint8_t rshift; + uint8_t ralt; + uint8_t rgui; + uint8_t keys[6]; +} hid_keybd_info; + +/* function declarations */ +/* initialize mouse */ +void usr_mouse_init (void); +/* process mouse data */ +void usr_mouse_process_data (hid_mouse_info *data); +/* initialize mouse function */ +usbh_status usbh_hid_mouse_init (usb_core_driver *udev, usbh_host *uhost); +/* decode mouse information */ +usbh_status usbh_hid_mouse_decode(uint8_t *data); + +/* initialize keyboard */ +void usr_keybrd_init (void); +/* process keyboard data */ +void usr_keybrd_process_data (uint8_t pbuf); +/* initialize the keyboard function */ +usbh_status usbh_hid_keybrd_init (usb_core_driver *udev, usbh_host *uhost); +/* decode keyboard information */ +usbh_status usbh_hid_keybrd_decode (uint8_t *data); + +#endif /* __USBH_STANDARD_HID_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Source/usbh_hid_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Source/usbh_hid_core.c new file mode 100644 index 0000000..a6281c1 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Source/usbh_hid_core.c @@ -0,0 +1,582 @@ +/*! + \file usbh_hid_core.c + \brief USB host HID class driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 +#include +#include "usbh_pipe.h" +#include "usbh_hid_core.h" +#include "usbh_standard_hid.h" + +/* local function prototypes ('static') */ +static void usbh_hiddesc_parse (usb_desc_hid *hid_desc, uint8_t *buf); +static void usbh_hid_itf_deinit (usbh_host *uhost); +static usbh_status usbh_hid_itf_init (usbh_host *uhost); +static usbh_status usbh_hid_class_req (usbh_host *uhost); +static usbh_status usbh_hid_handle (usbh_host *uhost); +static usbh_status usbh_hid_reportdesc_get (usbh_host *uhost, uint16_t len); +static usbh_status usbh_hid_sof(usbh_host *uhost); +static usbh_status usbh_hid_desc_get (usbh_host *uhost, uint16_t len); +static usbh_status usbh_set_idle (usbh_host *uhost, uint8_t duration, uint8_t report_ID); +static usbh_status usbh_set_protocol (usbh_host *uhost, uint8_t protocol); + +usbh_class usbh_hid = +{ + USB_HID_CLASS, + usbh_hid_itf_init, + usbh_hid_itf_deinit, + usbh_hid_class_req, + usbh_hid_handle, + usbh_hid_sof +}; + +/*! + \brief get report + \param[in] uhost: pointer to USB host + \param[in] report_type: duration for HID set idle request + \param[in] report_ID: targeted report ID for HID set idle request + \param[in] report_len: length of data report to be send + \param[in] report_buf: report buffer + \param[out] none + \retval operation status +*/ +usbh_status usbh_get_report (usbh_host *uhost, + uint8_t report_type, + uint8_t report_ID, + uint8_t report_len, + uint8_t *report_buf) +{ + usbh_status status = USBH_BUSY; + + if (CTL_IDLE == uhost->control.ctl_state) { + uhost->control.setup.req = (usb_req) { + .bmRequestType = USB_TRX_IN | USB_RECPTYPE_ITF | USB_REQTYPE_CLASS, + .bRequest = GET_REPORT, + .wValue = (report_type << 8U) | report_ID, + .wIndex = 0U, + .wLength = report_len + }; + + usbh_ctlstate_config (uhost, report_buf, report_len); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief set report + \param[in] udev: pointer to USB core instance + \param[in] uhost: pointer to USB host + \param[in] report_type: duration for HID set idle request + \param[in] report_ID: targeted report ID for HID set idle request + \param[in] report_len: length of data report to be send + \param[in] report_buf: report buffer + \param[out] none + \retval operation status +*/ +usbh_status usbh_set_report (usb_core_driver *udev, + usbh_host *uhost, + uint8_t report_type, + uint8_t report_ID, + uint8_t report_len, + uint8_t *report_buf) +{ + usbh_status status = USBH_BUSY; + + if (CTL_IDLE == uhost->control.ctl_state) { + uhost->control.setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_ITF | USB_REQTYPE_CLASS, + .bRequest = SET_REPORT, + .wValue = (report_type << 8U) | report_ID, + .wIndex = 0U, + .wLength = report_len + }; + + usbh_ctlstate_config (uhost, report_buf, report_len); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief deinitialize the host pipes used for the HID class + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +void usbh_hid_itf_deinit (usbh_host *uhost) +{ + usbh_hid_handler *hid = (usbh_hid_handler *)uhost->active_class->class_data; + + if (0x00U != hid->pipe_in) { + usb_pipe_halt (uhost->data, hid->pipe_in); + + usbh_pipe_free (uhost->data, hid->pipe_in); + + hid->pipe_in = 0U; /* reset the pipe as free */ + } + + if (0x00U != hid->pipe_out) { + usb_pipe_halt (uhost->data, hid->pipe_out); + + usbh_pipe_free (uhost->data, hid->pipe_out); + + hid->pipe_out = 0U; /* reset the channel as free */ + } +} + +/*! + \brief return device type + \param[in] udev: pointer to USB core instance + \param[in] uhost: pointer to USB host + \param[out] none + \retval hid_type +*/ +hid_type usbh_hid_device_type_get(usb_core_driver *udev, usbh_host *uhost) +{ + hid_type type = HID_UNKNOWN; + uint8_t interface_protocol; + + if (HOST_CLASS_HANDLER == uhost->cur_state) { + interface_protocol = uhost->dev_prop.cfg_desc_set.itf_desc_set[uhost->dev_prop.cur_itf][0].itf_desc.bInterfaceProtocol; + + if (USB_HID_PROTOCOL_KEYBOARD == interface_protocol) { + type = HID_KEYBOARD; + } else { + if (USB_HID_PROTOCOL_MOUSE == interface_protocol) { + type = HID_MOUSE; + } + } + } + + return type; +} + +/*! + \brief return HID device poll time + \param[in] udev: pointer to USB core instance + \param[in] uhost: pointer to USB host + \param[out] none + \retval poll time (ms) +*/ +uint8_t usbh_hid_poll_interval_get (usb_core_driver *udev, usbh_host *uhost) +{ + usbh_hid_handler *hid = (usbh_hid_handler *)uhost->active_class->class_data; + + if ((HOST_CLASS_ENUM == uhost->cur_state) || + (HOST_USER_INPUT == uhost->cur_state) || + (HOST_CLASS_CHECK == uhost->cur_state) || + (HOST_CLASS_HANDLER == uhost->cur_state)) { + return (uint8_t)(hid->poll); + } else { + return 0U; + } +} + +/*! + \brief initialize the hid class + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static usbh_status usbh_hid_itf_init (usbh_host *uhost) +{ + uint8_t num = 0U, ep_num = 0U, interface = 0U; + usbh_status status = USBH_BUSY; + + interface = usbh_interface_find(&uhost->dev_prop, USB_HID_CLASS, USB_HID_SUBCLASS_BOOT_ITF, 0xFFU); + + if (0xFFU == interface) { + uhost->usr_cb->dev_not_supported(); + + status = USBH_FAIL; + } else { + usbh_interface_select(&uhost->dev_prop, interface); + + static usbh_hid_handler hid_handler; + + memset((void*)&hid_handler, 0, sizeof(usbh_hid_handler)); + + hid_handler.state = HID_ERROR; + + uint8_t itf_protocol = uhost->dev_prop.cfg_desc_set.itf_desc_set[uhost->dev_prop.cur_itf][0].itf_desc.bInterfaceProtocol; + if (USB_HID_PROTOCOL_KEYBOARD == itf_protocol) { + hid_handler.init = usbh_hid_keybrd_init; + hid_handler.decode = usbh_hid_keybrd_decode; + } else if (USB_HID_PROTOCOL_MOUSE == itf_protocol) { + hid_handler.init = usbh_hid_mouse_init; + hid_handler.decode = usbh_hid_mouse_decode; + } else { + status = USBH_FAIL; + } + + hid_handler.state = HID_INIT; + hid_handler.ctl_state = HID_REQ_INIT; + hid_handler.ep_addr = uhost->dev_prop.cfg_desc_set.itf_desc_set[uhost->dev_prop.cur_itf][0].ep_desc[0].bEndpointAddress; + hid_handler.len = uhost->dev_prop.cfg_desc_set.itf_desc_set[uhost->dev_prop.cur_itf][0].ep_desc[0].wMaxPacketSize; + hid_handler.poll = uhost->dev_prop.cfg_desc_set.itf_desc_set[uhost->dev_prop.cur_itf][0].ep_desc[0].bInterval; + + if (hid_handler.poll < HID_MIN_POLL) { + hid_handler.poll = HID_MIN_POLL; + } + + /* check for available number of endpoints */ + /* find the number of endpoints in the interface descriptor */ + /* choose the lower number in order not to overrun the buffer allocated */ + ep_num = USB_MIN(uhost->dev_prop.cfg_desc_set.itf_desc_set[uhost->dev_prop.cur_itf][0].itf_desc.bNumEndpoints, USBH_MAX_EP_NUM); + + /* decode endpoint IN and OUT address from interface descriptor */ + for (num = 0U; num < ep_num; num++) { + usb_desc_ep *ep_desc = &uhost->dev_prop.cfg_desc_set.itf_desc_set[uhost->dev_prop.cur_itf][0].ep_desc[num]; + + uint8_t ep_addr = ep_desc->bEndpointAddress; + + if (ep_addr & 0x80U) { + hid_handler.ep_in = ep_addr; + hid_handler.pipe_in = usbh_pipe_allocate (uhost->data, ep_addr); + + /* open channel for IN endpoint */ + usbh_pipe_create (uhost->data, + &uhost->dev_prop, + hid_handler.pipe_in, + USB_EPTYPE_INTR, + hid_handler.len); + + usbh_pipe_toggle_set(uhost->data, hid_handler.pipe_in, 0U); + } else { + hid_handler.ep_out = ep_addr; + hid_handler.pipe_out = usbh_pipe_allocate (uhost->data, ep_addr); + + /* open channel for OUT endpoint */ + usbh_pipe_create (uhost->data, + &uhost->dev_prop, + hid_handler.pipe_out, + USB_EPTYPE_INTR, + hid_handler.len); + + usbh_pipe_toggle_set(uhost->data, hid_handler.pipe_out, 0U); + } + } + + uhost->active_class->class_data = (void *)&hid_handler; + + status = USBH_OK; + } + + return status; +} + +/*! + \brief handle HID class requests for HID class + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static usbh_status usbh_hid_class_req (usbh_host *uhost) +{ + usbh_status status = USBH_BUSY; + usbh_status class_req_status = USBH_BUSY; + + usbh_hid_handler *hid = (usbh_hid_handler *)uhost->active_class->class_data; + + /* handle HID control state machine */ + switch (hid->ctl_state) { + case HID_REQ_INIT: + case HID_REQ_GET_HID_DESC: + /* get HID descriptor */ + if (USBH_OK == usbh_hid_desc_get (uhost, USB_HID_DESC_SIZE)) { + usbh_hiddesc_parse(&hid->hid_desc, uhost->dev_prop.data); + + hid->ctl_state = HID_REQ_GET_REPORT_DESC; + } + break; + + case HID_REQ_GET_REPORT_DESC: + /* get report descriptor */ + if (USBH_OK == usbh_hid_reportdesc_get(uhost, hid->hid_desc.wDescriptorLength)) { + hid->ctl_state = HID_REQ_SET_IDLE; + } + break; + + case HID_REQ_SET_IDLE: + class_req_status = usbh_set_idle (uhost, 0U, 0U); + + /* set idle */ + if (USBH_OK == class_req_status) { + hid->ctl_state = HID_REQ_SET_PROTOCOL; + } else { + if(USBH_NOT_SUPPORTED == class_req_status) { + hid->ctl_state = HID_REQ_SET_PROTOCOL; + } + } + break; + + case HID_REQ_SET_PROTOCOL: + /* set protocol */ + if (USBH_OK == usbh_set_protocol (uhost, 0U)) { + hid->ctl_state = HID_REQ_IDLE; + + /* all requests performed */ + status = USBH_OK; + } + break; + + case HID_REQ_IDLE: + default: + break; + } + + return status; +} + +/*! + \brief manage state machine for HID data transfers + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static usbh_status usbh_hid_handle (usbh_host *uhost) +{ + usbh_status status = USBH_OK; + usbh_hid_handler *hid = (usbh_hid_handler *)uhost->active_class->class_data; + + switch (hid->state) { + case HID_INIT: + hid->init(uhost->data, uhost); + hid->state = HID_IDLE; + break; + + case HID_IDLE: + hid->state = HID_SYNC; + status = USBH_OK; + break; + + case HID_SYNC: + /* sync with start of even frame */ + if (true == usb_frame_even(uhost->data)) { + hid->state = HID_GET_DATA; + } + break; + + case HID_GET_DATA: + usbh_data_recev (uhost->data, hid->pdata, hid->pipe_in, hid->len); + + hid->state = HID_POLL; + hid->timer = usb_curframe_get (uhost->data); + hid->data_ready = 0U; + break; + + case HID_POLL: + if (URB_DONE == usbh_urbstate_get (uhost->data, hid->pipe_in)) { + if (0U == hid->data_ready) { + hid->data_ready = 1U; + + hid->decode(hid->pdata); + } + } else { + /* check IN endpoint stall status */ + if (URB_STALL == usbh_urbstate_get (uhost->data, hid->pipe_in)) { + /* issue clear feature on interrupt in endpoint */ + if (USBH_OK == (usbh_clrfeature (uhost, hid->ep_addr, hid->pipe_in))) { + /* change state to issue next in token */ + hid->state = HID_GET_DATA; + } + } + } + break; + + default: + break; + } + return status; +} + +/*! + \brief send get report descriptor command to the device + \param[in] uhost: pointer to USB host + \param[in] len: HID report descriptor length + \param[out] none + \retval operation status +*/ +static usbh_status usbh_hid_reportdesc_get (usbh_host *uhost, uint16_t len) +{ + usbh_status status = USBH_BUSY; + + if (CTL_IDLE == uhost->control.ctl_state) { + uhost->control.setup.req = (usb_req) { + .bmRequestType = USB_TRX_IN | USB_RECPTYPE_ITF | USB_REQTYPE_STRD, + .bRequest = USB_GET_DESCRIPTOR, + .wValue = USBH_DESC(USB_DESCTYPE_REPORT), + .wIndex = 0U, + .wLength = len + }; + + usbh_ctlstate_config (uhost, uhost->dev_prop.data, len); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief managing the SOF process + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static usbh_status usbh_hid_sof(usbh_host *uhost) +{ + usbh_hid_handler *hid = (usbh_hid_handler *)uhost->active_class->class_data; + + if (HID_POLL == hid->state) { + uint32_t frame_count = usb_curframe_get (uhost->data); + + if ((frame_count > hid->timer) && ((frame_count - hid->timer) >= hid->poll)) { + hid->state = HID_GET_DATA; + } else if ((frame_count < hid->timer) && ((frame_count + 0x3FFFU - hid->timer) >= hid->poll)) { + hid->state = HID_GET_DATA; + } else { + /* no operation */ + } + } + + return USBH_OK; +} + +/*! + \brief send the command of get HID descriptor to the device + \param[in] uhost: pointer to USB host + \param[in] len: HID descriptor length + \param[out] none + \retval operation status +*/ +static usbh_status usbh_hid_desc_get (usbh_host *uhost, uint16_t len) +{ + usbh_status status = USBH_BUSY; + + if (CTL_IDLE == uhost->control.ctl_state) { + uhost->control.setup.req = (usb_req) { + .bmRequestType = USB_TRX_IN | USB_RECPTYPE_ITF | USB_REQTYPE_STRD, + .bRequest = USB_GET_DESCRIPTOR, + .wValue = USBH_DESC(USB_DESCTYPE_HID), + .wIndex = 0U, + .wLength = len + }; + + usbh_ctlstate_config (uhost, uhost->dev_prop.data, len); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief set idle state + \param[in] uhost: pointer to USB host + \param[in] duration: duration for HID set idle request + \param[in] report_ID: targeted report ID for HID set idle request + \param[out] none + \retval operation status +*/ +static usbh_status usbh_set_idle (usbh_host *uhost, uint8_t duration, uint8_t report_ID) +{ + usbh_status status = USBH_BUSY; + + if (CTL_IDLE == uhost->control.ctl_state) { + uhost->control.setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_ITF | USB_REQTYPE_CLASS, + .bRequest = SET_IDLE, + .wValue = (duration << 8U) | report_ID, + .wIndex = 0U, + .wLength = 0U + }; + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief set protocol state + \param[in] uhost: pointer to USB host + \param[in] protocol: boot/report protocol + \param[out] none + \retval operation status +*/ +static usbh_status usbh_set_protocol (usbh_host *uhost, uint8_t protocol) +{ + usbh_status status = USBH_BUSY; + + if (CTL_IDLE == uhost->control.ctl_state) { + uhost->control.setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_ITF | USB_REQTYPE_CLASS, + .bRequest = SET_PROTOCOL, + .wValue = !protocol, + .wIndex = 0U, + .wLength = 0U + }; + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief parse the HID descriptor + \param[in] hid_desc: pointer to HID descriptor + \param[in] buf: pointer to buffer where the source descriptor is available + \param[out] none + \retval none +*/ +static void usbh_hiddesc_parse (usb_desc_hid *hid_desc, uint8_t *buf) +{ + hid_desc->header.bLength = *(uint8_t *)(buf + 0U); + hid_desc->header.bDescriptorType = *(uint8_t *)(buf + 1U); + hid_desc->bcdHID = BYTE_SWAP(buf + 2U); + hid_desc->bCountryCode = *(uint8_t *)(buf + 4U); + hid_desc->bNumDescriptors = *(uint8_t *)(buf + 5U); + hid_desc->bDescriptorType = *(uint8_t *)(buf + 6U); + hid_desc->wDescriptorLength = BYTE_SWAP(buf + 7U); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Source/usbh_standard_hid.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Source/usbh_standard_hid.c new file mode 100644 index 0000000..286a4a0 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/hid/Source/usbh_standard_hid.c @@ -0,0 +1,274 @@ +/*! + \file usbh_standard_hid.c + \brief USB host HID keyboard and mouse driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbh_standard_hid.h" +#include + +hid_mouse_info mouse_info; +hid_keybd_info keybd_info; + +__ALIGN_BEGIN uint8_t mouse_report_data[8] __ALIGN_END = {0U}; +__ALIGN_BEGIN uint32_t keybd_report_data[2] __ALIGN_END; + +/* local constants */ +static const uint8_t kbd_codes[] = +{ + 0, 0, 0, 0, 31, 50, 48, 33, + 19, 34, 35, 36, 24, 37, 38, 39, /* 0x00 - 0x0F */ + 52, 51, 25, 26, 17, 20, 32, 21, + 23, 49, 18, 47, 22, 46, 2, 3, /* 0x10 - 0x1F */ + 4, 5, 6, 7, 8, 9, 10, 11, + 43, 110, 15, 16, 61, 12, 13, 27, /* 0x20 - 0x2F */ + 28, 29, 42, 40, 41, 1, 53, 54, + 55, 30, 112, 113, 114, 115, 116, 117, /* 0x30 - 0x3F */ + 118, 119, 120, 121, 122, 123, 124, 125, + 126, 75, 80, 85, 76, 81, 86, 89, /* 0x40 - 0x4F */ + 79, 84, 83, 90, 95, 100, 105, 106, + 108, 93, 98, 103, 92, 97, 102, 91, /* 0x50 - 0x5F */ + 96, 101, 99, 104, 45, 129, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, /* 0x60 - 0x6F */ + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, /* 0x70 - 0x7F */ + 0, 0, 0, 0, 0, 107, 0, 56, + 0, 0, 0, 0, 0, 0, 0, 0, /* 0x80 - 0x8F */ + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, /* 0x90 - 0x9F */ + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, /* 0xA0 - 0xAF */ + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, /* 0xB0 - 0xBF */ + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, /* 0xC0 - 0xCF */ + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, /* 0xD0 - 0xDF */ + 58, 44, 60, 127, 64, 57, 62, 128 /* 0xE0 - 0xE7 */ +}; + +#ifdef QWERTY_KEYBOARD + +static const int8_t kbd_key[] = +{ + '\0', '`', '1', '2', '3', '4', '5', '6', + '7', '8', '9', '0', '-', '=', '\0', '\r', + '\t', 'q', 'w', 'e', 'r', 't', 'y', 'u', + 'i', 'o', 'p', '[', ']', '\\', + '\0', 'a', 's', 'd', 'f', 'g', 'h', 'j', + 'k', 'l', ';', '\'', '\0', '\n', + '\0', '\0', 'z', 'x', 'c', 'v', 'b', 'n', + 'm', ',', '.', '/', '\0', '\0', + '\0', '\0', '\0', ' ', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\r', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '7', '4', '1', + '\0', '/', '8', '5', '2', + '0', '*', '9', '6', '3', + '.', '-', '+', '\0', '\n', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0' +}; + +static const int8_t kbd_key_shift[] = { + '\0', '~', '!', '@', '#', '$', '%', '^', '&', '*', '(', ')', + '_', '+', '\0', '\0', '\0', 'Q', 'W', 'E', 'R', 'T', 'Y', 'U', + 'I', 'O', 'P', '{', '}', '|', '\0', 'A', 'S', 'D', 'F', 'G', + 'H', 'J', 'K', 'L', ':', '"', '\0', '\n', '\0', '\0', 'Z', 'X', + 'C', 'V', 'B', 'N', 'M', '<', '>', '?', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0' +}; + +#else + +static const int8_t kbd_key[] = { + '\0', '`', '1', '2', '3', '4', '5', '6', '7', '8', '9', '0', + '-', '=', '\0', '\r', '\t', 'a', 'z', 'e', 'r', 't', 'y', 'u', + 'i', 'o', 'p', '[', ']', '\\', '\0', 'q', 's', 'd', 'f', 'g', + 'h', 'j', 'k', 'l', 'm', '\0', '\0', '\n', '\0', '\0', 'w', 'x', + 'c', 'v', 'b', 'n', ',', ';', ':', '!', '\0', '\0', '\0', '\0', + '\0', ' ', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\r', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '7', '4', '1', '\0', '/', + '8', '5', '2', '0', '*', '9', '6', '3', '.', '-', '+', '\0', + '\n', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0' +}; + +static const int8_t kbd_key_shift[] = { + '\0', '~', '!', '@', '#', '$', '%', '^', '&', '*', '(', ')', '_', + '+', '\0', '\0', '\0', 'A', 'Z', 'E', 'R', 'T', 'Y', 'U', 'I', 'O', + 'P', '{', '}', '*', '\0', 'Q', 'S', 'D', 'F', 'G', 'H', 'J', 'K', + 'L', 'M', '%', '\0', '\n', '\0', '\0', 'W', 'X', 'C', 'V', 'B', 'N', + '?', '.', '/', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', + '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0', '\0' +}; + +#endif /* QWERTY_KEYBOARD */ + +/*! + \brief initialize the mouse function + \param[in] udev: pointer to USB core instance + \param[in] uhost: pointer to USB host + \param[out] none + \retval none +*/ +usbh_status usbh_hid_mouse_init (usb_core_driver *udev, usbh_host *uhost) +{ + usbh_hid_handler *hid = (usbh_hid_handler *)uhost->active_class->class_data; + + mouse_info.x = 0U; + mouse_info.y = 0U; + mouse_info.buttons[0] = 0U; + mouse_info.buttons[1] = 0U; + mouse_info.buttons[2] = 0U; + + if(hid->len > sizeof(mouse_report_data)) { + hid->len = sizeof(mouse_report_data); + } + + hid->pdata = (uint8_t *)(void *)mouse_report_data; + + usr_mouse_init(); + + return USBH_OK; +} + +/*! + \brief decode mouse information + \param[in] udev: pointer to USB core instance + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +usbh_status usbh_hid_mouse_decode(uint8_t *data) +{ + mouse_info.buttons[0] = data[0] & MOUSE_BUTTON_1; + mouse_info.buttons[1] = data[0] & MOUSE_BUTTON_2; + mouse_info.buttons[2] = data[0] & MOUSE_BUTTON_3; + + mouse_info.x = data[1]; + mouse_info.y = data[2]; + + /* handle mouse data position */ + usr_mouse_process_data(&mouse_info); + + return USBH_FAIL; +} + +/*! + \brief initialize the keyboard function + \param[in] udev: pointer to USB core instance + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +usbh_status usbh_hid_keybrd_init (usb_core_driver *udev, usbh_host *uhost) +{ + usbh_hid_handler *hid = (usbh_hid_handler *)uhost->active_class->class_data; + + keybd_info.lctrl = keybd_info.lshift = 0U; + keybd_info.lalt = keybd_info.lgui = 0U; + keybd_info.rctrl = keybd_info.rshift = 0U; + keybd_info.ralt = keybd_info.rgui = 0U; + + for (uint32_t x = 0U; x < (sizeof(keybd_report_data) / sizeof(uint32_t)); x++) { + keybd_report_data[x] = 0U; + } + + if (hid->len > (sizeof(keybd_report_data) / sizeof(uint32_t))) { + hid->len = (sizeof(keybd_report_data) / sizeof(uint32_t)); + } + + hid->pdata = (uint8_t*)(void *)keybd_report_data; + + /* call user initialization*/ + usr_keybrd_init(); + + return USBH_OK; +} + +/*! + \brief get ascii code + \param[in] info: keyboard information + \param[out] none + \retval output +*/ +uint8_t usbh_hid_ascii_code_get (hid_keybd_info *info) +{ + uint8_t output; + if ((1U == info->lshift) || (info->rshift)) { + output = kbd_key_shift[kbd_codes[info->keys[0]]]; + } else { + output = kbd_key[kbd_codes[info->keys[0]]]; + } + + return output; +} + +/*! + \brief decode keyboard information + \param[in] udev: pointer to USB core instance + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +usbh_status usbh_hid_keybrd_decode (uint8_t *data) +{ + uint8_t output; + + keybd_info.lshift = data[0] & KBD_LEFT_SHIFT; + keybd_info.rshift = data[0] & KBD_RIGHT_SHIFT; + + keybd_info.keys[0] = data[2]; + + if (keybd_info.lshift || keybd_info.rshift) { + output = kbd_key_shift[kbd_codes[keybd_info.keys[0]]]; + } else { + output = kbd_key[kbd_codes[keybd_info.keys[0]]]; + } + + if (0U != output) { + usr_keybrd_process_data(output); + } + + return USBH_OK; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_bbb.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_bbb.h new file mode 100644 index 0000000..e8bcf97 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_bbb.h @@ -0,0 +1,150 @@ +/*! + \file usbh_msc_bbb.h + \brief header file for usbh_msc_bbb.c + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_MSC_BBB_H +#define __USBH_MSC_BBB_H + +#include "usbh_enum.h" +#include "msc_bbb.h" + +typedef union { + msc_bbb_cbw field; + + uint8_t CBWArray[31]; +} usbh_cbw_pkt; + +typedef union { + msc_bbb_csw field; + + uint8_t CSWArray[13]; +} usbh_csw_pkt; + +enum usbh_msc_state { + USBH_MSC_BBB_INIT_STATE = 0U, + USBH_MSC_BBB_RESET, + USBH_MSC_GET_MAX_LUN, + USBH_MSC_TEST_UNIT_READY, + USBH_MSC_READ_CAPACITY10, + USBH_MSC_MODE_SENSE6, + USBH_MSC_REQUEST_SENSE, + USBH_MSC_BBB_USB_TRANSFERS, + USBH_MSC_DEFAULT_APPLI_STATE, + USBH_MSC_CTRL_ERROR_STATE, + USBH_MSC_UNRECOVERED_STATE +}; + +typedef enum +{ + BBB_OK = 0U, + BBB_FAIL, + BBB_PHASE_ERROR, + BBB_BUSY +} bbb_status; + +typedef enum +{ + BBB_CMD_IDLE = 0U, + BBB_CMD_SEND, + BBB_CMD_WAIT +} bbb_cmd_state; + +/* csw status definitions */ +typedef enum +{ + BBB_CSW_CMD_PASSED = 0U, + BBB_CSW_CMD_FAILED, + BBB_CSW_PHASE_ERROR +} bbb_csw_status; + +typedef enum +{ + BBB_SEND_CBW = 1U, + BBB_SEND_CBW_WAIT, + BBB_DATA_IN, + BBB_DATA_IN_WAIT, + BBB_DATA_OUT, + BBB_DATA_OUT_WAIT, + BBB_RECEIVE_CSW, + BBB_RECEIVE_CSW_WAIT, + BBB_ERROR_IN, + BBB_ERROR_OUT, + BBB_UNRECOVERED_ERROR +} bbb_state; + +typedef struct +{ + uint8_t *pbuf; + uint32_t data[16]; + bbb_state state; + bbb_state prev_state; + bbb_cmd_state cmd_state; + usbh_cbw_pkt cbw; + usbh_csw_pkt csw; +} bbb_handle; + +#define USBH_MSC_BBB_CBW_TAG 0x20304050U + +#define USBH_MSC_CSW_MAX_LENGTH 63U + +#define USBH_MSC_SEND_CSW_DISABLE 0U +#define USBH_MSC_SEND_CSW_ENABLE 1U + +#define USBH_MSC_DIR_IN 0U +#define USBH_MSC_DIR_OUT 1U +#define USBH_MSC_BOTH_DIR 2U + +#define USBH_MSC_PAGE_LENGTH 512U + +#define CBW_CB_LENGTH 16U +#define CBW_LENGTH 10U +#define CBW_LENGTH_TEST_UNIT_READY 0U + +#define MAX_BULK_STALL_COUNT_LIMIT 0x04U /*!< If STALL is seen on Bulk + Endpoint continously, this means + that device and Host has phase error + Hence a Reset is needed */ + +/* function declarations */ +/* initialize the mass storage parameters */ +void usbh_msc_bbb_init (usbh_host *uhost); +/* manage the different states of BBB transfer and updates the status to upper layer */ +usbh_status usbh_msc_bbb_process (usbh_host *uhost, uint8_t lun); +/* manages the different error handling for stall */ +usbh_status usbh_msc_bbb_abort (usbh_host *uhost, uint8_t direction); +/* reset MSC BBB request structure */ +usbh_status usbh_msc_bbb_reset (usbh_host *uhost); +/* decode the CSW received by the device and updates the same to upper layer */ +bbb_csw_status usbh_msc_csw_decode (usbh_host *uhost); + +#endif /* __USBH_MSC_BBB_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_core.h new file mode 100644 index 0000000..f4612d0 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_core.h @@ -0,0 +1,124 @@ +/*! + \file usbh_core.h + \brief header file for the usbh_core.c + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_MSC_CORE_H +#define __USBH_MSC_CORE_H + +#include "usb_msc.h" +#include "usbh_msc_scsi.h" +#include "usbh_msc_bbb.h" + +#define MSC_MAX_SUPPORTED_LUN 2U + +typedef enum +{ + MSC_INIT = 0U, + MSC_IDLE, + MSC_TEST_UNIT_READY, + MSC_READ_CAPACITY10, + MSC_READ_INQUIRY, + MSC_REQUEST_SENSE, + MSC_READ, + MSC_WRITE, + MSC_UNRECOVERED_ERROR, + MSC_PERIODIC_CHECK, +} msc_state; + +typedef enum +{ + MSC_OK, + MSC_NOT_READY, + MSC_ERROR, +} msc_error; + +typedef enum +{ + MSC_REQ_IDLE = 0U, + MSC_REQ_RESET, + MSC_REQ_GET_MAX_LUN, + MSC_REQ_ERROR, +} msc_req_state; + +/* structure for LUN */ +typedef struct +{ + msc_state state; + msc_error error; + msc_scsi_sense sense; + scsi_capacity capacity; + scsi_std_inquiry_data inquiry; + usbh_status prev_ready_state; + uint8_t state_changed; +} msc_lun; + +/* structure for msc process */ +typedef struct _msc_process +{ + uint8_t pipe_in; + uint8_t pipe_out; + uint8_t ep_in; + uint8_t ep_out; + uint16_t ep_size_in; + uint16_t ep_size_out; + uint8_t cur_lun; + uint16_t rw_lun; + uint32_t max_lun; + msc_state state; + msc_error error; + msc_req_state req_state; + msc_req_state prev_req_state; + bbb_handle bbb; + msc_lun unit[MSC_MAX_SUPPORTED_LUN]; + uint32_t timer; +} usbh_msc_handler; + +extern usbh_class usbh_msc; + +/* function declarations */ +/* get msc logic unit information */ +usbh_status usbh_msc_lun_info_get (usbh_host *uhost, uint8_t lun, msc_lun *info); +/* msc read interface */ +usbh_status usbh_msc_read (usbh_host *uhost, + uint8_t lun, + uint32_t address, + uint8_t *pbuf, + uint32_t length); +/* msc write interface */ +usbh_status usbh_msc_write (usbh_host *uhost, + uint8_t lun, + uint32_t address, + uint8_t *pbuf, + uint32_t length); + +#endif /* __USBH_MSC_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_scsi.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_scsi.h new file mode 100644 index 0000000..8eaa9c5 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Include/usbh_msc_scsi.h @@ -0,0 +1,100 @@ +/*! + \file usbh_msc_scsi.h + \brief header file for usbh_msc_scsi.c + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_MSC_SCSI_H +#define __USBH_MSC_SCSI_H + +#include "msc_scsi.h" +#include "usbh_enum.h" + +/* capacity data */ +typedef struct +{ + uint32_t block_nbr; + uint16_t block_size; +} scsi_capacity; + +/* inquiry data */ +typedef struct +{ + uint8_t peripheral_qualifier; + uint8_t device_type; + uint8_t removable_media; + uint8_t vendor_id[9]; + uint8_t product_id[17]; + uint8_t revision_id[5]; +} scsi_std_inquiry_data; + +typedef struct +{ + uint32_t msc_capacity; + uint32_t msc_sense_key; + uint16_t msc_page_len; + uint8_t msc_write_protect; +} usbh_msc_parameter; + +#define DESC_REQUEST_SENSE 0x00U +#define ALLOCATION_LENGTH_REQUEST_SENSE 63U +#define XFER_LEN_MODE_SENSE6 63U + +#define MASK_MODE_SENSE_WRITE_PROTECT 0x80U +#define MODE_SENSE_PAGE_CONTROL_FIELD 0x00U +#define MODE_SENSE_PAGE_CODE 0x3FU +#define DISK_WRITE_PROTECTED 0x01U + +/* function declarations */ +/* send 'Inquiry' command to the device */ +usbh_status usbh_msc_scsi_inquiry (usbh_host *uhost, uint8_t lun, scsi_std_inquiry_data *inquiry); +/* send 'Test unit ready' command to the device */ +usbh_status usbh_msc_test_unitready (usbh_host *uhost, uint8_t lun); +/* send the read capacity command to the device */ +usbh_status usbh_msc_read_capacity10 (usbh_host *uhost, uint8_t lun, scsi_capacity *capacity); +/* send the mode sense6 command to the device */ +usbh_status usbh_msc_mode_sense6 (usbh_host *uhost, uint8_t lun); +/* send the Request Sense command to the device */ +usbh_status usbh_msc_request_sense (usbh_host *uhost, uint8_t lun, msc_scsi_sense *sense_data); +/* send the write10 command to the device */ +usbh_status usbh_msc_write10 (usbh_host *uhost, + uint8_t lun, + uint8_t *data_buf, + uint32_t addr, + uint32_t byte_num); +/* send the read10 command to the device */ +usbh_status usbh_msc_read10 (usbh_host *uhost, + uint8_t lun, + uint8_t *data_buf, + uint32_t addr, + uint32_t byte_num); + +#endif /* __USBH_MSC_SCSI_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_bbb.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_bbb.c new file mode 100644 index 0000000..cda7e07 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_bbb.c @@ -0,0 +1,362 @@ +/*! + \file usbh_msc_bbb.c + \brief USB MSC BBB protocol related functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbh_pipe.h" +#include "usbh_msc_core.h" +#include "usbh_msc_scsi.h" +#include "usbh_msc_bbb.h" +#include "usbh_transc.h" +#include "drv_usbh_int.h" + +/*! + \brief initialize the mass storage parameters + \param[in] uhost: pointer to USB host handler + \param[out] none + \retval none +*/ +void usbh_msc_bbb_init (usbh_host *uhost) +{ + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + msc->bbb.cbw.field.dCBWSignature = BBB_CBW_SIGNATURE; + msc->bbb.cbw.field.dCBWTag = USBH_MSC_BBB_CBW_TAG; + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_SEND; +} + +/*! + \brief manage the different states of BBB transfer and updates the status to upper layer + \param[in] uhost: pointer to USB host handler + \param[in] lun: logic unit number + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_bbb_process (usbh_host *uhost, uint8_t lun) +{ + bbb_csw_status csw_status = BBB_CSW_CMD_FAILED; + usbh_status status = USBH_BUSY; + usbh_status error = USBH_BUSY; + usb_urb_state urb_status = URB_IDLE; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (msc->bbb.state) { + case BBB_SEND_CBW: + msc->bbb.cbw.field.bCBWLUN = lun; + msc->bbb.state = BBB_SEND_CBW_WAIT; + /* send CBW */ + usbh_data_send (uhost->data, + msc->bbb.cbw.CBWArray, + msc->pipe_out, + BBB_CBW_LENGTH); + break; + + case BBB_SEND_CBW_WAIT: + urb_status = usbh_urbstate_get(uhost->data, msc->pipe_out); + + if (URB_DONE == urb_status) { + if (0U != msc->bbb.cbw.field.dCBWDataTransferLength) { + if (USB_TRX_IN == (msc->bbb.cbw.field.bmCBWFlags & USB_TRX_MASK)) { + msc->bbb.state = BBB_DATA_IN; + } else { + msc->bbb.state = BBB_DATA_OUT; + } + } else { + msc->bbb.state = BBB_RECEIVE_CSW; + } + + } else if (URB_NOTREADY == urb_status) { + msc->bbb.state = BBB_SEND_CBW; + } else { + if (URB_STALL == urb_status) { + msc->bbb.state = BBB_ERROR_OUT; + } + } + break; + + case BBB_DATA_IN: + usbh_data_recev (uhost->data, + msc->bbb.pbuf, + msc->pipe_in, + msc->ep_size_in); + + msc->bbb.state = BBB_DATA_IN_WAIT; + break; + + case BBB_DATA_IN_WAIT: + urb_status = usbh_urbstate_get(uhost->data, msc->pipe_in); + + /* BBB DATA IN stage */ + if (URB_DONE == urb_status) { + if (msc->bbb.cbw.field.dCBWDataTransferLength > msc->ep_size_in) { + msc->bbb.pbuf += msc->ep_size_in; + msc->bbb.cbw.field.dCBWDataTransferLength -= msc->ep_size_in; + } else { + msc->bbb.cbw.field.dCBWDataTransferLength = 0U; + } + + if (msc->bbb.cbw.field.dCBWDataTransferLength > 0U) { + usbh_data_recev (uhost->data, + msc->bbb.pbuf, + msc->pipe_in, + msc->ep_size_in); + } else { + msc->bbb.state = BBB_RECEIVE_CSW; + } + } else if(URB_STALL == urb_status) { + /* this is data stage stall condition */ + msc->bbb.state = BBB_ERROR_IN; + } else { + /* no operation */ + } + break; + + case BBB_DATA_OUT: + usbh_data_send (uhost->data, + msc->bbb.pbuf, + msc->pipe_out, + msc->ep_size_out); + + msc->bbb.state = BBB_DATA_OUT_WAIT; + break; + + case BBB_DATA_OUT_WAIT: + /* BBB DATA OUT stage */ + urb_status = usbh_urbstate_get(uhost->data, msc->pipe_out); + if (URB_DONE == urb_status) { + if (msc->bbb.cbw.field.dCBWDataTransferLength > msc->ep_size_out) { + msc->bbb.pbuf += msc->ep_size_out; + msc->bbb.cbw.field.dCBWDataTransferLength -= msc->ep_size_out; + } else { + msc->bbb.cbw.field.dCBWDataTransferLength = 0; /* reset this value and keep in same state */ + } + + if (msc->bbb.cbw.field.dCBWDataTransferLength > 0) { + usbh_data_send (uhost->data, + msc->bbb.pbuf, + msc->pipe_out, + msc->ep_size_out); + } else { + msc->bbb.state = BBB_RECEIVE_CSW; + } + } else if (URB_NOTREADY == urb_status) { + msc->bbb.state = BBB_DATA_OUT; + } else if (URB_STALL == urb_status) { + msc->bbb.state = BBB_ERROR_OUT; + } else { + /* no operation */ + } + break; + + case BBB_RECEIVE_CSW: + /* BBB CSW stage */ + usbh_data_recev (uhost->data, + msc->bbb.csw.CSWArray, + msc->pipe_in, + BBB_CSW_LENGTH); + + msc->bbb.state = BBB_RECEIVE_CSW_WAIT; + break; + + case BBB_RECEIVE_CSW_WAIT: + urb_status = usbh_urbstate_get(uhost->data, msc->pipe_in); + + /* decode CSW */ + if (URB_DONE == urb_status) { + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_SEND; + + csw_status = usbh_msc_csw_decode(uhost); + if (BBB_CSW_CMD_PASSED == csw_status) { + status = USBH_OK; + } else { + status = USBH_FAIL; + } + } else if (URB_STALL == urb_status) { + msc->bbb.state = BBB_ERROR_IN; + } else { + /* no operation */ + } + break; + + case BBB_ERROR_IN: + error = usbh_msc_bbb_abort(uhost, USBH_MSC_DIR_IN); + + if (USBH_OK == error) { + msc->bbb.state = BBB_RECEIVE_CSW; + } else if (USBH_UNRECOVERED_ERROR == status) { + /* this means that there is a stall error limit, do reset recovery */ + msc->bbb.state = BBB_UNRECOVERED_ERROR; + } else { + /* no operation */ + } + break; + + case BBB_ERROR_OUT: + status = usbh_msc_bbb_abort (uhost, USBH_MSC_DIR_OUT); + + if (USBH_OK == status) { + uint8_t toggle = usbh_pipe_toggle_get(uhost->data, msc->pipe_out); + usbh_pipe_toggle_set(uhost->data, msc->pipe_out, 1U - toggle); + usbh_pipe_toggle_set(uhost->data, msc->pipe_in, 0U); + msc->bbb.state = BBB_ERROR_IN; + } else { + if (USBH_UNRECOVERED_ERROR == status) { + msc->bbb.state = BBB_UNRECOVERED_ERROR; + } + } + break; + + case BBB_UNRECOVERED_ERROR: + status = usbh_msc_bbb_reset(uhost); + if (USBH_OK == status) { + msc->bbb.state = BBB_SEND_CBW; + } + break; + + default: + break; + } + + return status; +} + +/*! + \brief manages the different error handling for stall + \param[in] uhost: pointer to USB host handler + \param[in] direction: data IN or OUT + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_bbb_abort (usbh_host *uhost, uint8_t direction) +{ + usbh_status status = USBH_BUSY; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (direction) { + case USBH_MSC_DIR_IN : + /* send clrfeature command on bulk IN endpoint */ + status = usbh_clrfeature(uhost, + msc->ep_in, + msc->pipe_in); + break; + + case USBH_MSC_DIR_OUT : + /*send clrfeature command on bulk OUT endpoint */ + status = usbh_clrfeature(uhost, + msc->ep_out, + msc->pipe_out); + break; + + default: + break; + } + + return status; +} + +/*! + \brief reset msc bbb transfer + \param[in] uhost: pointer to USB host handler + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_bbb_reset (usbh_host *uhost) +{ + usbh_status status = USBH_BUSY; + + if (CTL_IDLE == uhost->control.ctl_state) { + uhost->control.setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_REQTYPE_CLASS | USB_RECPTYPE_ITF, + .bRequest = BBB_RESET, + .wValue = 0U, + .wIndex = 0U, + .wLength = 0U + }; + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief decode the CSW received by the device and updates the same to upper layer + \param[in] uhost: pointer to USB host + \param[out] none + \retval on success USBH_MSC_OK, on failure USBH_MSC_FAIL + \notes + Refer to USB Mass-Storage Class: BBB (www.usb.org) + 6.3.1 Valid CSW Conditions : + The host shall consider the CSW valid when: + 1. dCSWSignature is equal to 53425355h + 2. the CSW is 13 (Dh) bytes in length, + 3. dCSWTag matches the dCBWTag from the corresponding CBW. +*/ +bbb_csw_status usbh_msc_csw_decode (usbh_host *uhost) +{ + bbb_csw_status status = BBB_CSW_CMD_FAILED; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + /* checking if the transfer length is different than 13 */ + if (BBB_CSW_LENGTH != usbh_xfercount_get (uhost->data, msc->pipe_in)) { + status = BBB_CSW_PHASE_ERROR; + } else { + /* CSW length is correct */ + + /* check validity of the CSW Signature and CSWStatus */ + if (BBB_CSW_SIGNATURE == msc->bbb.csw.field.dCSWSignature) { + /* check condition 1. dCSWSignature is equal to 53425355h */ + if (msc->bbb.csw.field.dCSWTag == msc->bbb.cbw.field.dCBWTag) { + /* check condition 3. dCSWTag matches the dCBWTag from the corresponding CBW */ + if (0U == msc->bbb.csw.field.bCSWStatus) { + status = BBB_CSW_CMD_PASSED; + } else if (1U == msc->bbb.csw.field.bCSWStatus) { + status = BBB_CSW_CMD_FAILED; + } else if (2U == msc->bbb.csw.field.bCSWStatus) { + status = BBB_CSW_PHASE_ERROR; + } else { + /* no operation */ + } + } + } else { + /* if the CSW signature is not valid, we shall return the phase error to + upper layers for reset recovery */ + status = BBB_CSW_PHASE_ERROR; + } + } + + return status; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_core.c new file mode 100644 index 0000000..3756f6a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_core.c @@ -0,0 +1,555 @@ +/*! + \file usbh_core.c + \brief USB MSC(mass storage device) class driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbh_msc_core.h" +#include "usbh_msc_scsi.h" +#include "usbh_msc_bbb.h" +#include "usbh_pipe.h" +#include "usbh_transc.h" +#include +#include + +/* local function prototypes ('static') */ +static void usbh_msc_itf_deinit (usbh_host *uhost); +static usbh_status usbh_msc_itf_init (usbh_host *uhost); +static usbh_status usbh_msc_req (usbh_host *uhost); +static usbh_status usbh_msc_handle (usbh_host *uhost); +static usbh_status usbh_msc_maxlun_get (usbh_host *uhost, uint8_t *maxlun); +static usbh_status usbh_msc_rdwr_process(usbh_host *uhost, uint8_t lun); + +usbh_class usbh_msc = +{ + USB_CLASS_MSC, + usbh_msc_itf_init, + usbh_msc_itf_deinit, + usbh_msc_req, + usbh_msc_handle, +}; + +/*! + \brief interface initialization for MSC class + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static usbh_status usbh_msc_itf_init (usbh_host *uhost) +{ + usbh_status status = USBH_OK; + + uint8_t interface = usbh_interface_find(&uhost->dev_prop, MSC_CLASS, USB_MSC_SUBCLASS_SCSI, MSC_PROTOCOL); + + if (0xFFU == interface) { + uhost->usr_cb->dev_not_supported(); + + status = USBH_FAIL; + } else { + static usbh_msc_handler msc_handler; + + memset((void*)&msc_handler, 0U, sizeof(usbh_msc_handler)); + + uhost->active_class->class_data = (void *)&msc_handler; + + usbh_interface_select(&uhost->dev_prop, interface); + + usb_desc_ep *ep_desc = &uhost->dev_prop.cfg_desc_set.itf_desc_set[interface][0].ep_desc[0]; + + if (ep_desc->bEndpointAddress & 0x80U) { + msc_handler.ep_in = ep_desc->bEndpointAddress; + msc_handler.ep_size_in = ep_desc->wMaxPacketSize; + } else { + msc_handler.ep_out = ep_desc->bEndpointAddress; + msc_handler.ep_size_out = ep_desc->wMaxPacketSize; + } + + ep_desc = &uhost->dev_prop.cfg_desc_set.itf_desc_set[interface][0].ep_desc[1]; + + if (ep_desc->bEndpointAddress & 0x80U) { + msc_handler.ep_in = ep_desc->bEndpointAddress; + msc_handler.ep_size_in = ep_desc->wMaxPacketSize; + } else { + msc_handler.ep_out = ep_desc->bEndpointAddress; + msc_handler.ep_size_out = ep_desc->wMaxPacketSize; + } + + msc_handler.state = MSC_INIT; + msc_handler.error = MSC_OK; + msc_handler.req_state = MSC_REQ_IDLE; + msc_handler.pipe_out = usbh_pipe_allocate(uhost->data, msc_handler.ep_out); + msc_handler.pipe_in = usbh_pipe_allocate(uhost->data, msc_handler.ep_in); + + usbh_msc_bbb_init(uhost); + + /* open the new channels */ + usbh_pipe_create (uhost->data, + &uhost->dev_prop, + msc_handler.pipe_out, + USB_EPTYPE_BULK, + msc_handler.ep_size_out); + + usbh_pipe_create (uhost->data, + &uhost->dev_prop, + msc_handler.pipe_in, + USB_EPTYPE_BULK, + msc_handler.ep_size_in); + + usbh_pipe_toggle_set (uhost->data, msc_handler.pipe_out, 0U); + usbh_pipe_toggle_set (uhost->data, msc_handler.pipe_in, 0U); + } + + return status; +} + +/*! + \brief deinitialize interface by freeing host channels allocated to interface + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +void usbh_msc_itf_deinit (usbh_host *uhost) +{ + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + if (msc->pipe_out) { + usb_pipe_halt (uhost->data, msc->pipe_out); + usbh_pipe_free (uhost->data, msc->pipe_out); + + msc->pipe_out = 0U; + } + + if (msc->pipe_in) { + usb_pipe_halt (uhost->data, msc->pipe_in); + usbh_pipe_free (uhost->data, msc->pipe_in); + + msc->pipe_in = 0U; + } +} + +/*! + \brief initialize the MSC state machine + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static usbh_status usbh_msc_req (usbh_host *uhost) +{ + usbh_status status = USBH_BUSY; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (msc->req_state) { + case MSC_REQ_IDLE: + case MSC_REQ_GET_MAX_LUN: + /* issue Get_MaxLun request */ + status = usbh_msc_maxlun_get (uhost, (uint8_t *)&msc->max_lun); + + if (USBH_OK == status) { + msc->max_lun = ((uint8_t)msc->max_lun > MSC_MAX_SUPPORTED_LUN) ? MSC_MAX_SUPPORTED_LUN : (uint8_t)msc->max_lun + 1U; + + for (uint8_t i = 0U; i < msc->max_lun; i++) { + msc->unit[i].prev_ready_state = USBH_FAIL; + msc->unit[i].state_changed = 0U; + } + } else { + if (USBH_NOT_SUPPORTED == status) { + msc->max_lun = 0U; + status = USBH_OK; + } + } + break; + + case MSC_REQ_ERROR: + /* issue clearfeature request */ + if (USBH_OK == usbh_clrfeature(uhost, 0x00U, uhost->control.pipe_out_num)) { + msc->req_state = msc->prev_req_state; + } + break; + + default: + break; + } + + return status; +} + +/*! + \brief MSC state machine handler + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static usbh_status usbh_msc_handle (usbh_host *uhost) +{ + usbh_status status = USBH_BUSY; + uint8_t scsi_status = USBH_BUSY; + uint8_t ready_status = USBH_BUSY; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (msc->state) { + case MSC_INIT: + if (msc->cur_lun < msc->max_lun) { + msc->unit[msc->cur_lun].error = MSC_NOT_READY; + + switch (msc->unit[msc->cur_lun].state) { + case MSC_INIT: + msc->unit[msc->cur_lun].state = MSC_READ_INQUIRY; + msc->timer = uhost->control.timer; + break; + + case MSC_READ_INQUIRY: + scsi_status = usbh_msc_scsi_inquiry (uhost, msc->cur_lun, &msc->unit[msc->cur_lun].inquiry); + + if (USBH_OK == scsi_status) { + msc->unit[msc->cur_lun].state = MSC_TEST_UNIT_READY; + } else if (scsi_status == USBH_FAIL) { + msc->unit[msc->cur_lun].state = MSC_REQUEST_SENSE; + } else { + if (scsi_status == USBH_UNRECOVERED_ERROR) { + msc->unit[msc->cur_lun].state = MSC_IDLE; + msc->unit[msc->cur_lun].error = MSC_ERROR; + } + } + break; + + case MSC_TEST_UNIT_READY: + /* issue SCSI command TestUnitReady */ + ready_status = usbh_msc_test_unitready (uhost, msc->cur_lun); + + if (USBH_OK == ready_status) { + if (USBH_OK != msc->unit[msc->cur_lun].prev_ready_state) { + msc->unit[msc->cur_lun].state_changed = 1U; + } else { + msc->unit[msc->cur_lun].state_changed = 0U; + } + + msc->unit[msc->cur_lun].state = MSC_READ_CAPACITY10; + msc->unit[msc->cur_lun].error = MSC_OK; + msc->unit[msc->cur_lun].prev_ready_state = USBH_OK; + } else if (USBH_FAIL == ready_status) { + if (USBH_FAIL != msc->unit[msc->cur_lun].prev_ready_state) { + msc->unit[msc->cur_lun].state_changed = 1U; + } else { + msc->unit[msc->cur_lun].state_changed = 0U; + } + + msc->unit[msc->cur_lun].state = MSC_REQUEST_SENSE; + msc->unit[msc->cur_lun].error = MSC_NOT_READY; + msc->unit[msc->cur_lun].prev_ready_state = USBH_FAIL; + } else { + if (USBH_UNRECOVERED_ERROR == ready_status) { + msc->unit[msc->cur_lun].state = MSC_IDLE; + msc->unit[msc->cur_lun].error = MSC_ERROR; + } + } + break; + + case MSC_READ_CAPACITY10: + /* issue READ_CAPACITY10 SCSI command */ + scsi_status = usbh_msc_read_capacity10 (uhost, msc->cur_lun, &msc->unit[msc->cur_lun].capacity); + + if (USBH_OK == scsi_status) { + if (1U == msc->unit[msc->cur_lun].state_changed) { + } + msc->unit[msc->cur_lun].state = MSC_IDLE; + msc->unit[msc->cur_lun].error = MSC_OK; + msc->cur_lun ++; + } else if (USBH_FAIL == scsi_status) { + msc->unit[msc->cur_lun].state = MSC_REQUEST_SENSE; + } else { + if (USBH_UNRECOVERED_ERROR == scsi_status) { + msc->unit[msc->cur_lun].state = MSC_IDLE; + msc->unit[msc->cur_lun].error = MSC_ERROR; + } + } + break; + + case MSC_REQUEST_SENSE: + /* issue RequestSense SCSI command for retrieving error code */ + scsi_status = usbh_msc_request_sense (uhost, msc->cur_lun, &msc->unit[msc->cur_lun].sense); + if (USBH_OK == scsi_status) { + if ((msc->unit[msc->cur_lun].sense.SenseKey == UNIT_ATTENTION) || (msc->unit[msc->cur_lun].sense.SenseKey == NOT_READY)) { + if ((uhost->control.timer - msc->timer) < 10000U) { + msc->unit[msc->cur_lun].state = MSC_TEST_UNIT_READY; + break; + } + } + + msc->unit[msc->cur_lun].state = MSC_IDLE; + msc->cur_lun++; + } else if (USBH_FAIL == scsi_status) { + msc->unit[msc->cur_lun].state = MSC_UNRECOVERED_ERROR; + } else { + if (MSC_UNRECOVERED_ERROR == scsi_status) { + msc->unit[msc->cur_lun].state = MSC_IDLE; + msc->unit[msc->cur_lun].error = MSC_ERROR; + } + } + break; + + case MSC_UNRECOVERED_ERROR: + msc->cur_lun++; + break; + + default: + break; + } + } else { + msc->cur_lun = 0U; + msc->state = MSC_IDLE; + } + break; + + case MSC_IDLE: + uhost->usr_cb->dev_user_app(); + status = USBH_OK; + break; + + default: + break; + } + + return status; +} + +/*! + \brief get max lun of the mass storage device + \param[in] uhost: pointer to USB host + \param[in] maxlun: pointer to max lun + \param[out] none + \retval operation status +*/ +static usbh_status usbh_msc_maxlun_get (usbh_host *uhost, uint8_t *maxlun) +{ + usbh_status status = USBH_BUSY; + + if (uhost->control.ctl_state == CTL_IDLE) { + uhost->control.setup.req = (usb_req) { + .bmRequestType = USB_TRX_IN | USB_REQTYPE_CLASS | USB_RECPTYPE_ITF, + .bRequest = BBB_GET_MAX_LUN, + .wValue = 0U, + .wIndex = 0U, + .wLength = 1U + }; + + usbh_ctlstate_config (uhost, maxlun, 1U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief get max lun of the mass storage device + \param[in] uhost: pointer to USB host + \param[in] lun: logic unit number + \param[out] none + \retval operation status +*/ +static usbh_status usbh_msc_rdwr_process(usbh_host *uhost, uint8_t lun) +{ + usbh_status error = USBH_BUSY; + usbh_status scsi_status = USBH_BUSY; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + /* switch msc req state machine */ + switch (msc->unit[lun].state) { + case MSC_READ: + scsi_status = usbh_msc_read10(uhost, lun, NULL, 0U, 0U); + + if (USBH_OK == scsi_status) { + msc->unit[lun].state = MSC_IDLE; + error = USBH_OK; + } else if (USBH_FAIL == scsi_status) { + msc->unit[lun].state = MSC_REQUEST_SENSE; + } else { + if (USBH_UNRECOVERED_ERROR == scsi_status) { + msc->unit[lun].state = MSC_UNRECOVERED_ERROR; + error = USBH_FAIL; + } + } + break; + + case MSC_WRITE: + scsi_status = usbh_msc_write10(uhost, lun, NULL, 0U, 0U); + + if (USBH_OK == scsi_status) { + msc->unit[lun].state = MSC_IDLE; + error = USBH_OK; + } else if (USBH_FAIL == scsi_status) { + msc->unit[lun].state = MSC_REQUEST_SENSE; + } else { + if (USBH_UNRECOVERED_ERROR == scsi_status) { + msc->unit[lun].state = MSC_UNRECOVERED_ERROR; + error = USBH_FAIL; + } + } + break; + + case MSC_REQUEST_SENSE: + scsi_status = usbh_msc_request_sense (uhost, lun, &msc->unit[lun].sense); + + if (USBH_OK == scsi_status) { + msc->unit[lun].state = MSC_IDLE; + msc->unit[lun].error = MSC_ERROR; + + error = USBH_FAIL; + } + + if (USBH_FAIL == scsi_status) { + } else { + if (USBH_UNRECOVERED_ERROR == scsi_status) { + msc->unit[lun].state = MSC_UNRECOVERED_ERROR; + error = USBH_FAIL; + } + } + break; + + default: + break; + } + + return error; +} + +/*! + \brief get lun information + \param[in] uhost: pointer to USB host + \param[in] lun: logic unit number + \param[in] info: pointer to lun information + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_lun_info_get (usbh_host *uhost, uint8_t lun, msc_lun *info) +{ + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + if (HOST_CLASS_HANDLER == uhost->cur_state) { + memcpy(info, &msc->unit[lun], sizeof(msc_lun)); + + return USBH_OK; + } else { + return USBH_FAIL; + } +} + +/*! + \brief handle msc read operation + \param[in] uhost: pointer to USB host + \param[in] lun: logic unit number + \param[in] address: data address + \param[in] pbuf: pointer to data buffer + \param[in] length: buffer length + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_read (usbh_host *uhost, + uint8_t lun, + uint32_t address, + uint8_t *pbuf, + uint32_t length) +{ + uint32_t timeout = 0U; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + usb_core_driver *udev = (usb_core_driver *)uhost->data; + + if ((0U == udev->host.connect_status) || + (HOST_CLASS_HANDLER != uhost->cur_state) || + (MSC_IDLE != msc->unit[lun].state)) { + return USBH_FAIL; + } + + msc->state = MSC_READ; + msc->unit[lun].state = MSC_READ; + msc->rw_lun = lun; + + usbh_msc_read10(uhost, lun, pbuf, address, length); + + timeout = uhost->control.timer; + + while (USBH_BUSY == usbh_msc_rdwr_process(uhost, lun)) { + if (((uhost->control.timer - timeout) > (10000U * length)) || (0U == udev->host.connect_status)){ + msc->state = MSC_IDLE; + return USBH_FAIL; + } + } + + msc->state = MSC_IDLE; + + return USBH_OK; +} + +/*! + \brief handle msc write operation + \param[in] uhost: pointer to USB host + \param[in] lun: logic unit number + \param[in] address: data address + \param[in] pbuf: pointer to data buffer + \param[in] length: buffer length + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_write (usbh_host *uhost, + uint8_t lun, + uint32_t address, + uint8_t *pbuf, + uint32_t length) +{ + uint32_t timeout = 0U; + usb_core_driver *udev = (usb_core_driver *)uhost->data; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + if ((0U == udev->host.connect_status) || + (HOST_CLASS_HANDLER != uhost->cur_state) || + (MSC_IDLE != msc->unit[lun].state)) { + return USBH_FAIL; + } + + msc->state = MSC_WRITE; + msc->unit[lun].state = MSC_WRITE; + msc->rw_lun = lun; + + usbh_msc_write10(uhost, lun, pbuf, address, length); + + timeout = uhost->control.timer; + + while (USBH_BUSY == usbh_msc_rdwr_process(uhost, lun)) { + if (((uhost->control.timer - timeout) > (10000U * length)) || (0U == udev->host.connect_status)) { + msc->state = MSC_IDLE; + return USBH_FAIL; + } + } + + msc->state = MSC_IDLE; + + return USBH_OK; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_fatfs.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_fatfs.c new file mode 100644 index 0000000..bd9c23a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_fatfs.c @@ -0,0 +1,233 @@ +/*! + \file usbh_msc_fatfs.c + \brief USB MSC host FATFS related functions + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usb_conf.h" +#include "diskio.h" +#include "usbh_msc_core.h" + +static volatile DSTATUS state = STA_NOINIT; /* disk status */ + +extern usbh_host usb_host_msc; + +/*! + \brief initialize the disk drive + \param[in] drv: physical drive number (0) + \param[out] none + \retval operation status +*/ +DSTATUS disk_initialize (BYTE drv) +{ + usb_core_driver *udev = (usb_core_driver *)usb_host_msc.data; + + if (udev->host.connect_status) { + state &= ~STA_NOINIT; + } + + return state; +} + +/*! + \brief get disk status + \param[in] drv: physical drive number (0) + \param[out] none + \retval operation status +*/ +DSTATUS disk_status (BYTE drv) +{ + if (drv) { + return STA_NOINIT; /* supports only single drive */ + } + + return state; +} + +/*! + \brief read sectors + \param[in] drv: physical drive number (0) + \param[in] buff: pointer to the data buffer to store read data + \param[in] sector: start sector number (LBA) + \param[in] count: sector count (1..255) + \param[out] none + \retval operation status +*/ +DRESULT disk_read (BYTE drv, BYTE *buff, DWORD sector, UINT count) +{ + BYTE status = USBH_OK; + usb_core_driver *udev = (usb_core_driver *)usb_host_msc.data; + + if (drv || (!count)) { + return RES_PARERR; + } + + if (state & STA_NOINIT) { + return RES_NOTRDY; + } + + if (udev->host.connect_status) { + do { + status = usbh_msc_read (&usb_host_msc, drv, sector, buff, count); + + if (!udev->host.connect_status) { + return RES_ERROR; + } + } while(status == USBH_BUSY); + } + + if (status == USBH_OK) { + return RES_OK; + } + + return RES_ERROR; +} + +#if _READONLY == 0U + +/*! + \brief write sectors + \param[in] drv: physical drive number (0) + \param[in] buff: pointer to the data buffer to store read data + \param[in] sector: start sector number (LBA) + \param[in] count: sector count (1..255) + \param[out] none + \retval operation status +*/ +DRESULT disk_write (BYTE drv, const BYTE *buff, DWORD sector, UINT count) +{ + BYTE status = USBH_OK; + usb_core_driver *udev = (usb_core_driver *)usb_host_msc.data; + + if ((!count) || drv) { + return RES_PARERR; + } + + if (state & STA_NOINIT) { + return RES_NOTRDY; + } + + if (state & STA_PROTECT) { + return RES_WRPRT; + } + + if (udev->host.connect_status) { + do { + status = usbh_msc_write (&usb_host_msc, drv, sector, (BYTE*)buff, count); + + if (!udev->host.connect_status) { + return RES_ERROR; + } + } while(status == USBH_BUSY); + } + + if (status == USBH_OK) { + return RES_OK; + } + + return RES_ERROR; +} + +#endif /* _READONLY == 0 */ + +/*! + \brief I/O control function + \param[in] drv: physical drive number (0) + \param[in] ctrl: control code + \param[in] buff: pointer to the data buffer to store read data + \param[out] none + \retval operation status +*/ +DRESULT disk_ioctl (BYTE drv, BYTE ctrl, void *buff) +{ + DRESULT res = RES_OK; + msc_lun info; + + if (drv) { + return RES_PARERR; + } + + res = RES_ERROR; + + if (state & STA_NOINIT) { + return RES_NOTRDY; + } + + switch (ctrl) { + /* make sure that no pending write process */ + case CTRL_SYNC: + res = RES_OK; + break; + + /* get number of sectors on the disk (dword) */ + case GET_SECTOR_COUNT: + if (USBH_OK == usbh_msc_lun_info_get(&usb_host_msc, drv, &info)) { + *(DWORD*)buff = (DWORD)info.capacity.block_nbr; + res = RES_OK; + } + break; + + /* get r/w sector size (word) */ + case GET_SECTOR_SIZE: + if (USBH_OK == usbh_msc_lun_info_get(&usb_host_msc, drv, &info)) { + *(WORD*)buff = (DWORD)info.capacity.block_size; + res = RES_OK; + } + break; + + /* get erase block size in unit of sector (dword) */ + case GET_BLOCK_SIZE: + *(DWORD *)buff = 512U; + break; + + default: + res = RES_PARERR; + break; + } + + return res; +} + +/*! + \brief get fat time + \param[in] none + \param[out] none + \retval time value +*/ +DWORD get_fattime (void) +{ + return ((DWORD)(2019U - 1980U) << 25U) /* year 2019 */ + | ((DWORD)1U << 21U) /* month 1 */ + | ((DWORD)1U << 16U) /* day 1 */ + | ((DWORD)0U << 11U) /* hour 0 */ + | ((DWORD)0U << 5U) /* min 0 */ + | ((DWORD)0U >> 1U); /* sec 0 */ +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_scsi.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_scsi.c new file mode 100644 index 0000000..de9ac6d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/class/msc/Source/usbh_msc_scsi.c @@ -0,0 +1,400 @@ +/*! + \file usbh_msc_scsi.c + \brief USB MSC SCSI commands implemention + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbh_msc_core.h" +#include "usbh_msc_scsi.h" +#include "usbh_msc_bbb.h" + +#include + +/*! + \brief send 'Inquiry' command to the device + \param[in] uhost: pointer to USB host handler + \param[in] lun: logic unit number + \param[in] inquiry: pointer to the inquiry structure + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_scsi_inquiry (usbh_host *uhost, uint8_t lun, scsi_std_inquiry_data *inquiry) +{ + usbh_status error = USBH_FAIL; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (msc->bbb.cmd_state) { + case BBB_CMD_SEND: + /* prepare the cbw and relevant field*/ + msc->bbb.cbw.field.dCBWDataTransferLength = STANDARD_INQUIRY_DATA_LEN; + msc->bbb.cbw.field.bmCBWFlags = USB_TRX_IN; + msc->bbb.cbw.field.bCBWCBLength = CBW_LENGTH; + + memset(msc->bbb.cbw.field.CBWCB, 0U, CBW_LENGTH); + + msc->bbb.cbw.field.CBWCB[0] = SCSI_INQUIRY; + msc->bbb.cbw.field.CBWCB[1] = (lun << 5U); + msc->bbb.cbw.field.CBWCB[4] = 0x24U; + + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_WAIT; + msc->bbb.pbuf = (uint8_t *)(void *)msc->bbb.data; + error = USBH_BUSY; + break; + + case BBB_CMD_WAIT: + error = usbh_msc_bbb_process(uhost, lun); + + if (USBH_OK == error) { + memset(inquiry, 0U, sizeof(scsi_std_inquiry_data)); + + /* assign inquiry data */ + inquiry->device_type = msc->bbb.pbuf[0] & 0x1FU; + inquiry->peripheral_qualifier = msc->bbb.pbuf[0] >> 5U; + + if (0x80U == ((uint32_t)msc->bbb.pbuf[1] & 0x80U)) { + inquiry->removable_media = 1U; + } else { + inquiry->removable_media = 0U; + } + + memcpy (inquiry->vendor_id, &msc->bbb.pbuf[8], 8U); + memcpy (inquiry->product_id, &msc->bbb.pbuf[16], 16U); + memcpy (inquiry->revision_id, &msc->bbb.pbuf[32], 4U); + } + break; + + default: + break; + } + + return error; +} + +/*! + \brief send 'Test unit ready' command to the device + \param[in] uhost: pointer to USB host handler + \param[in] lun: logic unit number + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_test_unitready (usbh_host *uhost, uint8_t lun) +{ + usbh_status status = USBH_FAIL; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + + switch (msc->bbb.cmd_state) { + case BBB_CMD_SEND: + /* prepare the CBW and relevant field */ + msc->bbb.cbw.field.dCBWDataTransferLength = CBW_LENGTH_TEST_UNIT_READY; + msc->bbb.cbw.field.bmCBWFlags = USB_TRX_OUT; + msc->bbb.cbw.field.bCBWCBLength = CBW_LENGTH; + + memset(msc->bbb.cbw.field.CBWCB, 0U, CBW_CB_LENGTH); + + msc->bbb.cbw.field.CBWCB[0] = SCSI_TEST_UNIT_READY; + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_WAIT; + + status = USBH_BUSY; + break; + + case BBB_CMD_WAIT: + status = usbh_msc_bbb_process(uhost, lun); + break; + + default: + break; + } + + return status; +} + +/*! + \brief send the read capacity command to the device + \param[in] uhost: pointer to USB host handler + \param[in] lun: logic unit number + \param[in] capacity: pointer to SCSI capacity + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_read_capacity10 (usbh_host *uhost, uint8_t lun, scsi_capacity *capacity) +{ + usbh_status status = USBH_FAIL; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (msc->bbb.cmd_state) { + case BBB_CMD_SEND: + /* prepare the CBW and relevant field */ + msc->bbb.cbw.field.dCBWDataTransferLength = READ_CAPACITY10_DATA_LEN; + msc->bbb.cbw.field.bmCBWFlags = USB_TRX_IN; + msc->bbb.cbw.field.bCBWCBLength = CBW_LENGTH; + + memset(msc->bbb.cbw.field.CBWCB, 0U, CBW_CB_LENGTH); + + msc->bbb.cbw.field.CBWCB[0] = SCSI_READ_CAPACITY10; + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_WAIT; + msc->bbb.pbuf = (uint8_t *)(void *)msc->bbb.data; + + status = USBH_BUSY; + break; + + case BBB_CMD_WAIT: + status = usbh_msc_bbb_process(uhost, lun); + + if (USBH_OK == status) { + capacity->block_nbr = msc->bbb.pbuf[3] | \ + ((uint32_t)msc->bbb.pbuf[2] << 8U) | \ + ((uint32_t)msc->bbb.pbuf[1] << 16U) | \ + ((uint32_t)msc->bbb.pbuf[0] << 24U); + + capacity->block_size = (uint16_t)(msc->bbb.pbuf[7] | ((uint32_t)msc->bbb.pbuf[6] << 8U)); + } + break; + + default: + break; + } + + return status; +} + +/*! + \brief send the mode sense6 command to the device + \param[in] uhost: pointer to USB host handler + \param[in] lun: logic unit number + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_mode_sense6 (usbh_host *uhost, uint8_t lun) +{ + usbh_status status = USBH_FAIL; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + + switch (msc->bbb.cmd_state) { + case BBB_CMD_SEND: + /* prepare the CBW and relevant field */ + msc->bbb.cbw.field.dCBWDataTransferLength = XFER_LEN_MODE_SENSE6; + msc->bbb.cbw.field.bmCBWFlags = USB_TRX_IN; + msc->bbb.cbw.field.bCBWCBLength = CBW_LENGTH; + + memset(msc->bbb.cbw.field.CBWCB, 0U, CBW_CB_LENGTH); + + msc->bbb.cbw.field.CBWCB[0] = SCSI_MODE_SENSE6; + msc->bbb.cbw.field.CBWCB[2] = MODE_SENSE_PAGE_CONTROL_FIELD | MODE_SENSE_PAGE_CODE; + msc->bbb.cbw.field.CBWCB[4] = XFER_LEN_MODE_SENSE6; + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_WAIT; + msc->bbb.pbuf = (uint8_t *)(void *)msc->bbb.data; + + status = USBH_BUSY; + break; + + case BBB_CMD_WAIT: + status = usbh_msc_bbb_process(uhost, lun); + + if (USBH_OK == status) { + if (msc->bbb.data[2] & MASK_MODE_SENSE_WRITE_PROTECT) { + + } else { + + } + } + break; + + default: + break; + } + + + return status; +} + +/*! + \brief send the Request Sense command to the device + \param[in] uhost: pointer to USB host handler + \param[in] lun: logic unit number + \param[in] sense_data: pointer to sense data + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_request_sense (usbh_host *uhost, uint8_t lun, msc_scsi_sense *sense_data) +{ + usbh_status status = USBH_FAIL; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (msc->bbb.cmd_state) { + case BBB_CMD_SEND: + /* prepare the cbw and relevant field */ + msc->bbb.cbw.field.dCBWDataTransferLength = ALLOCATION_LENGTH_REQUEST_SENSE; + msc->bbb.cbw.field.bmCBWFlags = USB_TRX_IN; + msc->bbb.cbw.field.bCBWCBLength = CBW_LENGTH; + + memset(msc->bbb.cbw.field.CBWCB, 0U, CBW_CB_LENGTH); + + msc->bbb.cbw.field.CBWCB[0] = SCSI_REQUEST_SENSE; + msc->bbb.cbw.field.CBWCB[1] = (lun << 5U); + msc->bbb.cbw.field.CBWCB[4] = ALLOCATION_LENGTH_REQUEST_SENSE; + + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_WAIT; + msc->bbb.pbuf = (uint8_t *)(void *)msc->bbb.data; + + status = USBH_BUSY; + break; + + case BBB_CMD_WAIT: + status = usbh_msc_bbb_process(uhost, lun); + + if (status == USBH_OK) { + /* get sense data */ + sense_data->SenseKey = msc->bbb.pbuf[2] & 0x0FU; + sense_data->ASC = msc->bbb.pbuf[12]; + sense_data->ASCQ = msc->bbb.pbuf[13]; + } + break; + + default: + break; + } + + return status; +} + +/*! + \brief send the write10 command to the device + \param[in] uhost: pointer to USB host handler + \param[in] lun: logic unit number + \param[in] data_buf: data buffer contains the data to write + \param[in] addr: address to which the data will be written + \param[in] sector_num: number of sector to be written + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_write10 (usbh_host *uhost, uint8_t lun, uint8_t *data_buf, uint32_t addr, uint32_t sector_num) +{ + usbh_status status = USBH_FAIL; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (msc->bbb.cmd_state) { + case BBB_CMD_SEND: + msc->bbb.cbw.field.dCBWDataTransferLength = sector_num * msc->unit[lun].capacity.block_size; + msc->bbb.cbw.field.bmCBWFlags = USB_TRX_OUT; + msc->bbb.cbw.field.bCBWCBLength = CBW_LENGTH; + + memset(msc->bbb.cbw.field.CBWCB, 0U, CBW_CB_LENGTH); + + msc->bbb.cbw.field.CBWCB[0] = SCSI_WRITE10; + + /* logical block address */ + msc->bbb.cbw.field.CBWCB[2] = (((uint8_t*)&addr)[3]); + msc->bbb.cbw.field.CBWCB[3] = (((uint8_t*)&addr)[2]); + msc->bbb.cbw.field.CBWCB[4] = (((uint8_t*)&addr)[1]); + msc->bbb.cbw.field.CBWCB[5] = (((uint8_t*)&addr)[0]); + + /* transfer length */ + msc->bbb.cbw.field.CBWCB[7] = (((uint8_t *)§or_num)[1]); + msc->bbb.cbw.field.CBWCB[8] = (((uint8_t *)§or_num)[0]); + + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_WAIT; + msc->bbb.pbuf = data_buf; + + status = USBH_BUSY; + break; + + case BBB_CMD_WAIT: + status = usbh_msc_bbb_process(uhost, lun); + break; + + default: + break; + } + + return status; +} + +/*! + \brief send the read10 command to the device + \param[in] uhost: pointer to USB host handler + \param[in] lun: logic unit number + \param[in] data_buf: data buffer contains the data to write + \param[in] addr: address to which the data will be read + \param[in] sector_num: number of sector to be read + \param[out] none + \retval operation status +*/ +usbh_status usbh_msc_read10 (usbh_host *uhost, uint8_t lun, uint8_t *data_buf, uint32_t addr, uint32_t sector_num) +{ + usbh_status status = USBH_FAIL; + usbh_msc_handler *msc = (usbh_msc_handler *)uhost->active_class->class_data; + + switch (msc->bbb.cmd_state) { + case BBB_CMD_SEND: + /* prepare the CBW and relevant field */ + msc->bbb.cbw.field.dCBWDataTransferLength = sector_num * msc->unit[lun].capacity.block_size; + msc->bbb.cbw.field.bmCBWFlags = USB_TRX_IN; + msc->bbb.cbw.field.bCBWCBLength = CBW_LENGTH; + + memset(msc->bbb.cbw.field.CBWCB, 0U, CBW_CB_LENGTH); + + msc->bbb.cbw.field.CBWCB[0] = SCSI_READ10; + + /* logical block address */ + msc->bbb.cbw.field.CBWCB[2] = (((uint8_t*)&addr)[3]); + msc->bbb.cbw.field.CBWCB[3] = (((uint8_t*)&addr)[2]); + msc->bbb.cbw.field.CBWCB[4] = (((uint8_t*)&addr)[1]); + msc->bbb.cbw.field.CBWCB[5] = (((uint8_t*)&addr)[0]); + + /* transfer length */ + msc->bbb.cbw.field.CBWCB[7] = (((uint8_t *)§or_num)[1]); + msc->bbb.cbw.field.CBWCB[8] = (((uint8_t *)§or_num)[0]); + + msc->bbb.state = BBB_SEND_CBW; + msc->bbb.cmd_state = BBB_CMD_WAIT; + msc->bbb.pbuf = data_buf; + + status = USBH_BUSY; + break; + + case BBB_CMD_WAIT: + status = usbh_msc_bbb_process(uhost, lun); + break; + + default: + break; + } + + return status; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_core.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_core.h new file mode 100644 index 0000000..e14ac1c --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_core.h @@ -0,0 +1,277 @@ +/*! + \file usbh_core.h + \brief USB host core state machine header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_CORE_H +#define __USBH_CORE_H + +#include "usbh_conf.h" +#include "drv_usb_host.h" + +#define MSC_CLASS 0x08U +#define HID_CLASS 0x03U +#define MSC_PROTOCOL 0x50U +#define CBI_PROTOCOL 0x01U + +#define USBH_MAX_ERROR_COUNT 3U + +#define USBH_DEV_ADDR_DEFAULT 0U +#define USBH_DEV_ADDR 1U + +typedef enum +{ + USBH_OK = 0U, + USBH_BUSY, + USBH_FAIL, + USBH_NOT_SUPPORTED, + USBH_UNRECOVERED_ERROR, + USBH_SPEED_UNKNOWN_ERROR, + USBH_APPLY_DEINIT +} usbh_status; + +/* USB host global operation state */ +typedef enum +{ + HOST_DEFAULT = 0U, + HOST_DETECT_DEV_SPEED, + HOST_DEV_CONNECT, + HOST_DEV_DETACHED, + HOST_DEV_ENUM, + HOST_PWR_FEATURE_SET, + HOST_CLASS_CHECK, + HOST_CLASS_ENUM, + HOST_CLASS_HANDLER, + HOST_USER_INPUT, + HOST_SUSPEND, + HOST_WAKEUP, + HOST_ERROR +} usb_host_state; + +/* USB host enumeration state */ +typedef enum +{ + ENUM_DEFAULT = 0U, + ENUM_GET_DEV_DESC, + ENUM_SET_ADDR, + ENUM_GET_CFG_DESC, + ENUM_GET_CFG_DESC_SET, + ENUM_GET_STR_DESC, +#ifdef USB_MTP + ENUM_GET_MTP_STR, +#endif + ENUM_SET_CONFIGURATION, + ENUM_DEV_CONFIGURED +} usbh_enum_state; + +/* USB host control transfer state */ +typedef enum +{ + CTL_IDLE = 0U, + CTL_SETUP, + CTL_SETUP_WAIT, + CTL_DATA_IN, + CTL_DATA_IN_WAIT, + CTL_DATA_OUT, + CTL_DATA_OUT_WAIT, + CTL_STATUS_IN, + CTL_STATUS_IN_WAIT, + CTL_STATUS_OUT, + CTL_STATUS_OUT_WAIT, + CTL_ERROR, + CTL_FINISH +} usbh_ctl_state; + +/* user action state */ +typedef enum +{ + USR_IN_NO_RESP = 0U, + USR_IN_RESP_OK = 1U, +} usbh_user_status; + +/* USB host wakeup mode */ +typedef enum +{ + NORMAL_WORK = 0U, + GENERAL_WAKEUP = 1U, + REMOTE_WAKEUP = 2, +} usbh_wakeup_mode; + +/* control transfer information */ +typedef struct _usbh_control +{ + uint8_t pipe_in_num; + uint8_t pipe_out_num; + uint8_t max_len; + uint8_t error_count; + + uint8_t *buf; + uint16_t ctl_len; + __IO uint32_t timer; + + usb_setup setup; + usbh_ctl_state ctl_state; +} usbh_control; + +/* USB interface descriptor set */ +typedef struct _usb_desc_itf_set +{ + usb_desc_itf itf_desc; + usb_desc_ep ep_desc[USBH_MAX_EP_NUM]; +} usb_desc_itf_set; + +/* USB configure descriptor set */ +typedef struct _usb_desc_cfg_set +{ + usb_desc_config cfg_desc; + usb_desc_itf_set itf_desc_set[USBH_MAX_INTERFACES_NUM][USBH_MAX_ALT_SETTING]; +} usb_desc_cfg_set; + +/* USB device property */ +typedef struct +{ + uint8_t data[USBH_DATA_BUF_MAX_LEN]; /* if DMA is used, the data array must be located in the first position */ + uint8_t cur_itf; + uint8_t addr; + + uint32_t speed; + + usb_desc_dev dev_desc; + usb_desc_cfg_set cfg_desc_set; + +#if (USBH_CFG_DESC_KEEP == 1U) + uint8_t cfgdesc_rawdata[USBH_CFGSET_MAX_LEN]; +#endif /* (USBH_CFG_DESC_KEEP == 1U) */ +} usb_dev_prop; + +struct _usbh_host; + +/* device class callbacks */ +typedef struct +{ + uint8_t class_code; /*!< USB class type */ + + usbh_status (*class_init) (struct _usbh_host *phost); + void (*class_deinit) (struct _usbh_host *phost); + usbh_status (*class_requests) (struct _usbh_host *phost); + usbh_status (*class_machine) (struct _usbh_host *phost); + usbh_status (*class_sof) (struct _usbh_host *uhost); + + void *class_data; +} usbh_class; + +/* user callbacks */ +typedef struct +{ + void (*dev_init) (void); + void (*dev_deinit) (void); + void (*dev_attach) (void); + void (*dev_reset) (void); + void (*dev_detach) (void); + void (*dev_over_currented) (void); + void (*dev_speed_detected) (uint32_t dev_speed); + void (*dev_devdesc_assigned) (void *dev_desc); + void (*dev_address_set) (void); + + void (*dev_cfgdesc_assigned) (usb_desc_config *cfg_desc, + usb_desc_itf *itf_desc, + usb_desc_ep *ep_desc); + + void (*dev_mfc_str) (void *mfc_str); + void (*dev_prod_str) (void *prod_str); + void (*dev_seral_str) (void *serial_str); + void (*dev_enumerated) (void); + usbh_user_status (*dev_user_input) (void); + int (*dev_user_app) (void); + void (*dev_not_supported) (void); + void (*dev_error) (void); +} usbh_user_cb; + +/* host information */ +typedef struct _usbh_host +{ + usb_host_state cur_state; /*!< host state machine value */ + usb_host_state backup_state; /*!< backup of previous state machine value */ + usbh_enum_state enum_state; /*!< enumeration state machine */ + usbh_control control; /*!< USB host control state machine */ + usb_dev_prop dev_prop; /*!< USB device property */ + + usbh_class *uclass[USBH_MAX_SUPPORTED_CLASS]; /*!< USB host supported class */ + usbh_class *active_class; /*!< USB active class */ + usbh_user_cb *usr_cb; /*!< USB user callback */ + + uint8_t class_num; /*!< USB class number */ + + void *data; /*!< used for... */ + + uint8_t suspend_flag; /*!< host suspend flag */ + uint8_t dev_supp_remote_wkup; /*!< record device remote wakeup function */ + usbh_wakeup_mode wakeup_mode; /*!< record wakeup mode */ +} usbh_host; + +/*! + \brief get USB URB state + \param[in] udev: pointer to USB core instance + \param[in] pp_num: pipe number + \param[out] none + \retval none +*/ +static inline usb_urb_state usbh_urbstate_get (usb_core_driver *udev, uint8_t pp_num) +{ + return udev->host.pipe[pp_num].urb_state; +} + +/*! + \brief get USB transfer data count + \param[in] udev: pointer to USB core instance + \param[in] pp_num: pipe number + \param[out] none + \retval none +*/ +static inline uint32_t usbh_xfercount_get (usb_core_driver *udev, uint8_t pp_num) +{ + return udev->host.backup_xfercount[pp_num]; +} + +/* function declarations */ +/* USB host stack initializations */ +void usbh_init (usbh_host *uhost, usb_core_driver *udev, usb_core_enum usb_core, usbh_user_cb *user_cb); +/* USB host register device class */ +usbh_status usbh_class_register (usbh_host *uhost, usbh_class *puclass); +/* de-initialize USB host */ +usbh_status usbh_deinit (usbh_host *uhost); +/* USB host core main state machine process */ +void usbh_core_task (usbh_host *uhost); +/* handle the error on USB host side */ +void usbh_error_handler (usbh_host *uhost, usbh_status err_type); + +#endif /* __USBH_CORE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_enum.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_enum.h new file mode 100644 index 0000000..91b7f63 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_enum.h @@ -0,0 +1,70 @@ +/*! + \file usbh_enum.h + \brief USB host mode USB enumeration header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_ENUM_H +#define __USBH_ENUM_H + +#include "usbh_core.h" + +/* function declarations */ +/* configure USB control status parameters */ +void usbh_ctlstate_config (usbh_host *uhost, uint8_t *buf, uint16_t len); +/* get device descriptor from the USB device */ +usbh_status usbh_devdesc_get (usbh_host *uhost, uint8_t len); +/* get configuration descriptor from the USB device */ +usbh_status usbh_cfgdesc_get (usbh_host *uhost, uint16_t len); +/* get string descriptor from the USB device */ +usbh_status usbh_strdesc_get (usbh_host *uhost,uint8_t str_index, uint8_t *buf, uint16_t len); +/* set the address to the connected device */ +usbh_status usbh_setaddress (usbh_host *uhost, uint8_t dev_addr); +/* set the configuration value to the connected device */ +usbh_status usbh_setcfg (usbh_host *uhost, uint16_t config); +/* set the interface value to the connected device */ +usbh_status usbh_setinterface (usbh_host *uhost, uint8_t itf_num, uint8_t alter_setting); +/* set or enable a specific device feature */ +usbh_status usbh_setdevfeature (usbh_host *uhost, uint8_t feature_selector, uint16_t windex); +/* clear or disable a specific device feature */ +usbh_status usbh_clrdevfeature (usbh_host *uhost, uint8_t feature_selector, uint16_t windex); +/* clear or disable a specific feature */ +usbh_status usbh_clrfeature (usbh_host *uhost, uint8_t ep_addr, uint8_t pp_num); +/* get the next descriptor header */ +usb_desc_header *usbh_nextdesc_get (uint8_t *pbuf, uint16_t *ptr); +/* select an interface */ +usbh_status usbh_interface_select (usb_dev_prop *udev, uint8_t interface); +/* find the interface index for a specific class */ +uint8_t usbh_interface_find (usb_dev_prop *udev, uint8_t main_class, uint8_t sub_class, uint8_t protocol); +/* find the interface index for a specific class interface and alternate setting number */ +uint8_t usbh_interfaceindex_find (usb_dev_prop *udev, uint8_t interface_number, uint8_t alt_settings); + +#endif /* __USBH_ENUM_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_pipe.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_pipe.h new file mode 100644 index 0000000..3bd5e60 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_pipe.h @@ -0,0 +1,102 @@ +/*! + \file usbh_pipe.h + \brief USB host mode pipe header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_PIPE_H +#define __USBH_PIPE_H + +#include "usbh_core.h" + +/* host pipe maximum */ +#define HP_MAX 8U + +/* host pipe status */ +#define HP_OK 0x0000U +#define HP_USED 0x8000U +#define HP_ERROR 0xFFFFU +#define HP_USED_MASK 0x7FFFU + +/*! + \brief set toggle for a pipe + \param[in] udev: pointer to USB core instance + \param[in] pp_num: pipe number + \param[in] toggle: toggle (0/1) + \param[out] none + \retval operation status +*/ +__STATIC_INLINE void usbh_pipe_toggle_set (usb_core_driver *udev, uint8_t pp_num, uint8_t toggle) +{ + if (udev->host.pipe[pp_num].ep.dir) { + udev->host.pipe[pp_num].data_toggle_in = toggle; + } else { + udev->host.pipe[pp_num].data_toggle_out = toggle; + } +} + +/*! + \brief get toggle flag of pipe + \param[in] udev: pointer to USB core instance + \param[in] pp_num: pipe number + \param[out] none + \retval operation status +*/ +__STATIC_INLINE uint8_t usbh_pipe_toggle_get (usb_core_driver *udev, uint8_t pp_num) +{ + if (udev->host.pipe[pp_num].ep.dir) { + return udev->host.pipe[pp_num].data_toggle_in; + } else { + return udev->host.pipe[pp_num].data_toggle_out; + } +} + +/* function declarations */ +/* create a pipe */ +uint8_t usbh_pipe_create (usb_core_driver *udev, + usb_dev_prop *dev, + uint8_t pp_num, + uint8_t ep_type, + uint16_t ep_mpl); +/* modify a pipe */ +uint8_t usbh_pipe_update (usb_core_driver *udev, + uint8_t pp_num, + uint8_t dev_addr, + uint32_t dev_speed, + uint16_t ep_mpl); +/* allocate a new pipe */ +uint8_t usbh_pipe_allocate (usb_core_driver *udev, uint8_t ep_addr); +/* free a pipe */ +uint8_t usbh_pipe_free (usb_core_driver *udev, uint8_t pp_num); +/* delete all USB host pipe */ +uint8_t usbh_pipe_delete (usb_core_driver *udev); + +#endif /* __USBH_PIPE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_transc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_transc.h new file mode 100644 index 0000000..d4dfaa4 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Include/usbh_transc.h @@ -0,0 +1,50 @@ +/*! + \file usbh_transc.h + \brief USB host mode transactions header file + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USBH_TRANSC_H +#define __USBH_TRANSC_H + +#include "usbh_core.h" + +/* function declarations */ +/* send the setup packet to the USB device */ +usbh_status usbh_ctlsetup_send (usb_core_driver *udev, uint8_t *buf, uint8_t pp_num); +/* send a data packet to the USB device */ +usbh_status usbh_data_send (usb_core_driver *udev, uint8_t *buf, uint8_t pp_num, uint16_t len); +/* receive a data packet from the USB device */ +usbh_status usbh_data_recev (usb_core_driver *udev, uint8_t *buf, uint8_t pp_num, uint16_t len); +/* USB control transfer handler */ +usbh_status usbh_ctl_handler (usbh_host *uhost); + +#endif /* __USBH_TRANSC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_core.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_core.c new file mode 100644 index 0000000..0a4b2b2 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_core.c @@ -0,0 +1,657 @@ +/*! + \file usbh_core.c + \brief USB host core state machine driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "drv_usb_hw.h" +#include "usbh_pipe.h" +#include "usbh_enum.h" +#include "usbh_core.h" +#include "drv_usbh_int.h" +#include + +/* local function prototypes ('static') */ +static uint8_t usb_ev_sof (usbh_host *uhost); +static uint8_t usb_ev_connect (usbh_host *uhost); +static uint8_t usb_ev_disconnect (usbh_host *uhost); +static usbh_status usbh_enum_task (usbh_host *uhost); +#if USBFS_LOW_POWER || USBHS_LOW_POWER +static void usb_hwp_suspend (usb_core_driver *udev); +static void usb_hwp_resume (usb_core_driver *udev); +#endif /* USBFS_LOW_POWER || USBHS_LOW_POWER */ + +usbh_ev_cb usbh_int_op = +{ + usb_ev_connect, + usb_ev_disconnect, + usb_ev_sof, +}; + +usbh_ev_cb *usbh_int_fop = &usbh_int_op; + +/*! + \brief USB host stack initializations + \param[in] uhost: pointer to USB host + \param[in] udev: pointer to USB device instance + \param[in] usb_core: USB core type + \param[in] user_cb: pointer to user callback + \param[out] none + \retval none +*/ +void usbh_init (usbh_host *uhost, usb_core_driver *udev, usb_core_enum usb_core, usbh_user_cb *user_cb) +{ + /* link driver to the stack */ + udev->host.data = (void *)uhost; + uhost->data = (void *)udev; + + /* host deinitialization */ + usbh_deinit(uhost); + + uhost->usr_cb = user_cb; + + udev->host.connect_status = 0U; + + for (uint8_t i = 0U; i < USBFS_MAX_TX_FIFOS; i++) { + udev->host.pipe[i].err_count = 0U; + udev->host.pipe[i].pp_status = PIPE_IDLE; + udev->host.backup_xfercount[i] = 0U; + } + + udev->host.pipe[0].ep.mps = 8U; + + usb_basic_init (&udev->bp, &udev->regs, usb_core); + +#ifndef DUAL_ROLE_MODE_ENABLED + usb_globalint_disable(&udev->regs); + + usb_core_init (udev->bp, &udev->regs); + +#ifndef USE_OTG_MODE + usb_curmode_set (&udev->regs, HOST_MODE); +#endif /* USE_OTG_MODE */ + + usb_host_init (udev); + + usb_globalint_enable(&udev->regs); +#endif /* DUAL_ROLE_MODE_ENABLED */ + + /* upon initialize call usr call back */ + uhost->usr_cb->dev_init(); +} + +/*! + \brief USB host register device class + \param[in] uhost: pointer to USB host instance + \param[in] puclass: pointer to USB device class + \param[out] none + \retval operation status +*/ +usbh_status usbh_class_register (usbh_host *uhost, usbh_class *puclass) +{ + usbh_status status = USBH_OK; + + if (NULL != puclass) { + if (uhost->class_num < USBH_MAX_SUPPORTED_CLASS) { + uhost->uclass[uhost->class_num++] = puclass; + } else { + status = USBH_FAIL; + } + } else { + status = USBH_FAIL; + } + + return status; +} + +/*! + \brief deinitialize USB host + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +usbh_status usbh_deinit(usbh_host *uhost) +{ + usb_core_driver *udev = (usb_core_driver *)uhost->data; + + /* software initialize */ + uhost->cur_state = HOST_DEFAULT; + uhost->backup_state = HOST_DEFAULT; + uhost->enum_state = ENUM_DEFAULT; + + uhost->control.ctl_state = CTL_IDLE; + uhost->control.max_len = USB_FS_EP0_MAX_LEN; + + uhost->dev_prop.addr = USBH_DEV_ADDR_DEFAULT; + uhost->dev_prop.speed = PORT_SPEED_FULL; + uhost->dev_prop.cur_itf = 0xFFU; + + usbh_pipe_free(udev, uhost->control.pipe_in_num); + usbh_pipe_free(udev, uhost->control.pipe_out_num); + + return USBH_OK; +} + +/*! + \brief USB host core main state machine process + \param[in] uhost: pointer to USB host + \param[out] none + \retval none +*/ +void usbh_core_task (usbh_host *uhost) +{ + volatile usbh_status status = USBH_FAIL; + usb_core_driver *udev = (usb_core_driver *)uhost->data; + + /* check for host port events */ + if (((0U == udev->host.connect_status) || (0U == udev->host.port_enabled)) && (HOST_DEFAULT != uhost->cur_state)) { + if (uhost->cur_state != HOST_DEV_DETACHED) { + uhost->cur_state = HOST_DEV_DETACHED; + } + } + + switch (uhost->cur_state) { + case HOST_DEFAULT: + if (udev->host.connect_status) { + uhost->cur_state = HOST_DETECT_DEV_SPEED; + + usb_mdelay (100U); + + usb_port_reset (udev); + + uhost->usr_cb->dev_reset(); + } + break; + + case HOST_DETECT_DEV_SPEED: + if (udev->host.port_enabled) { + uhost->cur_state = HOST_DEV_CONNECT; + + uhost->dev_prop.speed = usb_curspeed_get (udev); + + uhost->usr_cb->dev_speed_detected(uhost->dev_prop.speed); + + usb_mdelay (50U); + } + break; + + case HOST_DEV_CONNECT: + uhost->usr_cb->dev_attach(); + uhost->control.pipe_out_num = usbh_pipe_allocate(udev, 0x00U); + uhost->control.pipe_in_num = usbh_pipe_allocate(udev, 0x80U); + + /* open IN control pipe */ + usbh_pipe_create (udev, + &uhost->dev_prop, + uhost->control.pipe_in_num, + USB_EPTYPE_CTRL, + (uint16_t)uhost->control.max_len); + + /* open OUT control pipe */ + usbh_pipe_create (udev, + &uhost->dev_prop, + uhost->control.pipe_out_num, + USB_EPTYPE_CTRL, + (uint16_t)uhost->control.max_len); + + uhost->cur_state = HOST_DEV_ENUM; + break; + + case HOST_DEV_ENUM: + /* check for enumeration status */ + if (USBH_OK == usbh_enum_task (uhost)) { + /* the function shall return USBH_OK when full enumeration is complete */ + + /* user callback for end of device basic enumeration */ + uhost->usr_cb->dev_enumerated(); + +#if USBFS_LOW_POWER || USBHS_LOW_POWER + uhost->cur_state = HOST_SUSPEND; + + /* judge device remote wakeup function */ + if ((uhost->dev_prop.cfg_desc_set.cfg_desc.bmAttributes) & (1U << 5)) { + uhost->dev_supp_remote_wkup = 1; + }else{ + uhost->dev_supp_remote_wkup = 0; + } +#else + uhost->cur_state = HOST_PWR_FEATURE_SET; +#endif /* USBFS_LOW_POWER || USBHS_LOW_POWER */ + } + break; + + case HOST_PWR_FEATURE_SET: + if ((uhost->dev_prop.cfg_desc_set.cfg_desc.bmAttributes) & (1U << 5)) { + if (usbh_setdevfeature(uhost, FEATURE_SELECTOR_REMOTEWAKEUP, 0U) == USBH_OK) { + uhost->cur_state = HOST_CLASS_CHECK; + } + } else { + uhost->cur_state = HOST_CLASS_CHECK; + } + break; + + case HOST_CLASS_CHECK: + if (0U == uhost->class_num) { + uhost->cur_state = HOST_ERROR; + } else { + uhost->active_class = NULL; + + uint8_t itf_class = uhost->dev_prop.cfg_desc_set.itf_desc_set[0][0].itf_desc.bInterfaceClass; + + for (uint8_t index = 0U; index < uhost->class_num; index++) { + if ((uhost->uclass[index]->class_code == itf_class) || (0xFFU == itf_class)) { + uhost->active_class = uhost->uclass[index]; + } + } + + if (uhost->active_class != NULL) { + uhost->cur_state = HOST_USER_INPUT; + } else { + uhost->cur_state = HOST_ERROR; + } + } + break; + + case HOST_USER_INPUT: + /* the function should return user response true to move to class state */ + if (USR_IN_RESP_OK == uhost->usr_cb->dev_user_input()) { + if ((USBH_OK == uhost->active_class->class_init(uhost))) { + uhost->cur_state = HOST_CLASS_ENUM; + } + } + break; + +#if USBFS_LOW_POWER || USBHS_LOW_POWER + case HOST_SUSPEND: + if(uhost->dev_supp_remote_wkup){ + /* send set feature command*/ + if (USBH_OK == usbh_setdevfeature (uhost, FEATURE_SELECTOR_REMOTEWAKEUP, 0U)) { + + usb_hwp_suspend (udev); + + usb_mdelay (20U); + uhost->suspend_flag = 1; + uhost->usr_cb->dev_user_input(); + + /* MCU enter deep-sleep*/ + pmu_to_deepsleepmode (PMU_LDO_LOWPOWER, PMU_LOWDRIVER_DISABLE, WFI_CMD); + uhost->cur_state = HOST_WAKEUP; + } + } else { + /* host suspend */ + usb_hwp_suspend (udev); + + usb_mdelay(20U); + uhost->suspend_flag = 1U; + uhost->usr_cb->dev_user_input(); + + /* MCU enter deep-sleep */ + pmu_to_deepsleepmode (PMU_LDO_LOWPOWER, PMU_LOWDRIVER_DISABLE, WFI_CMD); + uhost->cur_state = HOST_WAKEUP; + } + break; + + case HOST_WAKEUP: + /* judge suspend status */ + if (0U == uhost->suspend_flag) { + usb_hwp_resume(udev); + usb_mdelay(500U); + + if (uhost->dev_supp_remote_wkup) { + if (USBH_OK == usbh_clrdevfeature (uhost, FEATURE_SELECTOR_DEV, 0U)) { + /* user callback for initialization */ + uhost->usr_cb->dev_init(); + uhost->cur_state = HOST_CLASS_CHECK; + } + } else { + uhost->cur_state = HOST_CLASS_CHECK; + } + } + break; +#endif /* USBFS_LOW_POWER || USBHS_LOW_POWER */ + + case HOST_CLASS_ENUM: + /* process class standard control requests state machine */ + status = uhost->active_class->class_requests(uhost); + + if (USBH_OK == status) { + uhost->cur_state = HOST_CLASS_HANDLER; + } else { + usbh_error_handler (uhost, status); + } + break; + + case HOST_CLASS_HANDLER: + /* process class state machine */ + status = uhost->active_class->class_machine(uhost); + + usbh_error_handler (uhost, status); + break; + + case HOST_ERROR: + /* deinitialize host for new enumeration */ + usbh_deinit (uhost); + uhost->usr_cb->dev_deinit(); + uhost->active_class->class_deinit(uhost); + break; + + case HOST_DEV_DETACHED: + /* manage user disconnect operations*/ + uhost->usr_cb->dev_detach(); + + /* re-initialize host for new enumeration */ + usbh_deinit (uhost); + uhost->usr_cb->dev_deinit(); + uhost->active_class->class_deinit(uhost); + usbh_pipe_delete(udev); + uhost->cur_state = HOST_DEFAULT; + break; + + default: + break; + } +} + +/*! + \brief handle the error on USB host side + \param[in] uhost: pointer to USB host + \param[in] err_type: type of error or busy/OK state + \param[out] none + \retval none +*/ +void usbh_error_handler (usbh_host *uhost, usbh_status err_type) +{ + /* error unrecovered or not supported device speed */ + if ((USBH_SPEED_UNKNOWN_ERROR == err_type) || (USBH_UNRECOVERED_ERROR == err_type)) { + uhost->usr_cb->dev_error(); + + uhost->cur_state = HOST_ERROR; + } else if (USBH_APPLY_DEINIT == err_type) { + uhost->cur_state = HOST_ERROR; + + /* user callback for initialization */ + uhost->usr_cb->dev_init(); + } else { + /* no operation */ + } +} + +/*! + \brief USB SOF event function from the interrupt + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static uint8_t usb_ev_sof (usbh_host *uhost) +{ + /* update timer variable */ + uhost->control.timer++; + + /* this callback could be used to implement a scheduler process */ + if (uhost->active_class != NULL) { + if (uhost->active_class->class_sof != NULL) { + uhost->active_class->class_sof(uhost); + } + } + + return 0U; +} + +/*! + \brief USB connect event function from the interrupt + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static uint8_t usb_ev_connect (usbh_host *uhost) +{ + usb_core_driver *udev = (usb_core_driver *)uhost->data; + udev->host.connect_status = 1U; + + return 0U; +} + +/*! + \brief USB disconnect event function from the interrupt + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +static uint8_t usb_ev_disconnect (usbh_host *uhost) +{ + usb_core_driver *udev = (usb_core_driver *)uhost->data; + udev->host.connect_status = 0U; + + return 0U; +} + +/*! + \brief handle the USB enumeration task + \param[in] uhost: pointer to host + \param[out] none + \retval none +*/ +static usbh_status usbh_enum_task (usbh_host *uhost) +{ + uint8_t str_buf[512]; + usbh_status status = USBH_BUSY; + usb_core_driver *udev = (usb_core_driver *)uhost->data; + + static uint8_t index_mfc_str = 0U, index_prod_str = 0U, index_serial_str = 0U; + + switch (uhost->enum_state) { + case ENUM_DEFAULT: + /* get device descriptor for only 1st 8 bytes : to get ep0 max packet size */ + if (USBH_OK == usbh_devdesc_get (uhost, 8U)) { + uhost->control.max_len = uhost->dev_prop.dev_desc.bMaxPacketSize0; + + /* modify control channels configuration for maximum packet size */ + usbh_pipe_update (udev, + uhost->control.pipe_out_num, + 0U, 0U, + (uint16_t)uhost->control.max_len); + + usbh_pipe_update (udev, + uhost->control.pipe_in_num, + 0U, 0U, + (uint16_t)uhost->control.max_len); + + uhost->enum_state = ENUM_GET_DEV_DESC; + } + break; + + case ENUM_GET_DEV_DESC: + /* get full device descriptor */ + if (USBH_OK == usbh_devdesc_get (uhost, USB_DEV_DESC_LEN)) { + uhost->usr_cb->dev_devdesc_assigned(&uhost->dev_prop.dev_desc); + + index_mfc_str = uhost->dev_prop.dev_desc.iManufacturer; + index_prod_str = uhost->dev_prop.dev_desc.iProduct; + index_serial_str = uhost->dev_prop.dev_desc.iSerialNumber; + + uhost->enum_state = ENUM_SET_ADDR; + } + break; + + case ENUM_SET_ADDR: + /* set address */ + if (USBH_OK == usbh_setaddress (uhost, USBH_DEV_ADDR)) { + usb_mdelay (2U); + + uhost->dev_prop.addr = USBH_DEV_ADDR; + + /* user callback for device address assigned */ + uhost->usr_cb->dev_address_set(); + + /* modify control channels to update device address */ + usbh_pipe_update (udev, + uhost->control.pipe_in_num, + uhost->dev_prop.addr, + 0U, 0U); + + usbh_pipe_update (udev, + uhost->control.pipe_out_num, + uhost->dev_prop.addr, + 0U, 0U); + + uhost->enum_state = ENUM_GET_CFG_DESC; + } + break; + + case ENUM_GET_CFG_DESC: + /* get standard configuration descriptor */ + if (USBH_OK == usbh_cfgdesc_get (uhost, USB_CFG_DESC_LEN)) { + uhost->enum_state = ENUM_GET_CFG_DESC_SET; + } + break; + + case ENUM_GET_CFG_DESC_SET: + /* get full configure descriptor (config, interface, endpoints) */ + if (USBH_OK == usbh_cfgdesc_get (uhost, uhost->dev_prop.cfg_desc_set.cfg_desc.wTotalLength)) { + /* user callback for configuration descriptors available */ + uhost->usr_cb->dev_cfgdesc_assigned (&uhost->dev_prop.cfg_desc_set.cfg_desc, + &uhost->dev_prop.cfg_desc_set.itf_desc_set[0][0].itf_desc, + &uhost->dev_prop.cfg_desc_set.itf_desc_set[0][0].ep_desc[0]); + + uhost->enum_state = ENUM_GET_STR_DESC; + } + break; + + case ENUM_GET_STR_DESC: + if (index_mfc_str) { + if (USBH_OK == usbh_strdesc_get (uhost, + uhost->dev_prop.dev_desc.iManufacturer, + str_buf, + 0xFFU)) { + /* user callback for manufacturing string */ + uhost->usr_cb->dev_mfc_str(str_buf); + + index_mfc_str = 0U; + } + } else { + if (index_prod_str) { + /* check that product string is available */ + if (USBH_OK == usbh_strdesc_get (uhost, + uhost->dev_prop.dev_desc.iProduct, + str_buf, + 0xFFU)) { + uhost->usr_cb->dev_prod_str(str_buf); + + index_prod_str = 0U; + } + } else { + if (index_serial_str) { + if (USBH_OK == usbh_strdesc_get (uhost, + uhost->dev_prop.dev_desc.iSerialNumber, + str_buf, + 0xFFU)) { + uhost->usr_cb->dev_seral_str(str_buf); + uhost->enum_state = ENUM_SET_CONFIGURATION; + index_serial_str = 0U; + } + } else { + uhost->enum_state = ENUM_SET_CONFIGURATION; + } + } + } + break; + + case ENUM_SET_CONFIGURATION: + if (USBH_OK == usbh_setcfg (uhost, (uint16_t)uhost->dev_prop.cfg_desc_set.cfg_desc.bConfigurationValue)) { + uhost->enum_state = ENUM_DEV_CONFIGURED; + } + break; + + case ENUM_DEV_CONFIGURED: + status = USBH_OK; + break; + + default: + break; + } + + return status; +} + +#if USBFS_LOW_POWER || USBHS_LOW_POWER + +/*! + \brief handles the USB resume from suspend mode + \param[in] udev: pointer to selected USB device + \param[out] none + \retval none +*/ +static void usb_hwp_resume(usb_core_driver *udev) +{ + __IO uint32_t hprt = 0U; + + /* switch-on the clocks */ + *udev->regs.PWRCLKCTL &= ~PWRCLKCTL_SUCLK; + + *udev->regs.PWRCLKCTL &= ~PWRCLKCTL_SHCLK; + + hprt = usb_port_read(udev); + + hprt &= ~HPCS_PSP; + hprt |= HPCS_PREM; + + *udev->regs.HPCS = hprt; + + usb_mdelay (20U); + + hprt &= ~HPCS_PREM; + + *udev->regs.HPCS = hprt; +} + +/*! + \brief handles the USB enter to suspend mode + \param[in] udev: pointer to selected USB device + \param[out] none + \retval none +*/ +static void usb_hwp_suspend(usb_core_driver *udev) +{ + __IO uint32_t hprt = 0U; + + hprt = usb_port_read(udev); + + hprt |= HPCS_PSP; + + *udev->regs.HPCS = hprt; + + /* switch-off the clocks */ + *udev->regs.PWRCLKCTL |= PWRCLKCTL_SUCLK; + + *udev->regs.PWRCLKCTL |= PWRCLKCTL_SHCLK; +} + +#endif /* USBFS_LOW_POWER || USBHS_LOW_POWER */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_enum.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_enum.c new file mode 100644 index 0000000..f16520c --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_enum.c @@ -0,0 +1,693 @@ +/*! + \file usbh_enum.c + \brief USB host mode enumeration driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbh_pipe.h" +#include "usbh_transc.h" +#include "usbh_enum.h" + +/* local function prototypes ('static') */ +static void usbh_devdesc_parse (usb_desc_dev *dev_desc, uint8_t *buf, uint16_t len); +static void usbh_cfgdesc_parse (usb_desc_config *cfg_desc, uint8_t *buf); +static void usbh_cfgset_parse (usb_dev_prop *udev, uint8_t *buf); +static void usbh_itfdesc_parse (usb_desc_itf *itf_desc, uint8_t *buf); +static void usbh_epdesc_parse (usb_desc_ep *ep_desc, uint8_t *buf); +static void usbh_strdesc_parse (uint8_t *psrc, uint8_t *pdest, uint16_t len); + +/*! + \brief configure USB control status parameters + \param[in] uhost: pointer to USB host + \param[in] buf: control transfer data buffer pointer + \param[in] len: length of the data buffer + \param[out] none + \retval none +*/ +void usbh_ctlstate_config (usbh_host *uhost, uint8_t *buf, uint16_t len) +{ + /* prepare the transactions */ + uhost->control.buf = buf; + uhost->control.ctl_len = len; + + uhost->control.ctl_state = CTL_SETUP; +} + +/*! + \brief get device descriptor from the USB device + \param[in] uhost: pointer to USB host + \param[in] len: length of the descriptor + \param[out] none + \retval operation status +*/ +usbh_status usbh_devdesc_get (usbh_host *uhost, uint8_t len) +{ + usbh_status status = USBH_BUSY; + + usbh_control *usb_ctl = &uhost->control; + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_IN | USB_RECPTYPE_DEV | USB_REQTYPE_STRD, + .bRequest = USB_GET_DESCRIPTOR, + .wValue = USBH_DESC(USB_DESCTYPE_DEV), + .wIndex = 0U, + .wLength = len + }; + + usbh_ctlstate_config (uhost, uhost->dev_prop.data, (uint16_t)len); + } + + status = usbh_ctl_handler (uhost); + + if (USBH_OK == status) { + /* commands successfully sent and response received */ + usbh_devdesc_parse (&uhost->dev_prop.dev_desc, uhost->dev_prop.data, (uint16_t)len); + } + + return status; +} + +/*! + \brief get configuration descriptor from the USB device + \param[in] uhost: pointer to USB host + \param[in] len: length of the descriptor + \param[out] none + \retval operation status +*/ +usbh_status usbh_cfgdesc_get (usbh_host *uhost, uint16_t len) +{ + uint8_t *pdata = NULL; + + usbh_status status = USBH_BUSY; + + usbh_control *usb_ctl = &uhost->control; + +#if (USBH_CFG_DESC_KEEP == 1U) + pdata = uhost->dev_prop.cfgdesc_rawdata; +#else + pdata = uhost->dev_prop.data; +#endif /* (USBH_CFG_DESC_KEEP == 1U) */ + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_IN | USB_RECPTYPE_DEV | USB_REQTYPE_STRD, + .bRequest = USB_GET_DESCRIPTOR, + .wValue = USBH_DESC(USB_DESCTYPE_CONFIG), + .wIndex = 0U, + .wLength = len + }; + + usbh_ctlstate_config (uhost, pdata, len); + } + + status = usbh_ctl_handler (uhost); + + if (USBH_OK == status) { + if (len <= USB_CFG_DESC_LEN) { + usbh_cfgdesc_parse (&uhost->dev_prop.cfg_desc_set.cfg_desc, pdata); + } else { + usbh_cfgset_parse (&uhost->dev_prop, pdata); + } + } + + return status; +} + +/*! + \brief get string descriptor from the USB device + \param[in] uhost: pointer to USB host + \param[in] str_index: index for the string descriptor + \param[in] buf: buffer pointer to the string descriptor + \param[in] len: length of the descriptor + \param[out] none + \retval operation status +*/ +usbh_status usbh_strdesc_get (usbh_host *uhost, + uint8_t str_index, + uint8_t *buf, + uint16_t len) +{ + usbh_status status = USBH_BUSY; + + usbh_control *usb_ctl = &uhost->control; + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_IN | USB_RECPTYPE_DEV | USB_REQTYPE_STRD, + .bRequest = USB_GET_DESCRIPTOR, + .wValue = USBH_DESC(USB_DESCTYPE_STR) | str_index, + .wIndex = 0x0409U, + .wLength = len + }; + + usbh_ctlstate_config (uhost, uhost->dev_prop.data, len); + } + + status = usbh_ctl_handler (uhost); + + if (USBH_OK == status) { + /* commands successfully sent and response received */ + usbh_strdesc_parse (uhost->dev_prop.data, buf, len); + } + + return status; +} + +/*! + \brief set the address to the connected device + \param[in] uhost: pointer to USB host + \param[in] dev_addr: device address to assign + \param[out] none + \retval operation status +*/ +usbh_status usbh_setaddress (usbh_host *uhost, uint8_t dev_addr) +{ + usbh_status status = USBH_BUSY; + + usbh_control *usb_ctl = &uhost->control; + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_DEV | USB_REQTYPE_STRD, + .bRequest = USB_SET_ADDRESS, + .wValue = (uint16_t)dev_addr, + .wIndex = 0U, + .wLength = 0U + }; + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief set the configuration value to the connected device + \param[in] uhost: pointer to USB host + \param[in] config_index: configuration value + \param[out] none + \retval operation status +*/ +usbh_status usbh_setcfg (usbh_host *uhost, uint16_t config_index) +{ + usbh_status status = USBH_BUSY; + + usbh_control *usb_ctl = &uhost->control; + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_DEV | USB_REQTYPE_STRD, + .bRequest = USB_SET_CONFIGURATION, + .wValue = config_index, + .wIndex = 0U, + .wLength = 0U + }; + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief set the interface value to the connected device + \param[in] uhost: pointer to USB host + \param[in] itf_num: interface number + \param[in] set: alternated setting value + \param[out] none + \retval operation status +*/ +usbh_status usbh_setinterface (usbh_host *uhost, uint8_t itf_num, uint8_t set) +{ + usbh_status status = USBH_BUSY; + + usbh_control *usb_ctl = &uhost->control; + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_ITF | USB_REQTYPE_STRD, + .bRequest = USB_SET_INTERFACE, + .wValue = set, + .wIndex = itf_num, + .wLength = 0U + }; + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief set the interface value to the connected device + \param[in] uhost: pointer to USB host + \param[in] feature_selector: feature selector + \param[in] windex: index value + \param[out] none + \retval operation status +*/ +usbh_status usbh_setdevfeature (usbh_host *uhost, uint8_t feature_selector, uint16_t windex) +{ + usbh_status status = USBH_BUSY; + + usbh_control *usb_ctl = &uhost->control; + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_DEV | USB_REQTYPE_STRD, + .bRequest = USB_SET_FEATURE, + .wValue = feature_selector, + .wIndex = windex, + .wLength = 0U + }; + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief clear the interface value to the connected device + \param[in] uhost: pointer to USB host + \param[in] feature_selector: feature selector + \param[in] windex: index value + \param[out] none + \retval operation status +*/ +usbh_status usbh_clrdevfeature (usbh_host *uhost, uint8_t feature_selector, uint16_t windex) +{ + usbh_status status = USBH_BUSY; + + usbh_control *usb_ctl = &uhost->control; + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_DEV | USB_REQTYPE_STRD, + .bRequest = USB_CLEAR_FEATURE, + .wValue = feature_selector, + .wIndex = windex, + .wLength = 0U + }; + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief clear or disable a specific feature + \param[in] uhost: pointer to USB host + \param[in] ep_addr: endpoint address + \param[in] pp_num: pipe number + \param[out] none + \retval operation status +*/ +usbh_status usbh_clrfeature (usbh_host *uhost, uint8_t ep_addr, uint8_t pp_num) +{ + usbh_status status = USBH_BUSY; + usbh_control *usb_ctl = &uhost->control; + usb_core_driver *udev = (usb_core_driver *)uhost->data; + + if (CTL_IDLE == usb_ctl->ctl_state) { + usb_ctl->setup.req = (usb_req) { + .bmRequestType = USB_TRX_OUT | USB_RECPTYPE_EP | USB_REQTYPE_STRD, + .bRequest = USB_CLEAR_FEATURE, + .wValue = FEATURE_SELECTOR_EP, + .wIndex = ep_addr, + .wLength = 0U + }; + + if (EP_ID(ep_addr) == udev->host.pipe[pp_num].ep.num) { + usbh_pipe_toggle_set(udev, pp_num, 0U); + } else { + return USBH_FAIL; + } + + usbh_ctlstate_config (uhost, NULL, 0U); + } + + status = usbh_ctl_handler (uhost); + + return status; +} + +/*! + \brief get the next descriptor header + \param[in] pbuf: pointer to buffer where the configuration descriptor set is available + \param[in] ptr: data pointer inside the configuration descriptor set + \param[out] none + \retval return descriptor header +*/ +usb_desc_header *usbh_nextdesc_get (uint8_t *pbuf, uint16_t *ptr) +{ + usb_desc_header *pnext; + + *ptr += ((usb_desc_header *)pbuf)->bLength; + + pnext = (usb_desc_header *)((uint8_t *)pbuf + ((usb_desc_header *)pbuf)->bLength); + + return (pnext); +} + +/*! + \brief get the next descriptor header + \param[in] udev: pointer to device property + \param[in] interface: interface number + \param[out] none + \retval operation status +*/ +usbh_status usbh_interface_select (usb_dev_prop *udev, uint8_t interface) +{ + usbh_status status = USBH_OK; + + if (interface < udev->cfg_desc_set.cfg_desc.bNumInterfaces) { + udev->cur_itf = interface; + } else { + status = USBH_FAIL; + } + + return status; +} + +/*! + \brief find the interface index for a specific class + \param[in] udev: pointer to device property + \param[in] main_class: class code + \param[in] sub_class: subclass code + \param[in] protocol: Protocol code + \param[out] none + \retval interface index in the configuration structure + \note interface index 0xFF means interface index not found +*/ +uint8_t usbh_interface_find (usb_dev_prop *udev, uint8_t main_class, uint8_t sub_class, uint8_t protocol) +{ + usb_desc_itf *pif; + + uint8_t if_ix = 0U; + + pif = (usb_desc_itf *)0; + + while (if_ix < udev->cfg_desc_set.cfg_desc.bNumInterfaces) { + pif = &udev->cfg_desc_set.itf_desc_set[if_ix][0].itf_desc; + + if (((pif->bInterfaceClass == main_class) || (main_class == 0xFFU))&& + ((pif->bInterfaceSubClass == sub_class) || (sub_class == 0xFFU))&& + ((pif->bInterfaceProtocol == protocol) || (protocol == 0xFFU))) { + return if_ix; + } + + if_ix++; + } + + return 0xFFU; +} + +/*! + \brief find the interface index for a specific class interface and alternate setting number + \param[in] udev: pointer to device property + \param[in] interface_number: interface number + \param[in] alt_settings: alternate setting number + \param[out] none + \retval interface index in the configuration structure + \note interface index 0xFF means interface index not found +*/ +uint8_t usbh_interfaceindex_find (usb_dev_prop *udev, uint8_t interface_number, uint8_t alt_settings) +{ + usb_desc_itf *pif; + + uint8_t if_ix = 0U; + + pif = (usb_desc_itf *)0; + + while (if_ix < USBH_MAX_INTERFACES_NUM) { + pif = &udev->cfg_desc_set.itf_desc_set[if_ix][alt_settings].itf_desc; + + if ((pif->bInterfaceNumber == interface_number) && (pif->bAlternateSetting == alt_settings)) { + return if_ix; + } + + if_ix++; + } + + return 0xFFU; +} + +/*! + \brief parse the device descriptor + \param[in] dev_desc: pointer to USB device descriptor buffer + \param[in] buf: pointer to the source descriptor buffer + \param[in] len: length of the descriptor + \param[out] none + \retval none +*/ +static void usbh_devdesc_parse (usb_desc_dev *dev_desc, uint8_t *buf, uint16_t len) +{ + *dev_desc = (usb_desc_dev) { + .header = { + .bLength = *(uint8_t *)(buf + 0U), + .bDescriptorType = *(uint8_t *)(buf + 1U) + }, + + .bcdUSB = BYTE_SWAP(buf + 2U), + .bDeviceClass = *(uint8_t *)(buf + 4U), + .bDeviceSubClass = *(uint8_t *)(buf + 5U), + .bDeviceProtocol = *(uint8_t *)(buf + 6U), + .bMaxPacketSize0 = *(uint8_t *)(buf + 7U) + }; + + if (len > 8U) { + /* for 1st time after device connection, host may issue only 8 bytes for device descriptor length */ + dev_desc->idVendor = BYTE_SWAP(buf + 8U); + dev_desc->idProduct = BYTE_SWAP(buf + 10U); + dev_desc->bcdDevice = BYTE_SWAP(buf + 12U); + dev_desc->iManufacturer = *(uint8_t *)(buf + 14U); + dev_desc->iProduct = *(uint8_t *)(buf + 15U); + dev_desc->iSerialNumber = *(uint8_t *)(buf + 16U); + dev_desc->bNumberConfigurations = *(uint8_t *)(buf + 17U); + } +} + +/*! + \brief parse the configuration descriptor + \param[in] cfg_desc: pointer to USB configuration descriptor buffer + \param[in] buf: pointer to the source descriptor buffer + \param[out] none + \retval none +*/ +static void usbh_cfgdesc_parse (usb_desc_config *cfg_desc, uint8_t *buf) +{ + /* parse configuration descriptor */ + *cfg_desc = (usb_desc_config) { + .header = { + .bLength = *(uint8_t *)(buf + 0U), + .bDescriptorType = *(uint8_t *)(buf + 1U), + }, + + .wTotalLength = BYTE_SWAP(buf + 2U), + .bNumInterfaces = *(uint8_t *)(buf + 4U), + .bConfigurationValue = *(uint8_t *)(buf + 5U), + .iConfiguration = *(uint8_t *)(buf + 6U), + .bmAttributes = *(uint8_t *)(buf + 7U), + .bMaxPower = *(uint8_t *)(buf + 8U) + }; +} + +/*! + \brief parse the configuration descriptor set + \param[in] udev: pointer to device property + \param[in] buf: pointer to the source descriptor buffer + \param[out] none + \retval none +*/ +static void usbh_cfgset_parse (usb_dev_prop *udev, uint8_t *buf) +{ + usb_desc_ep *ep = NULL; + usb_desc_itf_set *itf = NULL; + usb_desc_itf itf_value; + usb_desc_config *cfg = NULL; + + usb_desc_header *pdesc = (usb_desc_header *)buf; + + uint8_t itf_index = 0U, ep_index = 0U, alt_setting = 0U; + uint8_t pre_itf_index = 0U; + uint16_t ptr; + + /* parse configuration descriptor */ + usbh_cfgdesc_parse (&udev->cfg_desc_set.cfg_desc, buf); + cfg = &udev->cfg_desc_set.cfg_desc; + ptr = USB_CFG_DESC_LEN; + + if (cfg->bNumInterfaces > USBH_MAX_INTERFACES_NUM) { + return; + } + + while (ptr < cfg->wTotalLength) { + pdesc = usbh_nextdesc_get ((uint8_t *)pdesc, &ptr); + + if (pdesc->bDescriptorType == USB_DESCTYPE_ITF) { + itf_index = *(((uint8_t *)pdesc) + 2U); + + if (pre_itf_index != itf_index) { + alt_setting = 0U; + } + + itf = &udev->cfg_desc_set.itf_desc_set[itf_index][alt_setting]; + + alt_setting++; + + if ((*((uint8_t *)pdesc + 3U)) < 3U) { + usbh_itfdesc_parse (&itf_value, (uint8_t *)pdesc); + + /* parse endpoint descriptors relative to the current interface */ + if (itf_value.bNumEndpoints > USBH_MAX_EP_NUM) { + return; + } + + usbh_itfdesc_parse (&itf->itf_desc, (uint8_t *)&itf_value); + + /* store the previous interface index */ + pre_itf_index = itf_index; + + if (0U == itf_value.bNumEndpoints) { + continue; + } + + for (ep_index = 0U; ep_index < itf_value.bNumEndpoints; ) { + pdesc = usbh_nextdesc_get ((void*)pdesc, &ptr); + + if (pdesc->bDescriptorType == USB_DESCTYPE_EP) { + ep = &itf->ep_desc[ep_index]; + + usbh_epdesc_parse (ep, (uint8_t *)pdesc); + + ep_index++; + } + } + } + } + } +} + +/*! + \brief parse the interface descriptor + \param[in] itf_desc: pointer to USB interface descriptor buffer + \param[in] buf: pointer to the source descriptor buffer + \param[out] none + \retval none +*/ +static void usbh_itfdesc_parse (usb_desc_itf *itf_desc, uint8_t *buf) +{ + *itf_desc = (usb_desc_itf) { + .header = { + .bLength = *(uint8_t *)(buf + 0U), + .bDescriptorType = *(uint8_t *)(buf + 1U), + }, + + .bInterfaceNumber = *(uint8_t *)(buf + 2U), + .bAlternateSetting = *(uint8_t *)(buf + 3U), + .bNumEndpoints = *(uint8_t *)(buf + 4U), + .bInterfaceClass = *(uint8_t *)(buf + 5U), + .bInterfaceSubClass = *(uint8_t *)(buf + 6U), + .bInterfaceProtocol = *(uint8_t *)(buf + 7U), + .iInterface = *(uint8_t *)(buf + 8U) + }; +} + +/*! + \brief parse the endpoint descriptor + \param[in] ep_desc: pointer to USB endpoint descriptor buffer + \param[in] buf: pointer to the source descriptor buffer + \param[out] none + \retval none +*/ +static void usbh_epdesc_parse (usb_desc_ep *ep_desc, uint8_t *buf) +{ + *ep_desc = (usb_desc_ep) { + .header = { + .bLength = *(uint8_t *)(buf + 0U), + .bDescriptorType = *(uint8_t *)(buf + 1U) + }, + + .bEndpointAddress = *(uint8_t *)(buf + 2U), + .bmAttributes = *(uint8_t *)(buf + 3U), + .wMaxPacketSize = BYTE_SWAP(buf + 4U), + .bInterval = *(uint8_t *)(buf + 6U) + }; +} + +/*! + \brief parse the string descriptor + \param[in] psrc: source pointer containing the descriptor data + \param[in] pdest: destination address pointer + \param[in] len: length of the descriptor + \param[out] none + \retval none +*/ +static void usbh_strdesc_parse (uint8_t *psrc, uint8_t *pdest, uint16_t len) +{ + uint16_t str_len = 0U, index = 0U; + + /* the unicode string descriptor is not NULL-terminated. The string length is + * computed by substracting two from the value of the first byte of the descriptor. + */ + + /* check which is lower size, the size of string or the length of bytes read from the device */ + if (USB_DESCTYPE_STR == psrc[1]) { + /* make sure the descriptor is string type */ + + /* psrc[0] contains size of descriptor, subtract 2 to get the length of string */ + str_len = USB_MIN((uint16_t)psrc[0] - 2U, len); + + psrc += 2U; /* adjust the offset ignoring the string length and descriptor type */ + + for(index = 0U; index < str_len; index += 2U) { + /* copy only the string and ignore the unicode id, hence add the source */ + *pdest = psrc[index]; + + pdest++; + } + + *pdest = 0U; /* mark end of string */ + } +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_pipe.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_pipe.c new file mode 100644 index 0000000..9d86723 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_pipe.c @@ -0,0 +1,181 @@ +/*! + \file usbh_pipe.c + \brief USB host mode pipe operation driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "usbh_pipe.h" + +/* local function prototypes ('static') */ +static uint16_t usbh_freepipe_get (usb_core_driver *udev); + +/*! + \brief create a pipe + \param[in] udev: pointer to USB core instance + \param[in] dev: USB device + \param[in] pp_num: pipe number + \param[in] ep_type: endpoint type + \param[in] ep_mpl: endpoint max packet length + \param[out] none + \retval operation status +*/ +uint8_t usbh_pipe_create (usb_core_driver *udev, + usb_dev_prop *dev, + uint8_t pp_num, + uint8_t ep_type, + uint16_t ep_mpl) +{ + usb_pipe *pp = &udev->host.pipe[pp_num]; + + pp->dev_addr = dev->addr; + pp->dev_speed = dev->speed; + pp->ep.type = ep_type; + pp->ep.mps = ep_mpl; + + if (((USB_EPTYPE_BULK == pp->ep.type) || (USB_EPTYPE_CTRL == pp->ep.type))) { + pp->supp_ping = (uint8_t)(pp->dev_speed == PORT_SPEED_HIGH); + } + + usb_pipe_init (udev, pp_num); + + return HP_OK; +} + +/*! + \brief modify a pipe + \param[in] udev: pointer to USB core instance + \param[in] pp_num: pipe number + \param[in] dev_addr: device address + \param[in] dev_speed: device speed + \param[in] ep_mpl: endpoint max packet length + \param[out] none + \retval operation status +*/ +uint8_t usbh_pipe_update (usb_core_driver *udev, + uint8_t pp_num, + uint8_t dev_addr, + uint32_t dev_speed, + uint16_t ep_mpl) +{ + usb_pipe *pp = &udev->host.pipe[pp_num]; + + if ((pp->dev_addr != dev_addr) && (dev_addr)) { + pp->dev_addr = dev_addr; + } + + if ((pp->dev_speed != dev_speed) && (dev_speed)) { + pp->dev_speed = dev_speed; + + if (((USB_EPTYPE_BULK == pp->ep.type) || (USB_EPTYPE_CTRL == pp->ep.type))) { + pp->supp_ping = (uint8_t)(pp->dev_speed == PORT_SPEED_HIGH); + } + } + + if ((pp->ep.mps != ep_mpl) && (ep_mpl)) { + pp->ep.mps = ep_mpl; + } + + usb_pipe_init (udev, pp_num); + + return HP_OK; +} + +/*! + \brief allocate a new pipe + \param[in] udev: pointer to USB core instance + \param[in] ep_addr: endpoint address + \param[out] none + \retval operation status +*/ +uint8_t usbh_pipe_allocate (usb_core_driver *udev, uint8_t ep_addr) +{ + uint16_t pp_num = usbh_freepipe_get (udev); + + if (HP_ERROR != pp_num) { + udev->host.pipe[pp_num].in_used = 1U; + udev->host.pipe[pp_num].ep.dir = EP_DIR(ep_addr); + udev->host.pipe[pp_num].ep.num = EP_ID(ep_addr); + } + + return (uint8_t)pp_num; +} + +/*! + \brief free a pipe + \param[in] udev: pointer to USB core instance + \param[in] pp_num: pipe number + \param[out] none + \retval operation status +*/ +uint8_t usbh_pipe_free (usb_core_driver *udev, uint8_t pp_num) +{ + if (pp_num < HP_MAX) { + udev->host.pipe[pp_num].in_used = 0U; + } + + return USBH_OK; +} + +/*! + \brief delete all USB host pipe + \param[in] udev: pointer to USB core instance + \param[out] none + \retval operation status +*/ +uint8_t usbh_pipe_delete (usb_core_driver *udev) +{ + uint8_t pp_num = 0U; + + for (pp_num = 2U; pp_num < HP_MAX; pp_num++) { + udev->host.pipe[pp_num] = (usb_pipe) {0}; + } + + return USBH_OK; +} + +/*! + \brief get a free pipe number for allocation + \param[in] udev: pointer to USB core instance + \param[out] none + \retval operation status +*/ +static uint16_t usbh_freepipe_get (usb_core_driver *udev) +{ + uint8_t pp_num = 0U; + + for (pp_num = 0U; pp_num < HP_MAX; pp_num++) { + if (0U == udev->host.pipe[pp_num].in_used) { + return (uint16_t)pp_num; + } + } + + return HP_ERROR; +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_transc.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_transc.c new file mode 100644 index 0000000..ee7fd0a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/host/core/Source/usbh_transc.c @@ -0,0 +1,371 @@ +/*! + \file usbh_transc.c + \brief USB host mode transactions driver + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 "drv_usb_hw.h" +#include "usbh_pipe.h" +#include "usbh_transc.h" + +/* local function prototypes ('static') */ +static usb_urb_state usbh_urb_wait (usbh_host *uhost, uint8_t pp_num, uint32_t wait_time); +static void usbh_setup_transc (usbh_host *uhost); +static void usbh_data_in_transc (usbh_host *uhost); +static void usbh_data_out_transc (usbh_host *uhost); +static void usbh_status_in_transc (usbh_host *uhost); +static void usbh_status_out_transc (usbh_host *uhost); +static uint32_t usbh_request_submit (usb_core_driver *udev, uint8_t pp_num); + +/*! + \brief send the setup packet to the USB device + \param[in] udev: pointer to USB core instance + \param[in] buf: data buffer which will be sent to USB device + \param[in] pp_num: pipe number + \param[out] none + \retval operation status +*/ +usbh_status usbh_ctlsetup_send (usb_core_driver *udev, uint8_t *buf, uint8_t pp_num) +{ + usb_pipe *pp = &udev->host.pipe[pp_num]; + + pp->DPID = PIPE_DPID_SETUP; + pp->xfer_buf = buf; + pp->xfer_len = USB_SETUP_PACKET_LEN; + + return (usbh_status)usbh_request_submit (udev, pp_num); +} + +/*! + \brief send a data packet to the USB device + \param[in] udev: pointer to USB core instance + \param[in] buf: data buffer which will be sent to USB device + \param[in] pp_num: pipe number + \param[in] len: length of the data to be sent + \param[out] none + \retval operation status +*/ +usbh_status usbh_data_send (usb_core_driver *udev, uint8_t *buf, uint8_t pp_num, uint16_t len) +{ + usb_pipe *pp = &udev->host.pipe[pp_num]; + + pp->xfer_buf = buf; + pp->xfer_len = len; + + switch (pp->ep.type) { + case USB_EPTYPE_CTRL: + if (0U == len) { + pp->data_toggle_out = 1U; + } + + pp->DPID = PIPE_DPID[pp->data_toggle_out]; + break; + + case USB_EPTYPE_INTR: + pp->DPID = PIPE_DPID[pp->data_toggle_out]; + + pp->data_toggle_out ^= 1U; + break; + + case USB_EPTYPE_BULK: + pp->DPID = PIPE_DPID[pp->data_toggle_out]; + break; + + case USB_EPTYPE_ISOC: + pp->DPID = PIPE_DPID[0]; + break; + + default: + break; + } + + usbh_request_submit (udev, pp_num); + + return USBH_OK; +} + +/*! + \brief receive a data packet from the USB device + \param[in] udev: pointer to USB core instance + \param[in] buf: data buffer which will be received from USB device + \param[in] pp_num: pipe number + \param[in] len: length of the data to be received + \param[out] none + \retval operation status +*/ +usbh_status usbh_data_recev (usb_core_driver *udev, uint8_t *buf, uint8_t pp_num, uint16_t len) +{ + usb_pipe *pp = &udev->host.pipe[pp_num]; + + pp->xfer_buf = buf; + pp->xfer_len = len; + + switch (pp->ep.type) { + case USB_EPTYPE_CTRL: + pp->DPID = PIPE_DPID[1]; + break; + + case USB_EPTYPE_INTR: + pp->DPID = PIPE_DPID[pp->data_toggle_in]; + + /* toggle DATA PID */ + pp->data_toggle_in ^= 1U; + break; + + case USB_EPTYPE_BULK: + pp->DPID = PIPE_DPID[pp->data_toggle_in]; + break; + + case USB_EPTYPE_ISOC: + pp->DPID = PIPE_DPID[0]; + break; + + default: + break; + } + + usbh_request_submit (udev, pp_num); + + return USBH_OK; +} + +/*! + \brief USB control transfer handler + \param[in] uhost: pointer to USB host + \param[out] none + \retval operation status +*/ +usbh_status usbh_ctl_handler (usbh_host *uhost) +{ + usbh_status status = USBH_BUSY; + + switch (uhost->control.ctl_state) { + case CTL_SETUP: + usbh_setup_transc (uhost); + break; + + case CTL_DATA_IN: + usbh_data_in_transc (uhost); + break; + + case CTL_DATA_OUT: + usbh_data_out_transc (uhost); + break; + + case CTL_STATUS_IN: + usbh_status_in_transc (uhost); + break; + + case CTL_STATUS_OUT: + usbh_status_out_transc (uhost); + break; + + case CTL_FINISH: + uhost->control.ctl_state = CTL_IDLE; + + status = USBH_OK; + break; + + case CTL_ERROR: + if (++uhost->control.error_count <= USBH_MAX_ERROR_COUNT) { + /* do the transmission again, starting from SETUP packet */ + uhost->control.ctl_state = CTL_SETUP; + } else { + status = USBH_FAIL; + } + break; + + default: + break; + } + + return status; +} + +/*! + \brief wait for USB URB(USB request block) state + \param[in] uhost: pointer to USB host + \param[in] pp_num: pipe number + \param[in] wait_time: wait time + \param[out] none + \retval USB URB state +*/ +static usb_urb_state usbh_urb_wait (usbh_host *uhost, uint8_t pp_num, uint32_t wait_time) +{ + uint32_t timeout = 0U; + usb_urb_state urb_status = URB_IDLE; + timeout = uhost->control.timer; + + while (URB_DONE != (urb_status = usbh_urbstate_get(uhost->data, pp_num))) { + if (URB_NOTREADY == urb_status) { + break; + } else if (URB_STALL == urb_status) { + uhost->control.ctl_state = CTL_SETUP; + break; + } else if (URB_ERROR == urb_status) { + uhost->control.ctl_state = CTL_ERROR; + break; + } else if ((wait_time > 0U) && ((uhost->control.timer - timeout) > wait_time)) { + /* timeout for in transfer */ + uhost->control.ctl_state = CTL_ERROR; + break; + } else { + /* no operation, just wait */ + } + } + + return urb_status; +} + +/*! + \brief USB setup transaction + \param[in] uhost: pointer to USB host + \param[out] none + \retval none +*/ +static void usbh_setup_transc (usbh_host *uhost) +{ + /* send a SETUP packet */ + usbh_ctlsetup_send (uhost->data, + uhost->control.setup.data, + uhost->control.pipe_out_num); + + if (URB_DONE == usbh_urb_wait (uhost, uhost->control.pipe_out_num, 0U)) { + uint8_t dir = (uhost->control.setup.req.bmRequestType & USB_TRX_MASK); + + if (uhost->control.setup.req.wLength) { + if (USB_TRX_IN == dir) { + uhost->control.ctl_state = CTL_DATA_IN; + } else { + uhost->control.ctl_state = CTL_DATA_OUT; + } + } else { + if (USB_TRX_IN == dir) { + uhost->control.ctl_state = CTL_STATUS_OUT; + } else { + uhost->control.ctl_state = CTL_STATUS_IN; + } + } + } +} + +/*! + \brief USB data IN transaction + \param[in] uhost: pointer to USB host + \param[out] none + \retval none +*/ +static void usbh_data_in_transc (usbh_host *uhost) +{ + usbh_data_recev (uhost->data, + uhost->control.buf, + uhost->control.pipe_in_num, + uhost->control.ctl_len); + + if (URB_DONE == usbh_urb_wait (uhost, uhost->control.pipe_in_num, DATA_STAGE_TIMEOUT)) { + uhost->control.ctl_state = CTL_STATUS_OUT; + + } +} + +/*! + \brief USB data OUT transaction + \param[in] uhost: pointer to USB host + \param[out] none + \retval none +*/ +static void usbh_data_out_transc (usbh_host *uhost) +{ + usbh_pipe_toggle_set(uhost->data, uhost->control.pipe_out_num, 1U); + + usbh_data_send (uhost->data, + uhost->control.buf, + uhost->control.pipe_out_num, + uhost->control.ctl_len); + + if (URB_DONE == usbh_urb_wait (uhost, uhost->control.pipe_out_num, DATA_STAGE_TIMEOUT)) { + uhost->control.ctl_state = CTL_STATUS_IN; + } +} + +/*! + \brief USB status IN transaction + \param[in] uhost: pointer to USB host + \param[out] none + \retval none +*/ +static void usbh_status_in_transc (usbh_host *uhost) +{ + uint8_t pp_num = uhost->control.pipe_in_num; + + usbh_data_recev (uhost->data, NULL, pp_num, 0U); + + if (URB_DONE == usbh_urb_wait (uhost, pp_num, NODATA_STAGE_TIMEOUT)) { + uhost->control.ctl_state = CTL_FINISH; + } +} + +/*! + \brief USB status OUT transaction + \param[in] uhost: pointer to USB host + \param[out] none + \retval none +*/ +static void usbh_status_out_transc (usbh_host *uhost) +{ + uint8_t pp_num = uhost->control.pipe_out_num; + + usbh_data_send (uhost->data, NULL, pp_num, 0U); + + if (URB_DONE == usbh_urb_wait (uhost, pp_num, NODATA_STAGE_TIMEOUT)) { + uhost->control.ctl_state = CTL_FINISH; + } +} + +/*! + \brief prepare a pipe and start a transfer + \param[in] udev: pointer to USB core instance + \param[in] pp_num: pipe number + \param[out] none + \retval operation status +*/ +static uint32_t usbh_request_submit (usb_core_driver *udev, uint8_t pp_num) +{ + udev->host.pipe[pp_num].urb_state = URB_IDLE; + udev->host.pipe[pp_num].xfer_count = 0U; + + if (1U == udev->host.pipe[pp_num].do_ping) { + (void)usb_pipe_ping (udev, (uint8_t)pp_num); + return USB_OK; + } + + return (uint32_t)usb_pipe_xfer (udev, pp_num); +} diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/cdc/usb_cdc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/cdc/usb_cdc.h new file mode 100644 index 0000000..7508222 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/cdc/usb_cdc.h @@ -0,0 +1,180 @@ +/*! + \file usb_cdc.h + \brief the header file of communication device class standard + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USB_CDC_H +#define __USB_CDC_H + +#include "usb_ch9_std.h" + +/* communications device class code */ +#define USB_CLASS_CDC 0x02U + +/* communications interface class control protocol codes */ +#define USB_CDC_PROTOCOL_NONE 0x00U +#define USB_CDC_PROTOCOL_AT 0x01U +#define USB_CDC_PROTOCOL_VENDOR 0xFFU + +/* data interface class code */ +#define USB_CLASS_DATA 0x0AU + +#define USB_DESCTYPE_CDC_ACM 0x21U +#define USB_DESCTYPE_CS_INTERFACE 0x24U + +#define USB_CDC_ACM_CONFIG_DESC_SIZE 0x43U + +/* class-specific notification codes for pstn subclasses */ +#define USB_CDC_NOTIFY_SERIAL_STATE 0x20U + +/* class-specific request codes */ +#define SEND_ENCAPSULATED_COMMAND 0x00U +#define GET_ENCAPSULATED_RESPONSE 0x01U +#define SET_COMM_FEATURE 0x02U +#define GET_COMM_FEATURE 0x03U +#define CLEAR_COMM_FEATURE 0x04U + +#define SET_AUX_LINE_STATE 0x10U +#define SET_HOOK_STATE 0x11U +#define PULSE_SETUP 0x12U +#define SEND_PULSE 0x13U +#define SET_PULSE_TIME 0x14U +#define RING_AUX_JACK 0x15U + +#define SET_LINE_CODING 0x20U +#define GET_LINE_CODING 0x21U +#define SET_CONTROL_LINE_STATE 0x22U +#define SEND_BREAK 0x23U +#define NO_CMD 0xFFU + +#define SET_RINGER_PARMS 0x30U +#define GET_RINGER_PARMS 0x31U +#define SET_OPERATION_PARMS 0x32U +#define GET_OPERATION_PARMS 0x33U +#define SET_LINE_PARMS 0x34U +#define GET_LINE_PARMS 0x35U +#define DIAL_DIGITS 0x36U +#define SET_UNIT_PARAMETER 0x37U +#define GET_UNIT_PARAMETER 0x38U +#define CLEAR_UNIT_PARAMETER 0x39U +#define GET_PROFILE 0x3AU + +#define SET_ETHERNET_MULTICAST_FILTERS 0x40U +#define SET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x41U +#define GET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x42U +#define SET_ETHERNET_PACKET_FILTER 0x43U +#define GET_ETHERNET_STATISTIC 0x44U + +#define SET_ATM_DATA_FORMAT 0x50U +#define GET_ATM_DEVICE_STATISTICS 0x51U +#define SET_ATM_DEFAULT_VC 0x52U +#define GET_ATM_VC_STATISTICS 0x53U + +/* wValue for set control line state */ +#define CDC_ACTIVATE_CARRIER_SIGNAL_RTS 0x0002U +#define CDC_DEACTIVATE_CARRIER_SIGNAL_RTS 0x0000U +#define CDC_ACTIVATE_SIGNAL_DTR 0x0001U +#define CDC_DEACTIVATE_SIGNAL_DTR 0x0000U + +/* CDC subclass code */ +enum usb_cdc_subclass { + USB_CDC_SUBCLASS_RESERVED = 0U, /*!< reserved */ + USB_CDC_SUBCLASS_DLCM, /*!< direct line control mode */ + USB_CDC_SUBCLASS_ACM, /*!< abstract control mode */ + USB_CDC_SUBCLASS_TCM, /*!< telephone control mode */ + USB_CDC_SUBCLASS_MCM, /*!< multichannel control model */ + USB_CDC_SUBCLASS_CCM, /*!< CAPI control model */ + USB_CDC_SUBCLASS_ENCM, /*!< ethernet networking control model */ + USB_CDC_SUBCLASS_ANCM /*!< ATM networking control model */ +}; + +#pragma pack(1) + +/* cdc acm line coding structure */ +typedef struct { + uint32_t dwDTERate; /*!< data terminal rate */ + uint8_t bCharFormat; /*!< stop bits */ + uint8_t bParityType; /*!< parity */ + uint8_t bDataBits; /*!< data bits */ +} acm_line; + +/* notification structure */ +typedef struct { + uint8_t bmRequestType; /*!< type of request */ + uint8_t bNotification; /*!< communication interface class notifications */ + uint16_t wValue; /*!< value of notification */ + uint16_t wIndex; /*!< index of interface */ + uint16_t wLength; /*!< length of notification data */ +} acm_notification; + +typedef struct { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: header function descriptor */ + uint16_t bcdCDC; /*!< bcdCDC: low byte of spec release number (CDC1.10) */ +} usb_desc_header_func; + +typedef struct { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: call management function descriptor */ + uint8_t bmCapabilities; /*!< bmCapabilities: D0 is reset, D1 is ignored */ + uint8_t bDataInterface; /*!< bDataInterface: 1 interface used for call management */ +} usb_desc_call_managment_func; + +typedef struct { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: abstract control management descriptor */ + uint8_t bmCapabilities; /*!< bmCapabilities: D1 */ +} usb_desc_acm_func; + +typedef struct { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: union function descriptor */ + uint8_t bMasterInterface; /*!< bMasterInterface: communication class interface */ + uint8_t bSlaveInterface0; /*!< bSlaveInterface0: data class interface */ +} usb_desc_union_func; + +#pragma pack() + +typedef struct { + usb_desc_config config; + usb_desc_itf cmd_itf; + usb_desc_header_func cdc_header; + usb_desc_call_managment_func cdc_call_managment; + usb_desc_acm_func cdc_acm; + usb_desc_union_func cdc_union; + usb_desc_ep cdc_cmd_endpoint; + usb_desc_itf cdc_data_interface; + usb_desc_ep cdc_out_endpoint; + usb_desc_ep cdc_in_endpoint; +} usb_cdc_desc_config_set; + +#endif /* __USB_CDC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/hid/usb_hid.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/hid/usb_hid.h new file mode 100644 index 0000000..7cf9281 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/hid/usb_hid.h @@ -0,0 +1,83 @@ +/*! + \file usb_hid.h + \brief definitions for the USB HID class + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USB_HID_H +#define __USB_HID_H + +#include "usb_ch9_std.h" + +#define USB_HID_CLASS 0x03U + +#define USB_DESCTYPE_HID 0x21U +#define USB_DESCTYPE_REPORT 0x22U + +/* HID subclass code */ +#define USB_HID_SUBCLASS_BOOT_ITF 0x01U + +/* HID protocol codes */ +#define USB_HID_PROTOCOL_KEYBOARD 0x01U +#define USB_HID_PROTOCOL_MOUSE 0x02U + +#define GET_REPORT 0x01U +#define GET_IDLE 0x02U +#define GET_PROTOCOL 0x03U +#define SET_REPORT 0x09U +#define SET_IDLE 0x0AU +#define SET_PROTOCOL 0x0BU + +#pragma pack(1) + +typedef struct +{ + usb_desc_header header; /*!< regular descriptor header containing the descriptor's type and length */ + + uint16_t bcdHID; /*!< BCD encoded version that the HID descriptor and device complies to */ + uint8_t bCountryCode; /*!< country code of the localized device, or zero if universal */ + uint8_t bNumDescriptors; /*!< total number of HID report descriptors for the interface */ + uint8_t bDescriptorType; /*!< type of HID report */ + uint16_t wDescriptorLength; /*!< length of the associated HID report descriptor, in bytes */ +} usb_desc_hid; + +#pragma pack() + +typedef struct +{ + usb_desc_config config; + usb_desc_itf hid_itf; + usb_desc_hid hid_vendor; + usb_desc_ep hid_epin; + usb_desc_ep hid_epout; +} usb_hid_desc_config_set; + +#endif /* __USB_HID_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/msc_bbb.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/msc_bbb.h new file mode 100644 index 0000000..a3cf185 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/msc_bbb.h @@ -0,0 +1,69 @@ +/*! + \file msc_bbb.h + \brief definitions for the USB MSC BBB(bulk/bulk/bulk) protocol + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __MSC_BBB_H +#define __MSC_BBB_H + +#include "usb_ch9_std.h" + +#define BBB_CBW_SIGNATURE 0x43425355U +#define BBB_CSW_SIGNATURE 0x53425355U +#define BBB_CBW_LENGTH 31U +#define BBB_CSW_LENGTH 13U + +typedef struct { + uint32_t dCBWSignature; + uint32_t dCBWTag; + uint32_t dCBWDataTransferLength; + uint8_t bmCBWFlags; + uint8_t bCBWLUN; + uint8_t bCBWCBLength; + uint8_t CBWCB[16]; +} msc_bbb_cbw; + +typedef struct { + uint32_t dCSWSignature; + uint32_t dCSWTag; + uint32_t dCSWDataResidue; + uint8_t bCSWStatus; +} msc_bbb_csw; + +/* CSW command status */ +enum msc_csw_status { + CSW_CMD_PASSED = 0, + CSW_CMD_FAILED, + CSW_PHASE_ERROR +}; + +#endif /* __MSC_BBB_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/msc_scsi.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/msc_scsi.h new file mode 100644 index 0000000..c049a47 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/msc_scsi.h @@ -0,0 +1,117 @@ +/*! + \file msc_scsi.h + \brief definitions for the USB MSC SCSI commands + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __MSC_SCSI_H +#define __MSC_SCSI_H + +#include "usb_ch9_std.h" + +/* SCSI commands */ +#define SCSI_FORMAT_UNIT 0x04U +#define SCSI_INQUIRY 0x12U +#define SCSI_MODE_SELECT6 0x15U +#define SCSI_MODE_SELECT10 0x55U +#define SCSI_MODE_SENSE6 0x1AU +#define SCSI_READ_TOC_DATA 0x43U +#define SCSI_MODE_SENSE10 0x5AU +#define SCSI_ALLOW_MEDIUM_REMOVAL 0x1EU +#define SCSI_READ6 0x08U +#define SCSI_READ10 0x28U +#define SCSI_READ12 0xA8U +#define SCSI_READ16 0x88U + +#define SCSI_READ_CAPACITY10 0x25U +#define SCSI_READ_CAPACITY16 0x9EU + +#define SCSI_REQUEST_SENSE 0x03U +#define SCSI_START_STOP_UNIT 0x1BU +#define SCSI_TEST_UNIT_READY 0x00U +#define SCSI_WRITE6 0x0AU +#define SCSI_WRITE10 0x2AU +#define SCSI_WRITE12 0xAAU +#define SCSI_WRITE16 0x8AU + +#define SCSI_VERIFY10 0x2FU +#define SCSI_VERIFY12 0xAFU +#define SCSI_VERIFY16 0x8FU + +#define SCSI_SEND_DIAGNOSTIC 0x1DU +#define SCSI_READ_FORMAT_CAPACITIES 0x23U + +#define INVALID_CDB 0x20U +#define INVALID_FIELED_IN_COMMAND 0x24U +#define PARAMETER_LIST_LENGTH_ERROR 0x1AU +#define INVALID_FIELD_IN_PARAMETER_LIST 0x26U +#define ADDRESS_OUT_OF_RANGE 0x21U +#define MEDIUM_NOT_PRESENT 0x3AU +#define MEDIUM_HAVE_CHANGED 0x28U +#define WRITE_PROTECTED 0x27U +#define UNRECOVERED_READ_ERROR 0x11U +#define WRITE_FAULT 0x03U + +#define READ_FORMAT_CAPACITY_DATA_LEN 0x0CU +#define READ_CAPACITY10_DATA_LEN 0x08U +#define MODE_SENSE10_DATA_LEN 0x08U +#define MODE_SENSE6_DATA_LEN 0x04U +#define READ_TOC_CMD_LEN 0x14U +#define REQUEST_SENSE_DATA_LEN 0x12U +#define STANDARD_INQUIRY_DATA_LEN 0x24U +#define BLKVFY 0x04U + +enum sense_state { + NO_SENSE = 0U, + RECOVERED_ERROR, + NOT_READY, + MEDIUM_ERROR, + HARDWARE_ERROR, + ILLEGAL_REQUEST, + UNIT_ATTENTION, + DATA_PROTECT, + BLANK_CHECK, + VENDOR_SPECIFIC, + COPY_ABORTED, + ABORTED_COMMAND, + RESERVED, + VOLUME_OVERFLOW, + MISCOMPARE +}; + +typedef struct { + uint8_t SenseKey; + uint32_t Information; + uint8_t ASC; + uint8_t ASCQ; +} msc_scsi_sense; + +#endif /* __MSC_SCSI_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/usb_msc.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/usb_msc.h new file mode 100644 index 0000000..14c3053 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/msc/usb_msc.h @@ -0,0 +1,68 @@ +/*! + \file usb_msc.h + \brief definitions for the USB MSC class + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USB_MSC_H +#define __USB_MSC_H + +#include "usb_ch9_std.h" + +/* mass storage device class code */ +#define USB_CLASS_MSC 0x08U + +/* mass storage subclass code */ +#define USB_MSC_SUBCLASS_RBC 0x01U +#define USB_MSC_SUBCLASS_ATAPI 0x02U +#define USB_MSC_SUBCLASS_UFI 0x04U +#define USB_MSC_SUBCLASS_SCSI 0x06U +#define USB_MSC_SUBCLASS_LOCKABLE 0x07U +#define USB_MSC_SUBCLASS_IEEE1667 0x08U + +/* mass storage interface class control protocol codes */ +#define USB_MSC_PROTOCOL_CBI 0x00U +#define USB_MSC_PROTOCOL_CBI_ALT 0x01U +#define USB_MSC_PROTOCOL_BBB 0x50U + +/* mass storage request codes */ +#define USB_MSC_REQ_CODES_ADSC 0x00U +#define USB_MSC_REQ_CODES_GET 0xFCU +#define USB_MSC_REQ_CODES_PUT 0xFDU +#define USB_MSC_REQ_CODES_GML 0xFEU +#define USB_MSC_REQ_CODES_BOMSR 0xFFU + +#define BBB_GET_MAX_LUN 0xFEU +#define BBB_RESET 0xFFU + +#define SCSI_CMD_LENGTH 16U + +#endif /* __USB_MSC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/rndis/usb_rndis.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/rndis/usb_rndis.h new file mode 100644 index 0000000..9696e26 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/class/rndis/usb_rndis.h @@ -0,0 +1,160 @@ +/*! + \file usb_cdc.h + \brief the header file of communication device class standard + + \version 2018-10-08, V1.0.0, firmware for GD32 USBFS&USBHS +*/ + +/* + Copyright (c) 2018, GigaDevice Semiconductor Inc. + + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + 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 the copyright holder 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 __USB_CDC_H +#define __USB_CDC_H + +#include "usb_ch9_std.h" + +/* communications device class code */ +#define USB_CLASS_WIRELESS_CTR 0xE0U + +/* data interface class code */ +#define USB_CLASS_DATA 0x0AU + +#define USB_DESCTYPE_CDC_ACM 0x21U +#define USB_DESCTYPE_CS_INTERFACE 0x24U + +#define USB_RNDIS_CONFIG_DESC_SIZE 0x43U + +/* class-specific notification codes for pstn subclasses */ +#define USB_CDC_NOTIFY_SERIAL_STATE 0x20U + +/* class-specific request codes */ +#define SEND_ENCAPSULATED_COMMAND 0x00U +#define GET_ENCAPSULATED_RESPONSE 0x01U +#define SET_COMM_FEATURE 0x02U +#define GET_COMM_FEATURE 0x03U +#define CLEAR_COMM_FEATURE 0x04U + +#define SET_AUX_LINE_STATE 0x10U +#define SET_HOOK_STATE 0x11U +#define PULSE_SETUP 0x12U +#define SEND_PULSE 0x13U +#define SET_PULSE_TIME 0x14U +#define RING_AUX_JACK 0x15U + +#define SET_LINE_CODING 0x20U +#define GET_LINE_CODING 0x21U +#define SET_CONTROL_LINE_STATE 0x22U +#define SEND_BREAK 0x23U +#define NO_CMD 0xFFU + +#define SET_RINGER_PARMS 0x30U +#define GET_RINGER_PARMS 0x31U +#define SET_OPERATION_PARMS 0x32U +#define GET_OPERATION_PARMS 0x33U +#define SET_LINE_PARMS 0x34U +#define GET_LINE_PARMS 0x35U +#define DIAL_DIGITS 0x36U +#define SET_UNIT_PARAMETER 0x37U +#define GET_UNIT_PARAMETER 0x38U +#define CLEAR_UNIT_PARAMETER 0x39U +#define GET_PROFILE 0x3AU + +#define SET_ETHERNET_MULTICAST_FILTERS 0x40U +#define SET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x41U +#define GET_ETHERNET_POWER_MANAGEMENT_PATTERN FILTER 0x42U +#define SET_ETHERNET_PACKET_FILTER 0x43U +#define GET_ETHERNET_STATISTIC 0x44U + +#define SET_ATM_DATA_FORMAT 0x50U +#define GET_ATM_DEVICE_STATISTICS 0x51U +#define SET_ATM_DEFAULT_VC 0x52U +#define GET_ATM_VC_STATISTICS 0x53U + +#pragma pack(1) + +/* cdc acm line coding structure */ +typedef struct { + uint32_t dwDTERate; /*!< data terminal rate */ + uint8_t bCharFormat; /*!< stop bits */ + uint8_t bParityType; /*!< parity */ + uint8_t bDataBits; /*!< data bits */ +} acm_line; + +/* notification structure */ +typedef struct { + uint8_t bmRequestType; /*!< type of request */ + uint8_t bNotification; /*!< communication interface class notifications */ + uint16_t wValue; /*!< value of notification */ + uint16_t wIndex; /*!< index of interface */ + uint16_t wLength; /*!< length of notification data */ +} acm_notification; + +typedef struct { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: header function descriptor */ + uint16_t bcdCDC; /*!< bcdCDC: low byte of spec release number (CDC1.10) */ +} usb_desc_header_func; + +typedef struct { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: call management function descriptor */ + uint8_t bmCapabilities; /*!< bmCapabilities: D0 is reset, D1 is ignored */ + uint8_t bDataInterface; /*!< bDataInterface: 1 interface used for call management */ +} usb_desc_call_managment_func; + +typedef struct { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: abstract control management descriptor */ + uint8_t bmCapabilities; /*!< bmCapabilities: D1 */ +} usb_desc_acm_func; + +typedef struct { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint8_t bDescriptorSubtype; /*!< bDescriptorSubtype: union function descriptor */ + uint8_t bMasterInterface; /*!< bMasterInterface: communication class interface */ + uint8_t bSlaveInterface0; /*!< bSlaveInterface0: data class interface */ +} usb_desc_union_func; + +#pragma pack() + +typedef struct { + usb_desc_config config; + usb_desc_itf cmd_itf; + usb_desc_header_func rndis_header; + usb_desc_call_managment_func rndis_call_managment; + usb_desc_acm_func rndis_acm; + usb_desc_union_func rndis_union; + usb_desc_ep rndis_cmd_endpoint; + usb_desc_itf rndis_data_interface; + usb_desc_ep rndis_out_endpoint; + usb_desc_ep rndis_in_endpoint; +} usb_rndis_desc_config_set; + +#endif /* __USB_CDC_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/common/usb_ch9_std.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/common/usb_ch9_std.h new file mode 100644 index 0000000..d881eab --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/drivers/GD32F5xx_usb_library/ustd/common/usb_ch9_std.h @@ -0,0 +1,248 @@ +/*! + \file usb_ch9_std.h + \brief USB 2.0 standard defines + + \version 2023-12-20, V1.0.0, firmware for GD32F5xx +*/ + +/* + Copyright (c) 2023, GigaDevice Semiconductor Inc. + + 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 the copyright holder 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 __USB_CH9_STD_H +#define __USB_CH9_STD_H + +#include "usb_conf.h" + +#define USB_DEV_QUALIFIER_DESC_LEN 0x0AU /*!< USB device qualifier descriptor length */ +#define USB_DEV_DESC_LEN 0x12U /*!< USB device descriptor length */ +#define USB_CFG_DESC_LEN 0x09U /*!< USB configuration descriptor length */ +#define USB_ITF_DESC_LEN 0x09U /*!< USB interface descriptor length */ +#define USB_EP_DESC_LEN 0x07U /*!< USB endpoint descriptor length */ +#define USB_IAD_DESC_LEN 0x08U /*!< USB IAD descriptor length */ +#define USB_OTG_DESC_LEN 0x03U /*!< USB device OTG descriptor length */ + +#define USB_SETUP_PACKET_LEN 0x08U /*!< USB setup packet length */ + +/* bit 7 of bmRequestType: data phase transfer direction */ +#define USB_TRX_MASK 0x80U /*!< USB transfer direction mask */ +#define USB_TRX_OUT 0x00U /*!< USB transfer OUT direction */ +#define USB_TRX_IN 0x80U /*!< USB transfer IN direction */ + +/* bit 6..5 of bmRequestType: request type */ +#define USB_REQTYPE_STRD 0x00U /*!< USB standard request */ +#define USB_REQTYPE_CLASS 0x20U /*!< USB class request */ +#define USB_REQTYPE_VENDOR 0x40U /*!< USB vendor request */ +#define USB_REQTYPE_MASK 0x60U /*!< USB request mask */ + +#define USBD_BUS_POWERED 0x00U /*!< USB bus power supply */ +#define USBD_SELF_POWERED 0x01U /*!< USB self power supply */ + +#define USB_STATUS_REMOTE_WAKEUP 2U /*!< USB is in remote wakeup status */ +#define USB_STATUS_SELF_POWERED 1U /*!< USB is in self powered status */ + +/* bit 4..0 of bmRequestType: recipient type */ +enum _usb_recp_type { + USB_RECPTYPE_DEV = 0x0U, /*!< USB device request type */ + USB_RECPTYPE_ITF = 0x1U, /*!< USB interface request type */ + USB_RECPTYPE_EP = 0x2U, /*!< USB endpoint request type */ + USB_RECPTYPE_MASK = 0x3U /*!< USB request type mask */ +}; + +/* bRequest value */ +enum _usb_request { + USB_GET_STATUS = 0x0U, /*!< USB get status request */ + USB_CLEAR_FEATURE = 0x1U, /*!< USB clear feature request */ + USB_RESERVED2 = 0x2U, + USB_SET_FEATURE = 0x3U, /*!< USB set feature request */ + USB_RESERVED4 = 0x4U, + USB_SET_ADDRESS = 0x5U, /*!< USB set address request */ + USB_GET_DESCRIPTOR = 0x6U, /*!< USB get descriptor request */ + USB_SET_DESCRIPTOR = 0x7U, /*!< USB set descriptor request */ + USB_GET_CONFIGURATION = 0x8U, /*!< USB get configuration request */ + USB_SET_CONFIGURATION = 0x9U, /*!< USB set configuration request */ + USB_GET_INTERFACE = 0xAU, /*!< USB get interface request */ + USB_SET_INTERFACE = 0xBU, /*!< USB set interface request */ + USB_SYNCH_FRAME = 0xCU /*!< USB synchronize frame request */ +}; + +/* descriptor types of USB specifications */ +enum _usb_desctype { + USB_DESCTYPE_DEV = 0x1U, /*!< USB device descriptor type */ + USB_DESCTYPE_CONFIG = 0x2U, /*!< USB configuration descriptor type */ + USB_DESCTYPE_STR = 0x3U, /*!< USB string descriptor type */ + USB_DESCTYPE_ITF = 0x4U, /*!< USB interface descriptor type */ + USB_DESCTYPE_EP = 0x5U, /*!< USB endpoint descriptor type */ + USB_DESCTYPE_DEV_QUALIFIER = 0x6U, /*!< USB device qualifier descriptor type */ + USB_DESCTYPE_OTHER_SPD_CONFIG = 0x7U, /*!< USB other speed configuration descriptor type */ + USB_DESCTYPE_ITF_POWER = 0x8U, /*!< USB interface power descriptor type */ + USB_DESCTYPE_IAD = 0xBU, /*!< USB interface association descriptor type */ + USB_DESCTYPE_BOS = 0xFU /*!< USB BOS descriptor type */ +}; + +/* USB Endpoint Descriptor bmAttributes bit definitions */ +/* bits 1..0 : transfer type */ +enum _usbx_type { + USB_EP_ATTR_CTL = 0x0U, /*!< USB control transfer type */ + USB_EP_ATTR_ISO = 0x1U, /*!< USB Isochronous transfer type */ + USB_EP_ATTR_BULK = 0x2U, /*!< USB Bulk transfer type */ + USB_EP_ATTR_INT = 0x3U /*!< USB Interrupt transfer type */ +}; + +/* bits 3..2 : Sync type (only if ISOCHRONOUS) */ +#define USB_EP_ATTR_NOSYNC 0x00U /*!< No Synchronization */ +#define USB_EP_ATTR_ASYNC 0x04U /*!< Asynchronous */ +#define USB_EP_ATTR_ADAPTIVE 0x08U /*!< Adaptive */ +#define USB_EP_ATTR_SYNC 0x0CU /*!< Synchronous */ +#define USB_EP_ATTR_SYNCTYPE 0x0CU /*!< Synchronous type */ + +/* bits 5..4 : usage type (only if ISOCHRONOUS) */ +#define USB_EP_ATTR_DATA 0x00U /*!< Data endpoint */ +#define USB_EP_ATTR_FEEDBACK 0x10U /*!< Feedback endpoint */ +#define USB_EP_ATTR_IMPLICIT_FEEDBACK_DATA 0x20U /*!< Implicit feedback Data endpoint */ +#define USB_EP_ATTR_USAGETYPE 0x30U /*!< Usage type */ + +/* endpoint max packet size bits12..11 */ +#define USB_EP_MPS_ADD_0 (0x00 << 11) /*!< None(1 transaction per microframe */ +#define USB_EP_MPS_ADD_1 (0x01 << 11) /*!< 1 additional(2 transaction per microframe */ +#define USB_EP_MPS_ADD_2 (0x02 << 11) /*!< 2 additional(3 transaction per microframe */ + +#define FEATURE_SELECTOR_EP 0x00U /*!< USB endpoint feature selector */ +#define FEATURE_SELECTOR_DEV 0x01U /*!< USB device feature selector */ +#define FEATURE_SELECTOR_REMOTEWAKEUP 0x01U /*!< USB feature selector remote wakeup */ + +#define BYTE_SWAP(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \ + (uint16_t)(((uint16_t)(*(((uint8_t *)(addr)) + 1U))) << 8U)) + +#define BYTE_LOW(x) ((uint8_t)((x) & 0x00FFU)) +#define BYTE_HIGH(x) ((uint8_t)(((x) & 0xFF00U) >> 8U)) + +#define USB_MIN(a, b) (((a) < (b)) ? (a) : (b)) + +#define USB_DEFAULT_CONFIG 0U + +/* USB classes */ +#define USB_CLASS_HID 0x03U /*!< USB HID class */ +#define USB_CLASS_MSC 0x08U /*!< USB MSC class */ + +/* use the following values when USB host need to get descriptor */ +#define USBH_DESC(x) (((x)<< 8U) & 0xFF00U) + +/* as per USB specs 9.2.6.4 :standard request with data request timeout: 5sec + standard request with no data stage timeout : 50ms */ +#define DATA_STAGE_TIMEOUT 5000U /*!< USB data stage timeout*/ +#define NODATA_STAGE_TIMEOUT 50U /*!< USB no data stage timeout*/ + +#pragma pack(1) + +/* USB standard device request structure */ +typedef struct _usb_req { + uint8_t bmRequestType; /*!< type of request */ + uint8_t bRequest; /*!< request of setup packet */ + uint16_t wValue; /*!< value of setup packet */ + uint16_t wIndex; /*!< index of setup packet */ + uint16_t wLength; /*!< length of setup packet */ +} usb_req; + +/* USB setup packet define */ +typedef union _usb_setup { + uint8_t data[8]; + + usb_req req; +} usb_setup; + +/* USB descriptor defines */ + +typedef struct _usb_desc_header { + uint8_t bLength; /*!< size of the descriptor */ + uint8_t bDescriptorType; /*!< type of the descriptor */ +} usb_desc_header; + +typedef struct _usb_desc_dev { + usb_desc_header header; /*!< descriptor header, including type and size */ + + uint16_t bcdUSB; /*!< BCD of the supported USB specification */ + uint8_t bDeviceClass; /*!< USB device class */ + uint8_t bDeviceSubClass; /*!< USB device subclass */ + uint8_t bDeviceProtocol; /*!< USB device protocol */ + uint8_t bMaxPacketSize0; /*!< size of the control (address 0) endpoint's bank in bytes */ + uint16_t idVendor; /*!< vendor ID for the USB product */ + uint16_t idProduct; /*!< unique product ID for the USB product */ + uint16_t bcdDevice; /*!< product release (version) number */ + uint8_t iManufacturer; /*!< string index for the manufacturer's name */ + uint8_t iProduct; /*!< string index for the product name/details */ + uint8_t iSerialNumber; /*!< string index for the product's globally unique hexadecimal serial number */ + uint8_t bNumberConfigurations; /*!< total number of configurations supported by the device */ +} usb_desc_dev; + +typedef struct _usb_desc_config { + usb_desc_header header; /*!< descriptor header, including type and size */ + + uint16_t wTotalLength; /*!< size of the configuration descriptor header,and all sub descriptors inside the configuration */ + uint8_t bNumInterfaces; /*!< total number of interfaces in the configuration */ + uint8_t bConfigurationValue; /*!< configuration index of the current configuration */ + uint8_t iConfiguration; /*!< index of a string descriptor describing the configuration */ + uint8_t bmAttributes; /*!< configuration attributes */ + uint8_t bMaxPower; /*!< maximum power consumption of the device while in the current configuration */ +} usb_desc_config; + +typedef struct _usb_desc_itf { + usb_desc_header header; /*!< descriptor header, including type and size */ + + uint8_t bInterfaceNumber; /*!< index of the interface in the current configuration */ + uint8_t bAlternateSetting; /*!< alternate setting for the interface number */ + uint8_t bNumEndpoints; /*!< total number of endpoints in the interface */ + uint8_t bInterfaceClass; /*!< interface class ID */ + uint8_t bInterfaceSubClass; /*!< interface subclass ID */ + uint8_t bInterfaceProtocol; /*!< interface protocol ID */ + uint8_t iInterface; /*!< index of the string descriptor describing the interface */ +} usb_desc_itf; + +typedef struct _usb_desc_ep { + usb_desc_header header; /*!< descriptor header, including type and size. */ + + uint8_t bEndpointAddress; /*!< logical address of the endpoint */ + uint8_t bmAttributes; /*!< endpoint attributes */ + uint16_t wMaxPacketSize; /*!< size of the endpoint bank, in bytes */ + uint8_t bInterval; /*!< polling interval in milliseconds for the endpoint if it is an INTERRUPT or ISOCHRONOUS type */ +} usb_desc_ep; + +typedef struct _usb_desc_LANGID { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint16_t wLANGID; /*!< LANGID code */ +} usb_desc_LANGID; + +typedef struct _usb_desc_str { + usb_desc_header header; /*!< descriptor header, including type and size. */ + uint16_t unicode_string[128]; /*!< unicode string data */ +} usb_desc_str; + +#pragma pack() + +/* compute string descriptor length */ +#define USB_STRING_LEN(unicode_chars) (sizeof(usb_desc_header) + ((unicode_chars) << 1U)) + +#endif /* __USB_CH9_STD_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/hal/hal_uart.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/hal/hal_uart.c new file mode 100644 index 0000000..b653588 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/hal/hal_uart.c @@ -0,0 +1,145 @@ +/** + ******************************************************************** + * @file psdk_hal.c + * @version V2.0.0 + * @date 2019/07/01 + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Includes ------------------------------------------------------------------*/ +#include "hal_uart.h" +#include "dji_platform.h" +#include "usb_device.h" +#include "uart.h" +#include "cdc_acm_core.h" + +/* Private constants ---------------------------------------------------------*/ +#define COMMUNICATION_UART_NUM UART_NUM_1 +#define USE_NATIVE_UART_ON_EPORT_V2 (0) + +/* Private types -------------------------------------------------------------*/ +typedef enum { + USER_UART_NUM0 = 0, + USER_UART_NUM1 = 1, +} T_UserUartNum; + +typedef struct { + T_UserUartNum uartNum; +} T_UartHandleStruct; + +/* Private functions declaration ---------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle) +{ + T_UartHandleStruct *uartHandleStruct; + + uartHandleStruct = pvPortMalloc(sizeof(T_UartHandleStruct)); + if (uartHandleStruct == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED; + } + + if (uartNum == DJI_HAL_UART_NUM_0) { + uartHandleStruct->uartNum = USER_UART_NUM0; +#if USE_NATIVE_UART_ON_EPORT_V2 + UART_Init(COMMUNICATION_UART_NUM, baudRate); +#endif + } else if (uartNum == DJI_HAL_UART_NUM_1) { + uartHandleStruct->uartNum = USER_UART_NUM1; + } + + *uartHandle = uartHandleStruct; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle) +{ + vPortFree(uartHandle); + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen) +{ + T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle; + int32_t ret; + + if (uartHandleStruct->uartNum == USER_UART_NUM0) { +#if USE_NATIVE_UART_ON_EPORT_V2 + *realLen = UART_Write(COMMUNICATION_UART_NUM, buf, len); +#else + USBD_CDC_WriteData(buf, len, realLen); +#endif + } else if (uartHandleStruct->uartNum == USER_UART_NUM1) { + //This platform cannot be used on M300 OSDK Port, so no need adapter usb-host cdc drivers. + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen) +{ + T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle; + int32_t ret; + + if (uartHandleStruct->uartNum == USER_UART_NUM0) { +#if USE_NATIVE_UART_ON_EPORT_V2 + *realLen = UART_Read(COMMUNICATION_UART_NUM, buf, len); +#else + USBD_CDC_ReadData(buf, len, realLen); +#endif + } else if (uartHandleStruct->uartNum == USER_UART_NUM1) { + //This platform cannot be used on M300 OSDK Port, so no need adapter usb-host cdc drivers. + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status) +{ + if (uartNum == DJI_HAL_UART_NUM_0) { + status->isConnect = true; + } else if (uartNum == DJI_HAL_UART_NUM_1) { + status->isConnect = false; + } else { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo) +{ + + if (deviceInfo == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + deviceInfo->vid = ((usb_desc_dev *)(cdc_desc.dev_desc))->idVendor; + deviceInfo->pid = ((usb_desc_dev *)(cdc_desc.dev_desc))->idProduct; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + +/* Private functions definition-----------------------------------------------*/ + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/hal/hal_uart.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/hal/hal_uart.h new file mode 100644 index 0000000..c3fd8dd --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/hal/hal_uart.h @@ -0,0 +1,58 @@ +/** + ******************************************************************** + * @file hal.h + * @version V2.0.0 + * @date 2019/8/30 + * @brief This is the header file for "hal.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef HAL_H +#define HAL_H + +/* Includes ------------------------------------------------------------------*/ +//#include "dji_platform.h" +#include "stdint.h" +#include "dji_platform.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ + +/* Exported types ------------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle); +T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle); +T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); +T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status); +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo); + +#ifdef __cplusplus +} +#endif + +#endif // HAL_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/croutine.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/croutine.c new file mode 100644 index 0000000..bb049a4 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/croutine.c @@ -0,0 +1,353 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +#include "FreeRTOS.h" +#include "task.h" +#include "croutine.h" + +/* Remove the whole file is co-routines are not being used. */ +#if( configUSE_CO_ROUTINES != 0 ) + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + + +/* Lists for ready and blocked co-routines. --------------------*/ +static List_t pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ +static List_t xDelayedCoRoutineList1; /*< Delayed co-routines. */ +static List_t xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ +static List_t * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ +static List_t * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ +static List_t xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ + +/* Other file private variables. --------------------------------*/ +CRCB_t * pxCurrentCoRoutine = NULL; +static UBaseType_t uxTopCoRoutineReadyPriority = 0; +static TickType_t xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; + +/* The initial state of the co-routine when it is created. */ +#define corINITIAL_STATE ( 0 ) + +/* + * Place the co-routine represented by pxCRCB into the appropriate ready queue + * for the priority. It is inserted at the end of the list. + * + * This macro accesses the co-routine ready lists and therefore must not be + * used from within an ISR. + */ +#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ +{ \ + if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ + { \ + uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ + } \ + vListInsertEnd( ( List_t * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ +} + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first co-routine. + */ +static void prvInitialiseCoRoutineLists( void ); + +/* + * Co-routines that are readied by an interrupt cannot be placed directly into + * the ready lists (there is no mutual exclusion). Instead they are placed in + * in the pending ready list in order that they can later be moved to the ready + * list by the co-routine scheduler. + */ +static void prvCheckPendingReadyList( void ); + +/* + * Macro that looks at the list of co-routines that are currently delayed to + * see if any require waking. + * + * Co-routines are stored in the queue in the order of their wake time - + * meaning once one co-routine has been found whose timer has not expired + * we need not look any further down the list. + */ +static void prvCheckDelayedList( void ); + +/*-----------------------------------------------------------*/ + +BaseType_t xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, UBaseType_t uxPriority, UBaseType_t uxIndex ) +{ +BaseType_t xReturn; +CRCB_t *pxCoRoutine; + + /* Allocate the memory that will store the co-routine control block. */ + pxCoRoutine = ( CRCB_t * ) pvPortMalloc( sizeof( CRCB_t ) ); + if( pxCoRoutine ) + { + /* If pxCurrentCoRoutine is NULL then this is the first co-routine to + be created and the co-routine data structures need initialising. */ + if( pxCurrentCoRoutine == NULL ) + { + pxCurrentCoRoutine = pxCoRoutine; + prvInitialiseCoRoutineLists(); + } + + /* Check the priority is within limits. */ + if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) + { + uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; + } + + /* Fill out the co-routine control block from the function parameters. */ + pxCoRoutine->uxState = corINITIAL_STATE; + pxCoRoutine->uxPriority = uxPriority; + pxCoRoutine->uxIndex = uxIndex; + pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; + + /* Initialise all the other co-routine control block parameters. */ + vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); + vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); + + /* Set the co-routine control block as a link back from the ListItem_t. + This is so we can get back to the containing CRCB from a generic item + in a list. */ + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), ( ( TickType_t ) configMAX_CO_ROUTINE_PRIORITIES - ( TickType_t ) uxPriority ) ); + + /* Now the co-routine has been initialised it can be added to the ready + list at the correct priority. */ + prvAddCoRoutineToReadyQueue( pxCoRoutine ); + + xReturn = pdPASS; + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineAddToDelayedList( TickType_t xTicksToDelay, List_t *pxEventList ) +{ +TickType_t xTimeToWake; + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xCoRoutineTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + ( void ) uxListRemove( ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xCoRoutineTickCount ) + { + /* Wake time has overflowed. Place this item in the + overflow list. */ + vListInsert( ( List_t * ) pxOverflowDelayedCoRoutineList, ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the + current block list. */ + vListInsert( ( List_t * ) pxDelayedCoRoutineList, ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + + if( pxEventList ) + { + /* Also add the co-routine to an event list. If this is done then the + function must be called with interrupts disabled. */ + vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckPendingReadyList( void ) +{ + /* Are there any co-routines waiting to get moved to the ready list? These + are co-routines that have been readied by an ISR. The ISR cannot access + the ready lists itself. */ + while( listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) == pdFALSE ) + { + CRCB_t *pxUnblockedCRCB; + + /* The pending ready list can be accessed by an ISR. */ + portDISABLE_INTERRUPTS(); + { + pxUnblockedCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); + ( void ) uxListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + } + portENABLE_INTERRUPTS(); + + ( void ) uxListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); + prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckDelayedList( void ) +{ +CRCB_t *pxCRCB; + + xPassedTicks = xTaskGetTickCount() - xLastTickCount; + while( xPassedTicks ) + { + xCoRoutineTickCount++; + xPassedTicks--; + + /* If the tick count has overflowed we need to swap the ready lists. */ + if( xCoRoutineTickCount == 0 ) + { + List_t * pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. If there are + any items in pxDelayedCoRoutineList here then there is an error! */ + pxTemp = pxDelayedCoRoutineList; + pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; + pxOverflowDelayedCoRoutineList = pxTemp; + } + + /* See if this tick has made a timeout expire. */ + while( listLIST_IS_EMPTY( pxDelayedCoRoutineList ) == pdFALSE ) + { + pxCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ); + + if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) + { + /* Timeout not yet expired. */ + break; + } + + portDISABLE_INTERRUPTS(); + { + /* The event could have occurred just before this critical + section. If this is the case then the generic list item will + have been moved to the pending ready list and the following + line is still valid. Also the pvContainer parameter will have + been set to NULL so the following lines are also valid. */ + ( void ) uxListRemove( &( pxCRCB->xGenericListItem ) ); + + /* Is the co-routine waiting on an event also? */ + if( pxCRCB->xEventListItem.pxContainer ) + { + ( void ) uxListRemove( &( pxCRCB->xEventListItem ) ); + } + } + portENABLE_INTERRUPTS(); + + prvAddCoRoutineToReadyQueue( pxCRCB ); + } + } + + xLastTickCount = xCoRoutineTickCount; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineSchedule( void ) +{ + /* See if any co-routines readied by events need moving to the ready lists. */ + prvCheckPendingReadyList(); + + /* See if any delayed co-routines have timed out. */ + prvCheckDelayedList(); + + /* Find the highest priority queue that contains ready co-routines. */ + while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) + { + if( uxTopCoRoutineReadyPriority == 0 ) + { + /* No more co-routines to check. */ + return; + } + --uxTopCoRoutineReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines + of the same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); + + /* Call the co-routine. */ + ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); + + return; +} +/*-----------------------------------------------------------*/ + +static void prvInitialiseCoRoutineLists( void ) +{ +UBaseType_t uxPriority; + + for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( List_t * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); + } + + vListInitialise( ( List_t * ) &xDelayedCoRoutineList1 ); + vListInitialise( ( List_t * ) &xDelayedCoRoutineList2 ); + vListInitialise( ( List_t * ) &xPendingReadyCoRoutineList ); + + /* Start with pxDelayedCoRoutineList using list1 and the + pxOverflowDelayedCoRoutineList using list2. */ + pxDelayedCoRoutineList = &xDelayedCoRoutineList1; + pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; +} +/*-----------------------------------------------------------*/ + +BaseType_t xCoRoutineRemoveFromEventList( const List_t *pxEventList ) +{ +CRCB_t *pxUnblockedCRCB; +BaseType_t xReturn; + + /* This function is called from within an interrupt. It can only access + event lists and the pending ready list. This function assumes that a + check has already been made to ensure pxEventList is not empty. */ + pxUnblockedCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + ( void ) uxListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + vListInsertEnd( ( List_t * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); + + if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} + +#endif /* configUSE_CO_ROUTINES == 0 */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/event_groups.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/event_groups.c new file mode 100644 index 0000000..9c8f4db --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/event_groups.c @@ -0,0 +1,753 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* Standard includes. */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* FreeRTOS includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "timers.h" +#include "event_groups.h" + +/* Lint e961, e750 and e9021 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750 !e9021 See comment above. */ + +/* The following bit fields convey control information in a task's event list +item value. It is important they don't clash with the +taskEVENT_LIST_ITEM_VALUE_IN_USE definition. */ +#if configUSE_16_BIT_TICKS == 1 + #define eventCLEAR_EVENTS_ON_EXIT_BIT 0x0100U + #define eventUNBLOCKED_DUE_TO_BIT_SET 0x0200U + #define eventWAIT_FOR_ALL_BITS 0x0400U + #define eventEVENT_BITS_CONTROL_BYTES 0xff00U +#else + #define eventCLEAR_EVENTS_ON_EXIT_BIT 0x01000000UL + #define eventUNBLOCKED_DUE_TO_BIT_SET 0x02000000UL + #define eventWAIT_FOR_ALL_BITS 0x04000000UL + #define eventEVENT_BITS_CONTROL_BYTES 0xff000000UL +#endif + +typedef struct EventGroupDef_t +{ + EventBits_t uxEventBits; + List_t xTasksWaitingForBits; /*< List of tasks waiting for a bit to be set. */ + + #if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxEventGroupNumber; + #endif + + #if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + uint8_t ucStaticallyAllocated; /*< Set to pdTRUE if the event group is statically allocated to ensure no attempt is made to free the memory. */ + #endif +} EventGroup_t; + +/*-----------------------------------------------------------*/ + +/* + * Test the bits set in uxCurrentEventBits to see if the wait condition is met. + * The wait condition is defined by xWaitForAllBits. If xWaitForAllBits is + * pdTRUE then the wait condition is met if all the bits set in uxBitsToWaitFor + * are also set in uxCurrentEventBits. If xWaitForAllBits is pdFALSE then the + * wait condition is met if any of the bits set in uxBitsToWait for are also set + * in uxCurrentEventBits. + */ +static BaseType_t prvTestWaitCondition( const EventBits_t uxCurrentEventBits, const EventBits_t uxBitsToWaitFor, const BaseType_t xWaitForAllBits ) PRIVILEGED_FUNCTION; + +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + EventGroupHandle_t xEventGroupCreateStatic( StaticEventGroup_t *pxEventGroupBuffer ) + { + EventGroup_t *pxEventBits; + + /* A StaticEventGroup_t object must be provided. */ + configASSERT( pxEventGroupBuffer ); + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticEventGroup_t equals the size of the real + event group structure. */ + volatile size_t xSize = sizeof( StaticEventGroup_t ); + configASSERT( xSize == sizeof( EventGroup_t ) ); + } /*lint !e529 xSize is referenced if configASSERT() is defined. */ + #endif /* configASSERT_DEFINED */ + + /* The user has provided a statically allocated event group - use it. */ + pxEventBits = ( EventGroup_t * ) pxEventGroupBuffer; /*lint !e740 !e9087 EventGroup_t and StaticEventGroup_t are deliberately aliased for data hiding purposes and guaranteed to have the same size and alignment requirement - checked by configASSERT(). */ + + if( pxEventBits != NULL ) + { + pxEventBits->uxEventBits = 0; + vListInitialise( &( pxEventBits->xTasksWaitingForBits ) ); + + #if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + { + /* Both static and dynamic allocation can be used, so note that + this event group was created statically in case the event group + is later deleted. */ + pxEventBits->ucStaticallyAllocated = pdTRUE; + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + + traceEVENT_GROUP_CREATE( pxEventBits ); + } + else + { + /* xEventGroupCreateStatic should only ever be called with + pxEventGroupBuffer pointing to a pre-allocated (compile time + allocated) StaticEventGroup_t variable. */ + traceEVENT_GROUP_CREATE_FAILED(); + } + + return pxEventBits; + } + +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + EventGroupHandle_t xEventGroupCreate( void ) + { + EventGroup_t *pxEventBits; + + /* Allocate the event group. Justification for MISRA deviation as + follows: pvPortMalloc() always ensures returned memory blocks are + aligned per the requirements of the MCU stack. In this case + pvPortMalloc() must return a pointer that is guaranteed to meet the + alignment requirements of the EventGroup_t structure - which (if you + follow it through) is the alignment requirements of the TickType_t type + (EventBits_t being of TickType_t itself). Therefore, whenever the + stack alignment requirements are greater than or equal to the + TickType_t alignment requirements the cast is safe. In other cases, + where the natural word size of the architecture is less than + sizeof( TickType_t ), the TickType_t variables will be accessed in two + or more reads operations, and the alignment requirements is only that + of each individual read. */ + pxEventBits = ( EventGroup_t * ) pvPortMalloc( sizeof( EventGroup_t ) ); /*lint !e9087 !e9079 see comment above. */ + + if( pxEventBits != NULL ) + { + pxEventBits->uxEventBits = 0; + vListInitialise( &( pxEventBits->xTasksWaitingForBits ) ); + + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + /* Both static and dynamic allocation can be used, so note this + event group was allocated statically in case the event group is + later deleted. */ + pxEventBits->ucStaticallyAllocated = pdFALSE; + } + #endif /* configSUPPORT_STATIC_ALLOCATION */ + + traceEVENT_GROUP_CREATE( pxEventBits ); + } + else + { + traceEVENT_GROUP_CREATE_FAILED(); /*lint !e9063 Else branch only exists to allow tracing and does not generate code if trace macros are not defined. */ + } + + return pxEventBits; + } + +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait ) +{ +EventBits_t uxOriginalBitValue, uxReturn; +EventGroup_t *pxEventBits = xEventGroup; +BaseType_t xAlreadyYielded; +BaseType_t xTimeoutOccurred = pdFALSE; + + configASSERT( ( uxBitsToWaitFor & eventEVENT_BITS_CONTROL_BYTES ) == 0 ); + configASSERT( uxBitsToWaitFor != 0 ); + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + vTaskSuspendAll(); + { + uxOriginalBitValue = pxEventBits->uxEventBits; + + ( void ) xEventGroupSetBits( xEventGroup, uxBitsToSet ); + + if( ( ( uxOriginalBitValue | uxBitsToSet ) & uxBitsToWaitFor ) == uxBitsToWaitFor ) + { + /* All the rendezvous bits are now set - no need to block. */ + uxReturn = ( uxOriginalBitValue | uxBitsToSet ); + + /* Rendezvous always clear the bits. They will have been cleared + already unless this is the only task in the rendezvous. */ + pxEventBits->uxEventBits &= ~uxBitsToWaitFor; + + xTicksToWait = 0; + } + else + { + if( xTicksToWait != ( TickType_t ) 0 ) + { + traceEVENT_GROUP_SYNC_BLOCK( xEventGroup, uxBitsToSet, uxBitsToWaitFor ); + + /* Store the bits that the calling task is waiting for in the + task's event list item so the kernel knows when a match is + found. Then enter the blocked state. */ + vTaskPlaceOnUnorderedEventList( &( pxEventBits->xTasksWaitingForBits ), ( uxBitsToWaitFor | eventCLEAR_EVENTS_ON_EXIT_BIT | eventWAIT_FOR_ALL_BITS ), xTicksToWait ); + + /* This assignment is obsolete as uxReturn will get set after + the task unblocks, but some compilers mistakenly generate a + warning about uxReturn being returned without being set if the + assignment is omitted. */ + uxReturn = 0; + } + else + { + /* The rendezvous bits were not set, but no block time was + specified - just return the current event bit value. */ + uxReturn = pxEventBits->uxEventBits; + xTimeoutOccurred = pdTRUE; + } + } + } + xAlreadyYielded = xTaskResumeAll(); + + if( xTicksToWait != ( TickType_t ) 0 ) + { + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The task blocked to wait for its required bits to be set - at this + point either the required bits were set or the block time expired. If + the required bits were set they will have been stored in the task's + event list item, and they should now be retrieved then cleared. */ + uxReturn = uxTaskResetEventItemValue(); + + if( ( uxReturn & eventUNBLOCKED_DUE_TO_BIT_SET ) == ( EventBits_t ) 0 ) + { + /* The task timed out, just return the current event bit value. */ + taskENTER_CRITICAL(); + { + uxReturn = pxEventBits->uxEventBits; + + /* Although the task got here because it timed out before the + bits it was waiting for were set, it is possible that since it + unblocked another task has set the bits. If this is the case + then it needs to clear the bits before exiting. */ + if( ( uxReturn & uxBitsToWaitFor ) == uxBitsToWaitFor ) + { + pxEventBits->uxEventBits &= ~uxBitsToWaitFor; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + xTimeoutOccurred = pdTRUE; + } + else + { + /* The task unblocked because the bits were set. */ + } + + /* Control bits might be set as the task had blocked should not be + returned. */ + uxReturn &= ~eventEVENT_BITS_CONTROL_BYTES; + } + + traceEVENT_GROUP_SYNC_END( xEventGroup, uxBitsToSet, uxBitsToWaitFor, xTimeoutOccurred ); + + /* Prevent compiler warnings when trace macros are not used. */ + ( void ) xTimeoutOccurred; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait ) +{ +EventGroup_t *pxEventBits = xEventGroup; +EventBits_t uxReturn, uxControlBits = 0; +BaseType_t xWaitConditionMet, xAlreadyYielded; +BaseType_t xTimeoutOccurred = pdFALSE; + + /* Check the user is not attempting to wait on the bits used by the kernel + itself, and that at least one bit is being requested. */ + configASSERT( xEventGroup ); + configASSERT( ( uxBitsToWaitFor & eventEVENT_BITS_CONTROL_BYTES ) == 0 ); + configASSERT( uxBitsToWaitFor != 0 ); + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + vTaskSuspendAll(); + { + const EventBits_t uxCurrentEventBits = pxEventBits->uxEventBits; + + /* Check to see if the wait condition is already met or not. */ + xWaitConditionMet = prvTestWaitCondition( uxCurrentEventBits, uxBitsToWaitFor, xWaitForAllBits ); + + if( xWaitConditionMet != pdFALSE ) + { + /* The wait condition has already been met so there is no need to + block. */ + uxReturn = uxCurrentEventBits; + xTicksToWait = ( TickType_t ) 0; + + /* Clear the wait bits if requested to do so. */ + if( xClearOnExit != pdFALSE ) + { + pxEventBits->uxEventBits &= ~uxBitsToWaitFor; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else if( xTicksToWait == ( TickType_t ) 0 ) + { + /* The wait condition has not been met, but no block time was + specified, so just return the current value. */ + uxReturn = uxCurrentEventBits; + xTimeoutOccurred = pdTRUE; + } + else + { + /* The task is going to block to wait for its required bits to be + set. uxControlBits are used to remember the specified behaviour of + this call to xEventGroupWaitBits() - for use when the event bits + unblock the task. */ + if( xClearOnExit != pdFALSE ) + { + uxControlBits |= eventCLEAR_EVENTS_ON_EXIT_BIT; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xWaitForAllBits != pdFALSE ) + { + uxControlBits |= eventWAIT_FOR_ALL_BITS; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Store the bits that the calling task is waiting for in the + task's event list item so the kernel knows when a match is + found. Then enter the blocked state. */ + vTaskPlaceOnUnorderedEventList( &( pxEventBits->xTasksWaitingForBits ), ( uxBitsToWaitFor | uxControlBits ), xTicksToWait ); + + /* This is obsolete as it will get set after the task unblocks, but + some compilers mistakenly generate a warning about the variable + being returned without being set if it is not done. */ + uxReturn = 0; + + traceEVENT_GROUP_WAIT_BITS_BLOCK( xEventGroup, uxBitsToWaitFor ); + } + } + xAlreadyYielded = xTaskResumeAll(); + + if( xTicksToWait != ( TickType_t ) 0 ) + { + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The task blocked to wait for its required bits to be set - at this + point either the required bits were set or the block time expired. If + the required bits were set they will have been stored in the task's + event list item, and they should now be retrieved then cleared. */ + uxReturn = uxTaskResetEventItemValue(); + + if( ( uxReturn & eventUNBLOCKED_DUE_TO_BIT_SET ) == ( EventBits_t ) 0 ) + { + taskENTER_CRITICAL(); + { + /* The task timed out, just return the current event bit value. */ + uxReturn = pxEventBits->uxEventBits; + + /* It is possible that the event bits were updated between this + task leaving the Blocked state and running again. */ + if( prvTestWaitCondition( uxReturn, uxBitsToWaitFor, xWaitForAllBits ) != pdFALSE ) + { + if( xClearOnExit != pdFALSE ) + { + pxEventBits->uxEventBits &= ~uxBitsToWaitFor; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + xTimeoutOccurred = pdTRUE; + } + taskEXIT_CRITICAL(); + } + else + { + /* The task unblocked because the bits were set. */ + } + + /* The task blocked so control bits may have been set. */ + uxReturn &= ~eventEVENT_BITS_CONTROL_BYTES; + } + traceEVENT_GROUP_WAIT_BITS_END( xEventGroup, uxBitsToWaitFor, xTimeoutOccurred ); + + /* Prevent compiler warnings when trace macros are not used. */ + ( void ) xTimeoutOccurred; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) +{ +EventGroup_t *pxEventBits = xEventGroup; +EventBits_t uxReturn; + + /* Check the user is not attempting to clear the bits used by the kernel + itself. */ + configASSERT( xEventGroup ); + configASSERT( ( uxBitsToClear & eventEVENT_BITS_CONTROL_BYTES ) == 0 ); + + taskENTER_CRITICAL(); + { + traceEVENT_GROUP_CLEAR_BITS( xEventGroup, uxBitsToClear ); + + /* The value returned is the event group value prior to the bits being + cleared. */ + uxReturn = pxEventBits->uxEventBits; + + /* Clear the bits. */ + pxEventBits->uxEventBits &= ~uxBitsToClear; + } + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 1 ) ) + + BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) + { + BaseType_t xReturn; + + traceEVENT_GROUP_CLEAR_BITS_FROM_ISR( xEventGroup, uxBitsToClear ); + xReturn = xTimerPendFunctionCallFromISR( vEventGroupClearBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToClear, NULL ); /*lint !e9087 Can't avoid cast to void* as a generic callback function not specific to this use case. Callback casts back to original type so safe. */ + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup ) +{ +UBaseType_t uxSavedInterruptStatus; +EventGroup_t const * const pxEventBits = xEventGroup; +EventBits_t uxReturn; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + uxReturn = pxEventBits->uxEventBits; + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return uxReturn; +} /*lint !e818 EventGroupHandle_t is a typedef used in other functions to so can't be pointer to const. */ +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) +{ +ListItem_t *pxListItem, *pxNext; +ListItem_t const *pxListEnd; +List_t const * pxList; +EventBits_t uxBitsToClear = 0, uxBitsWaitedFor, uxControlBits; +EventGroup_t *pxEventBits = xEventGroup; +BaseType_t xMatchFound = pdFALSE; + + /* Check the user is not attempting to set the bits used by the kernel + itself. */ + configASSERT( xEventGroup ); + configASSERT( ( uxBitsToSet & eventEVENT_BITS_CONTROL_BYTES ) == 0 ); + + pxList = &( pxEventBits->xTasksWaitingForBits ); + pxListEnd = listGET_END_MARKER( pxList ); /*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. */ + vTaskSuspendAll(); + { + traceEVENT_GROUP_SET_BITS( xEventGroup, uxBitsToSet ); + + pxListItem = listGET_HEAD_ENTRY( pxList ); + + /* Set the bits. */ + pxEventBits->uxEventBits |= uxBitsToSet; + + /* See if the new bit value should unblock any tasks. */ + while( pxListItem != pxListEnd ) + { + pxNext = listGET_NEXT( pxListItem ); + uxBitsWaitedFor = listGET_LIST_ITEM_VALUE( pxListItem ); + xMatchFound = pdFALSE; + + /* Split the bits waited for from the control bits. */ + uxControlBits = uxBitsWaitedFor & eventEVENT_BITS_CONTROL_BYTES; + uxBitsWaitedFor &= ~eventEVENT_BITS_CONTROL_BYTES; + + if( ( uxControlBits & eventWAIT_FOR_ALL_BITS ) == ( EventBits_t ) 0 ) + { + /* Just looking for single bit being set. */ + if( ( uxBitsWaitedFor & pxEventBits->uxEventBits ) != ( EventBits_t ) 0 ) + { + xMatchFound = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else if( ( uxBitsWaitedFor & pxEventBits->uxEventBits ) == uxBitsWaitedFor ) + { + /* All bits are set. */ + xMatchFound = pdTRUE; + } + else + { + /* Need all bits to be set, but not all the bits were set. */ + } + + if( xMatchFound != pdFALSE ) + { + /* The bits match. Should the bits be cleared on exit? */ + if( ( uxControlBits & eventCLEAR_EVENTS_ON_EXIT_BIT ) != ( EventBits_t ) 0 ) + { + uxBitsToClear |= uxBitsWaitedFor; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Store the actual event flag value in the task's event list + item before removing the task from the event list. The + eventUNBLOCKED_DUE_TO_BIT_SET bit is set so the task knows + that is was unblocked due to its required bits matching, rather + than because it timed out. */ + vTaskRemoveFromUnorderedEventList( pxListItem, pxEventBits->uxEventBits | eventUNBLOCKED_DUE_TO_BIT_SET ); + } + + /* Move onto the next list item. Note pxListItem->pxNext is not + used here as the list item may have been removed from the event list + and inserted into the ready/pending reading list. */ + pxListItem = pxNext; + } + + /* Clear any bits that matched when the eventCLEAR_EVENTS_ON_EXIT_BIT + bit was set in the control word. */ + pxEventBits->uxEventBits &= ~uxBitsToClear; + } + ( void ) xTaskResumeAll(); + + return pxEventBits->uxEventBits; +} +/*-----------------------------------------------------------*/ + +void vEventGroupDelete( EventGroupHandle_t xEventGroup ) +{ +EventGroup_t *pxEventBits = xEventGroup; +const List_t *pxTasksWaitingForBits = &( pxEventBits->xTasksWaitingForBits ); + + vTaskSuspendAll(); + { + traceEVENT_GROUP_DELETE( xEventGroup ); + + while( listCURRENT_LIST_LENGTH( pxTasksWaitingForBits ) > ( UBaseType_t ) 0 ) + { + /* Unblock the task, returning 0 as the event list is being deleted + and cannot therefore have any bits set. */ + configASSERT( pxTasksWaitingForBits->xListEnd.pxNext != ( const ListItem_t * ) &( pxTasksWaitingForBits->xListEnd ) ); + vTaskRemoveFromUnorderedEventList( pxTasksWaitingForBits->xListEnd.pxNext, eventUNBLOCKED_DUE_TO_BIT_SET ); + } + + #if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 0 ) ) + { + /* The event group can only have been allocated dynamically - free + it again. */ + vPortFree( pxEventBits ); + } + #elif( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + { + /* The event group could have been allocated statically or + dynamically, so check before attempting to free the memory. */ + if( pxEventBits->ucStaticallyAllocated == ( uint8_t ) pdFALSE ) + { + vPortFree( pxEventBits ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + } + ( void ) xTaskResumeAll(); +} +/*-----------------------------------------------------------*/ + +/* For internal use only - execute a 'set bits' command that was pended from +an interrupt. */ +void vEventGroupSetBitsCallback( void *pvEventGroup, const uint32_t ulBitsToSet ) +{ + ( void ) xEventGroupSetBits( pvEventGroup, ( EventBits_t ) ulBitsToSet ); /*lint !e9079 Can't avoid cast to void* as a generic timer callback prototype. Callback casts back to original type so safe. */ +} +/*-----------------------------------------------------------*/ + +/* For internal use only - execute a 'clear bits' command that was pended from +an interrupt. */ +void vEventGroupClearBitsCallback( void *pvEventGroup, const uint32_t ulBitsToClear ) +{ + ( void ) xEventGroupClearBits( pvEventGroup, ( EventBits_t ) ulBitsToClear ); /*lint !e9079 Can't avoid cast to void* as a generic timer callback prototype. Callback casts back to original type so safe. */ +} +/*-----------------------------------------------------------*/ + +static BaseType_t prvTestWaitCondition( const EventBits_t uxCurrentEventBits, const EventBits_t uxBitsToWaitFor, const BaseType_t xWaitForAllBits ) +{ +BaseType_t xWaitConditionMet = pdFALSE; + + if( xWaitForAllBits == pdFALSE ) + { + /* Task only has to wait for one bit within uxBitsToWaitFor to be + set. Is one already set? */ + if( ( uxCurrentEventBits & uxBitsToWaitFor ) != ( EventBits_t ) 0 ) + { + xWaitConditionMet = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* Task has to wait for all the bits in uxBitsToWaitFor to be set. + Are they set already? */ + if( ( uxCurrentEventBits & uxBitsToWaitFor ) == uxBitsToWaitFor ) + { + xWaitConditionMet = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + return xWaitConditionMet; +} +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 1 ) ) + + BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken ) + { + BaseType_t xReturn; + + traceEVENT_GROUP_SET_BITS_FROM_ISR( xEventGroup, uxBitsToSet ); + xReturn = xTimerPendFunctionCallFromISR( vEventGroupSetBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToSet, pxHigherPriorityTaskWoken ); /*lint !e9087 Can't avoid cast to void* as a generic callback function not specific to this use case. Callback casts back to original type so safe. */ + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if (configUSE_TRACE_FACILITY == 1) + + UBaseType_t uxEventGroupGetNumber( void* xEventGroup ) + { + UBaseType_t xReturn; + EventGroup_t const *pxEventBits = ( EventGroup_t * ) xEventGroup; /*lint !e9087 !e9079 EventGroupHandle_t is a pointer to an EventGroup_t, but EventGroupHandle_t is kept opaque outside of this file for data hiding purposes. */ + + if( xEventGroup == NULL ) + { + xReturn = 0; + } + else + { + xReturn = pxEventBits->uxEventGroupNumber; + } + + return xReturn; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vEventGroupSetNumber( void * xEventGroup, UBaseType_t uxEventGroupNumber ) + { + ( ( EventGroup_t * ) xEventGroup )->uxEventGroupNumber = uxEventGroupNumber; /*lint !e9087 !e9079 EventGroupHandle_t is a pointer to an EventGroup_t, but EventGroupHandle_t is kept opaque outside of this file for data hiding purposes. */ + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/FreeRTOS.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/FreeRTOS.h new file mode 100644 index 0000000..ffad825 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/FreeRTOS.h @@ -0,0 +1,1295 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 INC_FREERTOS_H +#define INC_FREERTOS_H + +/* + * Include the generic headers required for the FreeRTOS port being used. + */ +#include + +/* + * If stdint.h cannot be located then: + * + If using GCC ensure the -nostdint options is *not* being used. + * + Ensure the project's include path includes the directory in which your + * compiler stores stdint.h. + * + Set any compiler options necessary for it to support C99, as technically + * stdint.h is only mandatory with C99 (FreeRTOS does not require C99 in any + * other way). + * + The FreeRTOS download includes a simple stdint.h definition that can be + * used in cases where none is provided by the compiler. The files only + * contains the typedefs required to build FreeRTOS. Read the instructions + * in FreeRTOS/source/stdint.readme for more information. + */ +#include /* READ COMMENT ABOVE. */ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Application specific configuration options. */ +#include "FreeRTOSConfig.h" + +/* Basic FreeRTOS definitions. */ +#include "projdefs.h" + +/* Definitions specific to the port being used. */ +#include "portable.h" + +/* Must be defaulted before configUSE_NEWLIB_REENTRANT is used below. */ +#ifndef configUSE_NEWLIB_REENTRANT + #define configUSE_NEWLIB_REENTRANT 0 +#endif + +/* Required if struct _reent is used. */ +#if ( configUSE_NEWLIB_REENTRANT == 1 ) + #include +#endif +/* + * Check all the required application specific macros have been defined. + * These macros are application specific and (as downloaded) are defined + * within FreeRTOSConfig.h. + */ + +#ifndef configMINIMAL_STACK_SIZE + #error Missing definition: configMINIMAL_STACK_SIZE must be defined in FreeRTOSConfig.h. configMINIMAL_STACK_SIZE defines the size (in words) of the stack allocated to the idle task. Refer to the demo project provided for your port for a suitable value. +#endif + +#ifndef configMAX_PRIORITIES + #error Missing definition: configMAX_PRIORITIES must be defined in FreeRTOSConfig.h. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#if configMAX_PRIORITIES < 1 + #error configMAX_PRIORITIES must be defined to be greater than or equal to 1. +#endif + +#ifndef configUSE_PREEMPTION + #error Missing definition: configUSE_PREEMPTION must be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_IDLE_HOOK + #error Missing definition: configUSE_IDLE_HOOK must be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_TICK_HOOK + #error Missing definition: configUSE_TICK_HOOK must be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_16_BIT_TICKS + #error Missing definition: configUSE_16_BIT_TICKS must be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_CO_ROUTINES + #define configUSE_CO_ROUTINES 0 +#endif + +#ifndef INCLUDE_vTaskPrioritySet + #define INCLUDE_vTaskPrioritySet 0 +#endif + +#ifndef INCLUDE_uxTaskPriorityGet + #define INCLUDE_uxTaskPriorityGet 0 +#endif + +#ifndef INCLUDE_vTaskDelete + #define INCLUDE_vTaskDelete 0 +#endif + +#ifndef INCLUDE_vTaskSuspend + #define INCLUDE_vTaskSuspend 0 +#endif + +#ifndef INCLUDE_vTaskDelayUntil + #define INCLUDE_vTaskDelayUntil 0 +#endif + +#ifndef INCLUDE_vTaskDelay + #define INCLUDE_vTaskDelay 0 +#endif + +#ifndef INCLUDE_xTaskGetIdleTaskHandle + #define INCLUDE_xTaskGetIdleTaskHandle 0 +#endif + +#ifndef INCLUDE_xTaskAbortDelay + #define INCLUDE_xTaskAbortDelay 0 +#endif + +#ifndef INCLUDE_xQueueGetMutexHolder + #define INCLUDE_xQueueGetMutexHolder 0 +#endif + +#ifndef INCLUDE_xSemaphoreGetMutexHolder + #define INCLUDE_xSemaphoreGetMutexHolder INCLUDE_xQueueGetMutexHolder +#endif + +#ifndef INCLUDE_xTaskGetHandle + #define INCLUDE_xTaskGetHandle 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark + #define INCLUDE_uxTaskGetStackHighWaterMark 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark2 + #define INCLUDE_uxTaskGetStackHighWaterMark2 0 +#endif + +#ifndef INCLUDE_eTaskGetState + #define INCLUDE_eTaskGetState 0 +#endif + +#ifndef INCLUDE_xTaskResumeFromISR + #define INCLUDE_xTaskResumeFromISR 1 +#endif + +#ifndef INCLUDE_xTimerPendFunctionCall + #define INCLUDE_xTimerPendFunctionCall 0 +#endif + +#ifndef INCLUDE_xTaskGetSchedulerState + #define INCLUDE_xTaskGetSchedulerState 0 +#endif + +#ifndef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 0 +#endif + +#if configUSE_CO_ROUTINES != 0 + #ifndef configMAX_CO_ROUTINE_PRIORITIES + #error configMAX_CO_ROUTINE_PRIORITIES must be greater than or equal to 1. + #endif +#endif + +#ifndef configUSE_DAEMON_TASK_STARTUP_HOOK + #define configUSE_DAEMON_TASK_STARTUP_HOOK 0 +#endif + +#ifndef configUSE_APPLICATION_TASK_TAG + #define configUSE_APPLICATION_TASK_TAG 0 +#endif + +#ifndef configNUM_THREAD_LOCAL_STORAGE_POINTERS + #define configNUM_THREAD_LOCAL_STORAGE_POINTERS 0 +#endif + +#ifndef configUSE_RECURSIVE_MUTEXES + #define configUSE_RECURSIVE_MUTEXES 0 +#endif + +#ifndef configUSE_MUTEXES + #define configUSE_MUTEXES 0 +#endif + +#ifndef configUSE_TIMERS + #define configUSE_TIMERS 0 +#endif + +#ifndef configUSE_COUNTING_SEMAPHORES + #define configUSE_COUNTING_SEMAPHORES 0 +#endif + +#ifndef configUSE_ALTERNATIVE_API + #define configUSE_ALTERNATIVE_API 0 +#endif + +#ifndef portCRITICAL_NESTING_IN_TCB + #define portCRITICAL_NESTING_IN_TCB 0 +#endif + +#ifndef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 16 +#endif + +#ifndef configIDLE_SHOULD_YIELD + #define configIDLE_SHOULD_YIELD 1 +#endif + +#if configMAX_TASK_NAME_LEN < 1 + #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h +#endif + +#ifndef configASSERT + #define configASSERT( x ) + #define configASSERT_DEFINED 0 +#else + #define configASSERT_DEFINED 1 +#endif + +/* configPRECONDITION should be defined as configASSERT. +The CBMC proofs need a way to track assumptions and assertions. +A configPRECONDITION statement should express an implicit invariant or +assumption made. A configASSERT statement should express an invariant that must +hold explicit before calling the code. */ +#ifndef configPRECONDITION + #define configPRECONDITION( X ) configASSERT(X) + #define configPRECONDITION_DEFINED 0 +#else + #define configPRECONDITION_DEFINED 1 +#endif + +#ifndef portMEMORY_BARRIER + #define portMEMORY_BARRIER() +#endif + +#ifndef portSOFTWARE_BARRIER + #define portSOFTWARE_BARRIER() +#endif + +/* The timers module relies on xTaskGetSchedulerState(). */ +#if configUSE_TIMERS == 1 + + #ifndef configTIMER_TASK_PRIORITY + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. + #endif /* configTIMER_TASK_PRIORITY */ + + #ifndef configTIMER_QUEUE_LENGTH + #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. + #endif /* configTIMER_QUEUE_LENGTH */ + + #ifndef configTIMER_TASK_STACK_DEPTH + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. + #endif /* configTIMER_TASK_STACK_DEPTH */ + +#endif /* configUSE_TIMERS */ + +#ifndef portSET_INTERRUPT_MASK_FROM_ISR + #define portSET_INTERRUPT_MASK_FROM_ISR() 0 +#endif + +#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR + #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue +#endif + +#ifndef portCLEAN_UP_TCB + #define portCLEAN_UP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef portPRE_TASK_DELETE_HOOK + #define portPRE_TASK_DELETE_HOOK( pvTaskToDelete, pxYieldPending ) +#endif + +#ifndef portSETUP_TCB + #define portSETUP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef configQUEUE_REGISTRY_SIZE + #define configQUEUE_REGISTRY_SIZE 0U +#endif + +#if ( configQUEUE_REGISTRY_SIZE < 1 ) + #define vQueueAddToRegistry( xQueue, pcName ) + #define vQueueUnregisterQueue( xQueue ) + #define pcQueueGetName( xQueue ) +#endif + +#ifndef portPOINTER_SIZE_TYPE + #define portPOINTER_SIZE_TYPE uint32_t +#endif + +/* Remove any unused trace macros. */ +#ifndef traceSTART + /* Used to perform any necessary initialisation - for example, open a file + into which trace is to be written. */ + #define traceSTART() +#endif + +#ifndef traceEND + /* Use to close a trace, for example close a file into which trace has been + written. */ + #define traceEND() +#endif + +#ifndef traceTASK_SWITCHED_IN + /* Called after a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the selected task. */ + #define traceTASK_SWITCHED_IN() +#endif + +#ifndef traceINCREASE_TICK_COUNT + /* Called before stepping the tick count after waking from tickless idle + sleep. */ + #define traceINCREASE_TICK_COUNT( x ) +#endif + +#ifndef traceLOW_POWER_IDLE_BEGIN + /* Called immediately before entering tickless idle. */ + #define traceLOW_POWER_IDLE_BEGIN() +#endif + +#ifndef traceLOW_POWER_IDLE_END + /* Called when returning to the Idle task after a tickless idle. */ + #define traceLOW_POWER_IDLE_END() +#endif + +#ifndef traceTASK_SWITCHED_OUT + /* Called before a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the task being switched out. */ + #define traceTASK_SWITCHED_OUT() +#endif + +#ifndef traceTASK_PRIORITY_INHERIT + /* Called when a task attempts to take a mutex that is already held by a + lower priority task. pxTCBOfMutexHolder is a pointer to the TCB of the task + that holds the mutex. uxInheritedPriority is the priority the mutex holder + will inherit (the priority of the task that is attempting to obtain the + muted. */ + #define traceTASK_PRIORITY_INHERIT( pxTCBOfMutexHolder, uxInheritedPriority ) +#endif + +#ifndef traceTASK_PRIORITY_DISINHERIT + /* Called when a task releases a mutex, the holding of which had resulted in + the task inheriting the priority of a higher priority task. + pxTCBOfMutexHolder is a pointer to the TCB of the task that is releasing the + mutex. uxOriginalPriority is the task's configured (base) priority. */ + #define traceTASK_PRIORITY_DISINHERIT( pxTCBOfMutexHolder, uxOriginalPriority ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_RECEIVE + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_PEEK + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_SEND + /* Task is about to block because it cannot write to a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the write was attempted. pxCurrentTCB points to the TCB of the + task that attempted the write. */ + #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) +#endif + +#ifndef configCHECK_FOR_STACK_OVERFLOW + #define configCHECK_FOR_STACK_OVERFLOW 0 +#endif + +#ifndef configRECORD_STACK_HIGH_ADDRESS + #define configRECORD_STACK_HIGH_ADDRESS 0 +#endif + +#ifndef configINCLUDE_FREERTOS_TASK_C_ADDITIONS_H + #define configINCLUDE_FREERTOS_TASK_C_ADDITIONS_H 0 +#endif + +/* The following event macros are embedded in the kernel API calls. */ + +#ifndef traceMOVED_TASK_TO_READY_STATE + #define traceMOVED_TASK_TO_READY_STATE( pxTCB ) +#endif + +#ifndef tracePOST_MOVED_TASK_TO_READY_STATE + #define tracePOST_MOVED_TASK_TO_READY_STATE( pxTCB ) +#endif + +#ifndef traceQUEUE_CREATE + #define traceQUEUE_CREATE( pxNewQueue ) +#endif + +#ifndef traceQUEUE_CREATE_FAILED + #define traceQUEUE_CREATE_FAILED( ucQueueType ) +#endif + +#ifndef traceCREATE_MUTEX + #define traceCREATE_MUTEX( pxNewQueue ) +#endif + +#ifndef traceCREATE_MUTEX_FAILED + #define traceCREATE_MUTEX_FAILED() +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE + #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED + #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE + #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED + #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE + #define traceCREATE_COUNTING_SEMAPHORE() +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED + #define traceCREATE_COUNTING_SEMAPHORE_FAILED() +#endif + +#ifndef traceQUEUE_SEND + #define traceQUEUE_SEND( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FAILED + #define traceQUEUE_SEND_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE + #define traceQUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK + #define traceQUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK_FAILED + #define traceQUEUE_PEEK_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK_FROM_ISR + #define traceQUEUE_PEEK_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FAILED + #define traceQUEUE_RECEIVE_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR + #define traceQUEUE_SEND_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR_FAILED + #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR + #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED + #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK_FROM_ISR_FAILED + #define traceQUEUE_PEEK_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_DELETE + #define traceQUEUE_DELETE( pxQueue ) +#endif + +#ifndef traceTASK_CREATE + #define traceTASK_CREATE( pxNewTCB ) +#endif + +#ifndef traceTASK_CREATE_FAILED + #define traceTASK_CREATE_FAILED() +#endif + +#ifndef traceTASK_DELETE + #define traceTASK_DELETE( pxTaskToDelete ) +#endif + +#ifndef traceTASK_DELAY_UNTIL + #define traceTASK_DELAY_UNTIL( x ) +#endif + +#ifndef traceTASK_DELAY + #define traceTASK_DELAY() +#endif + +#ifndef traceTASK_PRIORITY_SET + #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) +#endif + +#ifndef traceTASK_SUSPEND + #define traceTASK_SUSPEND( pxTaskToSuspend ) +#endif + +#ifndef traceTASK_RESUME + #define traceTASK_RESUME( pxTaskToResume ) +#endif + +#ifndef traceTASK_RESUME_FROM_ISR + #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) +#endif + +#ifndef traceTASK_INCREMENT_TICK + #define traceTASK_INCREMENT_TICK( xTickCount ) +#endif + +#ifndef traceTIMER_CREATE + #define traceTIMER_CREATE( pxNewTimer ) +#endif + +#ifndef traceTIMER_CREATE_FAILED + #define traceTIMER_CREATE_FAILED() +#endif + +#ifndef traceTIMER_COMMAND_SEND + #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) +#endif + +#ifndef traceTIMER_EXPIRED + #define traceTIMER_EXPIRED( pxTimer ) +#endif + +#ifndef traceTIMER_COMMAND_RECEIVED + #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) +#endif + +#ifndef traceMALLOC + #define traceMALLOC( pvAddress, uiSize ) +#endif + +#ifndef traceFREE + #define traceFREE( pvAddress, uiSize ) +#endif + +#ifndef traceEVENT_GROUP_CREATE + #define traceEVENT_GROUP_CREATE( xEventGroup ) +#endif + +#ifndef traceEVENT_GROUP_CREATE_FAILED + #define traceEVENT_GROUP_CREATE_FAILED() +#endif + +#ifndef traceEVENT_GROUP_SYNC_BLOCK + #define traceEVENT_GROUP_SYNC_BLOCK( xEventGroup, uxBitsToSet, uxBitsToWaitFor ) +#endif + +#ifndef traceEVENT_GROUP_SYNC_END + #define traceEVENT_GROUP_SYNC_END( xEventGroup, uxBitsToSet, uxBitsToWaitFor, xTimeoutOccurred ) ( void ) xTimeoutOccurred +#endif + +#ifndef traceEVENT_GROUP_WAIT_BITS_BLOCK + #define traceEVENT_GROUP_WAIT_BITS_BLOCK( xEventGroup, uxBitsToWaitFor ) +#endif + +#ifndef traceEVENT_GROUP_WAIT_BITS_END + #define traceEVENT_GROUP_WAIT_BITS_END( xEventGroup, uxBitsToWaitFor, xTimeoutOccurred ) ( void ) xTimeoutOccurred +#endif + +#ifndef traceEVENT_GROUP_CLEAR_BITS + #define traceEVENT_GROUP_CLEAR_BITS( xEventGroup, uxBitsToClear ) +#endif + +#ifndef traceEVENT_GROUP_CLEAR_BITS_FROM_ISR + #define traceEVENT_GROUP_CLEAR_BITS_FROM_ISR( xEventGroup, uxBitsToClear ) +#endif + +#ifndef traceEVENT_GROUP_SET_BITS + #define traceEVENT_GROUP_SET_BITS( xEventGroup, uxBitsToSet ) +#endif + +#ifndef traceEVENT_GROUP_SET_BITS_FROM_ISR + #define traceEVENT_GROUP_SET_BITS_FROM_ISR( xEventGroup, uxBitsToSet ) +#endif + +#ifndef traceEVENT_GROUP_DELETE + #define traceEVENT_GROUP_DELETE( xEventGroup ) +#endif + +#ifndef tracePEND_FUNC_CALL + #define tracePEND_FUNC_CALL(xFunctionToPend, pvParameter1, ulParameter2, ret) +#endif + +#ifndef tracePEND_FUNC_CALL_FROM_ISR + #define tracePEND_FUNC_CALL_FROM_ISR(xFunctionToPend, pvParameter1, ulParameter2, ret) +#endif + +#ifndef traceQUEUE_REGISTRY_ADD + #define traceQUEUE_REGISTRY_ADD(xQueue, pcQueueName) +#endif + +#ifndef traceTASK_NOTIFY_TAKE_BLOCK + #define traceTASK_NOTIFY_TAKE_BLOCK() +#endif + +#ifndef traceTASK_NOTIFY_TAKE + #define traceTASK_NOTIFY_TAKE() +#endif + +#ifndef traceTASK_NOTIFY_WAIT_BLOCK + #define traceTASK_NOTIFY_WAIT_BLOCK() +#endif + +#ifndef traceTASK_NOTIFY_WAIT + #define traceTASK_NOTIFY_WAIT() +#endif + +#ifndef traceTASK_NOTIFY + #define traceTASK_NOTIFY() +#endif + +#ifndef traceTASK_NOTIFY_FROM_ISR + #define traceTASK_NOTIFY_FROM_ISR() +#endif + +#ifndef traceTASK_NOTIFY_GIVE_FROM_ISR + #define traceTASK_NOTIFY_GIVE_FROM_ISR() +#endif + +#ifndef traceSTREAM_BUFFER_CREATE_FAILED + #define traceSTREAM_BUFFER_CREATE_FAILED( xIsMessageBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_CREATE_STATIC_FAILED + #define traceSTREAM_BUFFER_CREATE_STATIC_FAILED( xReturn, xIsMessageBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_CREATE + #define traceSTREAM_BUFFER_CREATE( pxStreamBuffer, xIsMessageBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_DELETE + #define traceSTREAM_BUFFER_DELETE( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_RESET + #define traceSTREAM_BUFFER_RESET( xStreamBuffer ) +#endif + +#ifndef traceBLOCKING_ON_STREAM_BUFFER_SEND + #define traceBLOCKING_ON_STREAM_BUFFER_SEND( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_SEND + #define traceSTREAM_BUFFER_SEND( xStreamBuffer, xBytesSent ) +#endif + +#ifndef traceSTREAM_BUFFER_SEND_FAILED + #define traceSTREAM_BUFFER_SEND_FAILED( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_SEND_FROM_ISR + #define traceSTREAM_BUFFER_SEND_FROM_ISR( xStreamBuffer, xBytesSent ) +#endif + +#ifndef traceBLOCKING_ON_STREAM_BUFFER_RECEIVE + #define traceBLOCKING_ON_STREAM_BUFFER_RECEIVE( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_RECEIVE + #define traceSTREAM_BUFFER_RECEIVE( xStreamBuffer, xReceivedLength ) +#endif + +#ifndef traceSTREAM_BUFFER_RECEIVE_FAILED + #define traceSTREAM_BUFFER_RECEIVE_FAILED( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_RECEIVE_FROM_ISR + #define traceSTREAM_BUFFER_RECEIVE_FROM_ISR( xStreamBuffer, xReceivedLength ) +#endif + +#ifndef configGENERATE_RUN_TIME_STATS + #define configGENERATE_RUN_TIME_STATS 0 +#endif + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. + #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ + + #ifndef portGET_RUN_TIME_COUNTER_VALUE + #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE + #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. + #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ + #endif /* portGET_RUN_TIME_COUNTER_VALUE */ + +#endif /* configGENERATE_RUN_TIME_STATS */ + +#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#endif + +#ifndef configUSE_MALLOC_FAILED_HOOK + #define configUSE_MALLOC_FAILED_HOOK 0 +#endif + +#ifndef portPRIVILEGE_BIT + #define portPRIVILEGE_BIT ( ( UBaseType_t ) 0x00 ) +#endif + +#ifndef portYIELD_WITHIN_API + #define portYIELD_WITHIN_API portYIELD +#endif + +#ifndef portSUPPRESS_TICKS_AND_SLEEP + #define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) +#endif + +#ifndef configEXPECTED_IDLE_TIME_BEFORE_SLEEP + #define configEXPECTED_IDLE_TIME_BEFORE_SLEEP 2 +#endif + +#if configEXPECTED_IDLE_TIME_BEFORE_SLEEP < 2 + #error configEXPECTED_IDLE_TIME_BEFORE_SLEEP must not be less than 2 +#endif + +#ifndef configUSE_TICKLESS_IDLE + #define configUSE_TICKLESS_IDLE 0 +#endif + +#ifndef configPRE_SUPPRESS_TICKS_AND_SLEEP_PROCESSING + #define configPRE_SUPPRESS_TICKS_AND_SLEEP_PROCESSING( x ) +#endif + +#ifndef configPRE_SLEEP_PROCESSING + #define configPRE_SLEEP_PROCESSING( x ) +#endif + +#ifndef configPOST_SLEEP_PROCESSING + #define configPOST_SLEEP_PROCESSING( x ) +#endif + +#ifndef configUSE_QUEUE_SETS + #define configUSE_QUEUE_SETS 0 +#endif + +#ifndef portTASK_USES_FLOATING_POINT + #define portTASK_USES_FLOATING_POINT() +#endif + +#ifndef portALLOCATE_SECURE_CONTEXT + #define portALLOCATE_SECURE_CONTEXT( ulSecureStackSize ) +#endif + +#ifndef portDONT_DISCARD + #define portDONT_DISCARD +#endif + +#ifndef configUSE_TIME_SLICING + #define configUSE_TIME_SLICING 1 +#endif + +#ifndef configINCLUDE_APPLICATION_DEFINED_PRIVILEGED_FUNCTIONS + #define configINCLUDE_APPLICATION_DEFINED_PRIVILEGED_FUNCTIONS 0 +#endif + +#ifndef configUSE_STATS_FORMATTING_FUNCTIONS + #define configUSE_STATS_FORMATTING_FUNCTIONS 0 +#endif + +#ifndef portASSERT_IF_INTERRUPT_PRIORITY_INVALID + #define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() +#endif + +#ifndef configUSE_TRACE_FACILITY + #define configUSE_TRACE_FACILITY 0 +#endif + +#ifndef mtCOVERAGE_TEST_MARKER + #define mtCOVERAGE_TEST_MARKER() +#endif + +#ifndef mtCOVERAGE_TEST_DELAY + #define mtCOVERAGE_TEST_DELAY() +#endif + +#ifndef portASSERT_IF_IN_ISR + #define portASSERT_IF_IN_ISR() +#endif + +#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION + #define configUSE_PORT_OPTIMISED_TASK_SELECTION 0 +#endif + +#ifndef configAPPLICATION_ALLOCATED_HEAP + #define configAPPLICATION_ALLOCATED_HEAP 0 +#endif + +#ifndef configUSE_TASK_NOTIFICATIONS + #define configUSE_TASK_NOTIFICATIONS 1 +#endif + +#ifndef configUSE_POSIX_ERRNO + #define configUSE_POSIX_ERRNO 0 +#endif + +#ifndef portTICK_TYPE_IS_ATOMIC + #define portTICK_TYPE_IS_ATOMIC 0 +#endif + +#ifndef configSUPPORT_STATIC_ALLOCATION + /* Defaults to 0 for backward compatibility. */ + #define configSUPPORT_STATIC_ALLOCATION 0 +#endif + +#ifndef configSUPPORT_DYNAMIC_ALLOCATION + /* Defaults to 1 for backward compatibility. */ + #define configSUPPORT_DYNAMIC_ALLOCATION 1 +#endif + +#ifndef configSTACK_DEPTH_TYPE + /* Defaults to uint16_t for backward compatibility, but can be overridden + in FreeRTOSConfig.h if uint16_t is too restrictive. */ + #define configSTACK_DEPTH_TYPE uint16_t +#endif + +#ifndef configMESSAGE_BUFFER_LENGTH_TYPE + /* Defaults to size_t for backward compatibility, but can be overridden + in FreeRTOSConfig.h if lengths will always be less than the number of bytes + in a size_t. */ + #define configMESSAGE_BUFFER_LENGTH_TYPE size_t +#endif + +/* Sanity check the configuration. */ +#if( configUSE_TICKLESS_IDLE != 0 ) + #if( INCLUDE_vTaskSuspend != 1 ) + #error INCLUDE_vTaskSuspend must be set to 1 if configUSE_TICKLESS_IDLE is not set to 0 + #endif /* INCLUDE_vTaskSuspend */ +#endif /* configUSE_TICKLESS_IDLE */ + +#if( ( configSUPPORT_STATIC_ALLOCATION == 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) ) + #error configSUPPORT_STATIC_ALLOCATION and configSUPPORT_DYNAMIC_ALLOCATION cannot both be 0, but can both be 1. +#endif + +#if( ( configUSE_RECURSIVE_MUTEXES == 1 ) && ( configUSE_MUTEXES != 1 ) ) + #error configUSE_MUTEXES must be set to 1 to use recursive mutexes +#endif + +#ifndef configINITIAL_TICK_COUNT + #define configINITIAL_TICK_COUNT 0 +#endif + +#if( portTICK_TYPE_IS_ATOMIC == 0 ) + /* Either variables of tick type cannot be read atomically, or + portTICK_TYPE_IS_ATOMIC was not set - map the critical sections used when + the tick count is returned to the standard critical section macros. */ + #define portTICK_TYPE_ENTER_CRITICAL() portENTER_CRITICAL() + #define portTICK_TYPE_EXIT_CRITICAL() portEXIT_CRITICAL() + #define portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR() portSET_INTERRUPT_MASK_FROM_ISR() + #define portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( x ) portCLEAR_INTERRUPT_MASK_FROM_ISR( ( x ) ) +#else + /* The tick type can be read atomically, so critical sections used when the + tick count is returned can be defined away. */ + #define portTICK_TYPE_ENTER_CRITICAL() + #define portTICK_TYPE_EXIT_CRITICAL() + #define portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR() 0 + #define portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( x ) ( void ) x +#endif + +/* Definitions to allow backward compatibility with FreeRTOS versions prior to +V8 if desired. */ +#ifndef configENABLE_BACKWARD_COMPATIBILITY + #define configENABLE_BACKWARD_COMPATIBILITY 1 +#endif + +#ifndef configPRINTF + /* configPRINTF() was not defined, so define it away to nothing. To use + configPRINTF() then define it as follows (where MyPrintFunction() is + provided by the application writer): + + void MyPrintFunction(const char *pcFormat, ... ); + #define configPRINTF( X ) MyPrintFunction X + + Then call like a standard printf() function, but placing brackets around + all parameters so they are passed as a single parameter. For example: + configPRINTF( ("Value = %d", MyVariable) ); */ + #define configPRINTF( X ) +#endif + +#ifndef configMAX + /* The application writer has not provided their own MAX macro, so define + the following generic implementation. */ + #define configMAX( a, b ) ( ( ( a ) > ( b ) ) ? ( a ) : ( b ) ) +#endif + +#ifndef configMIN + /* The application writer has not provided their own MAX macro, so define + the following generic implementation. */ + #define configMIN( a, b ) ( ( ( a ) < ( b ) ) ? ( a ) : ( b ) ) +#endif + +#if configENABLE_BACKWARD_COMPATIBILITY == 1 + #define eTaskStateGet eTaskGetState + #define portTickType TickType_t + #define xTaskHandle TaskHandle_t + #define xQueueHandle QueueHandle_t + #define xSemaphoreHandle SemaphoreHandle_t + #define xQueueSetHandle QueueSetHandle_t + #define xQueueSetMemberHandle QueueSetMemberHandle_t + #define xTimeOutType TimeOut_t + #define xMemoryRegion MemoryRegion_t + #define xTaskParameters TaskParameters_t + #define xTaskStatusType TaskStatus_t + #define xTimerHandle TimerHandle_t + #define xCoRoutineHandle CoRoutineHandle_t + #define pdTASK_HOOK_CODE TaskHookFunction_t + #define portTICK_RATE_MS portTICK_PERIOD_MS + #define pcTaskGetTaskName pcTaskGetName + #define pcTimerGetTimerName pcTimerGetName + #define pcQueueGetQueueName pcQueueGetName + #define vTaskGetTaskInfo vTaskGetInfo + #define xTaskGetIdleRunTimeCounter ulTaskGetIdleRunTimeCounter + + /* Backward compatibility within the scheduler code only - these definitions + are not really required but are included for completeness. */ + #define tmrTIMER_CALLBACK TimerCallbackFunction_t + #define pdTASK_CODE TaskFunction_t + #define xListItem ListItem_t + #define xList List_t + + /* For libraries that break the list data hiding, and access list structure + members directly (which is not supposed to be done). */ + #define pxContainer pvContainer +#endif /* configENABLE_BACKWARD_COMPATIBILITY */ + +#if( configUSE_ALTERNATIVE_API != 0 ) + #error The alternative API was deprecated some time ago, and was removed in FreeRTOS V9.0 0 +#endif + +/* Set configUSE_TASK_FPU_SUPPORT to 0 to omit floating point support even +if floating point hardware is otherwise supported by the FreeRTOS port in use. +This constant is not supported by all FreeRTOS ports that include floating +point support. */ +#ifndef configUSE_TASK_FPU_SUPPORT + #define configUSE_TASK_FPU_SUPPORT 1 +#endif + +/* Set configENABLE_MPU to 1 to enable MPU support and 0 to disable it. This is +currently used in ARMv8M ports. */ +#ifndef configENABLE_MPU + #define configENABLE_MPU 0 +#endif + +/* Set configENABLE_FPU to 1 to enable FPU support and 0 to disable it. This is +currently used in ARMv8M ports. */ +#ifndef configENABLE_FPU + #define configENABLE_FPU 1 +#endif + +/* Set configENABLE_TRUSTZONE to 1 enable TrustZone support and 0 to disable it. +This is currently used in ARMv8M ports. */ +#ifndef configENABLE_TRUSTZONE + #define configENABLE_TRUSTZONE 1 +#endif + +/* Set configRUN_FREERTOS_SECURE_ONLY to 1 to run the FreeRTOS ARMv8M port on +the Secure Side only. */ +#ifndef configRUN_FREERTOS_SECURE_ONLY + #define configRUN_FREERTOS_SECURE_ONLY 0 +#endif + +/* Sometimes the FreeRTOSConfig.h settings only allow a task to be created using + * dynamically allocated RAM, in which case when any task is deleted it is known + * that both the task's stack and TCB need to be freed. Sometimes the + * FreeRTOSConfig.h settings only allow a task to be created using statically + * allocated RAM, in which case when any task is deleted it is known that neither + * the task's stack or TCB should be freed. Sometimes the FreeRTOSConfig.h + * settings allow a task to be created using either statically or dynamically + * allocated RAM, in which case a member of the TCB is used to record whether the + * stack and/or TCB were allocated statically or dynamically, so when a task is + * deleted the RAM that was allocated dynamically is freed again and no attempt is + * made to free the RAM that was allocated statically. + * tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE is only true if it is possible for a + * task to be created using either statically or dynamically allocated RAM. Note + * that if portUSING_MPU_WRAPPERS is 1 then a protected task can be created with + * a statically allocated stack and a dynamically allocated TCB. + * + * The following table lists various combinations of portUSING_MPU_WRAPPERS, + * configSUPPORT_DYNAMIC_ALLOCATION and configSUPPORT_STATIC_ALLOCATION and + * when it is possible to have both static and dynamic allocation: + * +-----+---------+--------+-----------------------------+-----------------------------------+------------------+-----------+ + * | MPU | Dynamic | Static | Available Functions | Possible Allocations | Both Dynamic and | Need Free | + * | | | | | | Static Possible | | + * +-----+---------+--------+-----------------------------+-----------------------------------+------------------+-----------+ + * | 0 | 0 | 1 | xTaskCreateStatic | TCB - Static, Stack - Static | No | No | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 0 | 1 | 0 | xTaskCreate | TCB - Dynamic, Stack - Dynamic | No | Yes | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 0 | 1 | 1 | xTaskCreate, | 1. TCB - Dynamic, Stack - Dynamic | Yes | Yes | + * | | | | xTaskCreateStatic | 2. TCB - Static, Stack - Static | | | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 1 | 0 | 1 | xTaskCreateStatic, | TCB - Static, Stack - Static | No | No | + * | | | | xTaskCreateRestrictedStatic | | | | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 1 | 1 | 0 | xTaskCreate, | 1. TCB - Dynamic, Stack - Dynamic | Yes | Yes | + * | | | | xTaskCreateRestricted | 2. TCB - Dynamic, Stack - Static | | | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 1 | 1 | 1 | xTaskCreate, | 1. TCB - Dynamic, Stack - Dynamic | Yes | Yes | + * | | | | xTaskCreateStatic, | 2. TCB - Dynamic, Stack - Static | | | + * | | | | xTaskCreateRestricted, | 3. TCB - Static, Stack - Static | | | + * | | | | xTaskCreateRestrictedStatic | | | | + * +-----+---------+--------+-----------------------------+-----------------------------------+------------------+-----------+ + */ +#define tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE ( ( ( portUSING_MPU_WRAPPERS == 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) || \ + ( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) ) + +/* + * In line with software engineering best practice, FreeRTOS implements a strict + * data hiding policy, so the real structures used by FreeRTOS to maintain the + * state of tasks, queues, semaphores, etc. are not accessible to the application + * code. However, if the application writer wants to statically allocate such + * an object then the size of the object needs to be know. Dummy structures + * that are guaranteed to have the same size and alignment requirements of the + * real objects are used for this purpose. The dummy list and list item + * structures below are used for inclusion in such a dummy structure. + */ +struct xSTATIC_LIST_ITEM +{ + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy1; + #endif + TickType_t xDummy2; + void *pvDummy3[ 4 ]; + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy4; + #endif +}; +typedef struct xSTATIC_LIST_ITEM StaticListItem_t; + +/* See the comments above the struct xSTATIC_LIST_ITEM definition. */ +struct xSTATIC_MINI_LIST_ITEM +{ + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy1; + #endif + TickType_t xDummy2; + void *pvDummy3[ 2 ]; +}; +typedef struct xSTATIC_MINI_LIST_ITEM StaticMiniListItem_t; + +/* See the comments above the struct xSTATIC_LIST_ITEM definition. */ +typedef struct xSTATIC_LIST +{ + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy1; + #endif + UBaseType_t uxDummy2; + void *pvDummy3; + StaticMiniListItem_t xDummy4; + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy5; + #endif +} StaticList_t; + +/* + * In line with software engineering best practice, especially when supplying a + * library that is likely to change in future versions, FreeRTOS implements a + * strict data hiding policy. This means the Task structure used internally by + * FreeRTOS is not accessible to application code. However, if the application + * writer wants to statically allocate the memory required to create a task then + * the size of the task object needs to be know. The StaticTask_t structure + * below is provided for this purpose. Its sizes and alignment requirements are + * guaranteed to match those of the genuine structure, no matter which + * architecture is being used, and no matter how the values in FreeRTOSConfig.h + * are set. Its contents are somewhat obfuscated in the hope users will + * recognise that it would be unwise to make direct use of the structure members. + */ +typedef struct xSTATIC_TCB +{ + void *pxDummy1; + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xDummy2; + #endif + StaticListItem_t xDummy3[ 2 ]; + UBaseType_t uxDummy5; + void *pxDummy6; + uint8_t ucDummy7[ configMAX_TASK_NAME_LEN ]; + #if ( ( portSTACK_GROWTH > 0 ) || ( configRECORD_STACK_HIGH_ADDRESS == 1 ) ) + void *pxDummy8; + #endif + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + UBaseType_t uxDummy9; + #endif + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy10[ 2 ]; + #endif + #if ( configUSE_MUTEXES == 1 ) + UBaseType_t uxDummy12[ 2 ]; + #endif + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + void *pxDummy14; + #endif + #if( configNUM_THREAD_LOCAL_STORAGE_POINTERS > 0 ) + void *pvDummy15[ configNUM_THREAD_LOCAL_STORAGE_POINTERS ]; + #endif + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + uint32_t ulDummy16; + #endif + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + struct _reent xDummy17; + #endif + #if ( configUSE_TASK_NOTIFICATIONS == 1 ) + uint32_t ulDummy18; + uint8_t ucDummy19; + #endif + #if ( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) + uint8_t uxDummy20; + #endif + + #if( INCLUDE_xTaskAbortDelay == 1 ) + uint8_t ucDummy21; + #endif + #if ( configUSE_POSIX_ERRNO == 1 ) + int iDummy22; + #endif +} StaticTask_t; + +/* + * In line with software engineering best practice, especially when supplying a + * library that is likely to change in future versions, FreeRTOS implements a + * strict data hiding policy. This means the Queue structure used internally by + * FreeRTOS is not accessible to application code. However, if the application + * writer wants to statically allocate the memory required to create a queue + * then the size of the queue object needs to be know. The StaticQueue_t + * structure below is provided for this purpose. Its sizes and alignment + * requirements are guaranteed to match those of the genuine structure, no + * matter which architecture is being used, and no matter how the values in + * FreeRTOSConfig.h are set. Its contents are somewhat obfuscated in the hope + * users will recognise that it would be unwise to make direct use of the + * structure members. + */ +typedef struct xSTATIC_QUEUE +{ + void *pvDummy1[ 3 ]; + + union + { + void *pvDummy2; + UBaseType_t uxDummy2; + } u; + + StaticList_t xDummy3[ 2 ]; + UBaseType_t uxDummy4[ 3 ]; + uint8_t ucDummy5[ 2 ]; + + #if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + uint8_t ucDummy6; + #endif + + #if ( configUSE_QUEUE_SETS == 1 ) + void *pvDummy7; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy8; + uint8_t ucDummy9; + #endif + +} StaticQueue_t; +typedef StaticQueue_t StaticSemaphore_t; + +/* + * In line with software engineering best practice, especially when supplying a + * library that is likely to change in future versions, FreeRTOS implements a + * strict data hiding policy. This means the event group structure used + * internally by FreeRTOS is not accessible to application code. However, if + * the application writer wants to statically allocate the memory required to + * create an event group then the size of the event group object needs to be + * know. The StaticEventGroup_t structure below is provided for this purpose. + * Its sizes and alignment requirements are guaranteed to match those of the + * genuine structure, no matter which architecture is being used, and no matter + * how the values in FreeRTOSConfig.h are set. Its contents are somewhat + * obfuscated in the hope users will recognise that it would be unwise to make + * direct use of the structure members. + */ +typedef struct xSTATIC_EVENT_GROUP +{ + TickType_t xDummy1; + StaticList_t xDummy2; + + #if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy3; + #endif + + #if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + uint8_t ucDummy4; + #endif + +} StaticEventGroup_t; + +/* + * In line with software engineering best practice, especially when supplying a + * library that is likely to change in future versions, FreeRTOS implements a + * strict data hiding policy. This means the software timer structure used + * internally by FreeRTOS is not accessible to application code. However, if + * the application writer wants to statically allocate the memory required to + * create a software timer then the size of the queue object needs to be know. + * The StaticTimer_t structure below is provided for this purpose. Its sizes + * and alignment requirements are guaranteed to match those of the genuine + * structure, no matter which architecture is being used, and no matter how the + * values in FreeRTOSConfig.h are set. Its contents are somewhat obfuscated in + * the hope users will recognise that it would be unwise to make direct use of + * the structure members. + */ +typedef struct xSTATIC_TIMER +{ + void *pvDummy1; + StaticListItem_t xDummy2; + TickType_t xDummy3; + void *pvDummy5; + TaskFunction_t pvDummy6; + #if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy7; + #endif + uint8_t ucDummy8; + +} StaticTimer_t; + +/* +* In line with software engineering best practice, especially when supplying a +* library that is likely to change in future versions, FreeRTOS implements a +* strict data hiding policy. This means the stream buffer structure used +* internally by FreeRTOS is not accessible to application code. However, if +* the application writer wants to statically allocate the memory required to +* create a stream buffer then the size of the stream buffer object needs to be +* know. The StaticStreamBuffer_t structure below is provided for this purpose. +* Its size and alignment requirements are guaranteed to match those of the +* genuine structure, no matter which architecture is being used, and no matter +* how the values in FreeRTOSConfig.h are set. Its contents are somewhat +* obfuscated in the hope users will recognise that it would be unwise to make +* direct use of the structure members. +*/ +typedef struct xSTATIC_STREAM_BUFFER +{ + size_t uxDummy1[ 4 ]; + void * pvDummy2[ 3 ]; + uint8_t ucDummy3; + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy4; + #endif +} StaticStreamBuffer_t; + +/* Message buffers are built on stream buffers. */ +typedef StaticStreamBuffer_t StaticMessageBuffer_t; + +#ifdef __cplusplus +} +#endif + +#endif /* INC_FREERTOS_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/StackMacros.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/StackMacros.h new file mode 100644 index 0000000..6d232b6 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/StackMacros.h @@ -0,0 +1,133 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 STACK_MACROS_H +#define STACK_MACROS_H + +#ifndef _MSC_VER /* Visual Studio doesn't support #warning. */ + #warning The name of this file has changed to stack_macros.h. Please update your code accordingly. This source file (which has the original name) will be removed in future released. +#endif + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + const uint32_t * const pulStack = ( uint32_t * ) pxCurrentTCB->pxStack; \ + const uint32_t ulCheckValue = ( uint32_t ) 0xa5a5a5a5; \ + \ + if( ( pulStack[ 0 ] != ulCheckValue ) || \ + ( pulStack[ 1 ] != ulCheckValue ) || \ + ( pulStack[ 2 ] != ulCheckValue ) || \ + ( pulStack[ 3 ] != ulCheckValue ) ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + int8_t *pcEndOfStack = ( int8_t * ) pxCurrentTCB->pxEndOfStack; \ + static const uint8_t ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +/* Remove stack overflow macro if not being used. */ +#ifndef taskCHECK_FOR_STACK_OVERFLOW + #define taskCHECK_FOR_STACK_OVERFLOW() +#endif + + + +#endif /* STACK_MACROS_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/atomic.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/atomic.h new file mode 100644 index 0000000..b77dc1f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/atomic.h @@ -0,0 +1,414 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/** + * @file atomic.h + * @brief FreeRTOS atomic operation support. + * + * This file implements atomic functions by disabling interrupts globally. + * Implementations with architecture specific atomic instructions can be + * provided under each compiler directory. + */ + +#ifndef ATOMIC_H +#define ATOMIC_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include atomic.h" +#endif + +/* Standard includes. */ +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * Port specific definitions -- entering/exiting critical section. + * Refer template -- ./lib/FreeRTOS/portable/Compiler/Arch/portmacro.h + * + * Every call to ATOMIC_EXIT_CRITICAL() must be closely paired with + * ATOMIC_ENTER_CRITICAL(). + * + */ +#if defined( portSET_INTERRUPT_MASK_FROM_ISR ) + + /* Nested interrupt scheme is supported in this port. */ + #define ATOMIC_ENTER_CRITICAL() \ + UBaseType_t uxCriticalSectionType = portSET_INTERRUPT_MASK_FROM_ISR() + + #define ATOMIC_EXIT_CRITICAL() \ + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxCriticalSectionType ) + +#else + + /* Nested interrupt scheme is NOT supported in this port. */ + #define ATOMIC_ENTER_CRITICAL() portENTER_CRITICAL() + #define ATOMIC_EXIT_CRITICAL() portEXIT_CRITICAL() + +#endif /* portSET_INTERRUPT_MASK_FROM_ISR() */ + +/* + * Port specific definition -- "always inline". + * Inline is compiler specific, and may not always get inlined depending on your + * optimization level. Also, inline is considered as performance optimization + * for atomic. Thus, if portFORCE_INLINE is not provided by portmacro.h, + * instead of resulting error, simply define it away. + */ +#ifndef portFORCE_INLINE + #define portFORCE_INLINE +#endif + +#define ATOMIC_COMPARE_AND_SWAP_SUCCESS 0x1U /**< Compare and swap succeeded, swapped. */ +#define ATOMIC_COMPARE_AND_SWAP_FAILURE 0x0U /**< Compare and swap failed, did not swap. */ + +/*----------------------------- Swap && CAS ------------------------------*/ + +/** + * Atomic compare-and-swap + * + * @brief Performs an atomic compare-and-swap operation on the specified values. + * + * @param[in, out] pulDestination Pointer to memory location from where value is + * to be loaded and checked. + * @param[in] ulExchange If condition meets, write this value to memory. + * @param[in] ulComparand Swap condition. + * + * @return Unsigned integer of value 1 or 0. 1 for swapped, 0 for not swapped. + * + * @note This function only swaps *pulDestination with ulExchange, if previous + * *pulDestination value equals ulComparand. + */ +static portFORCE_INLINE uint32_t Atomic_CompareAndSwap_u32( uint32_t volatile * pulDestination, + uint32_t ulExchange, + uint32_t ulComparand ) +{ +uint32_t ulReturnValue; + + ATOMIC_ENTER_CRITICAL(); + { + if( *pulDestination == ulComparand ) + { + *pulDestination = ulExchange; + ulReturnValue = ATOMIC_COMPARE_AND_SWAP_SUCCESS; + } + else + { + ulReturnValue = ATOMIC_COMPARE_AND_SWAP_FAILURE; + } + } + ATOMIC_EXIT_CRITICAL(); + + return ulReturnValue; +} +/*-----------------------------------------------------------*/ + +/** + * Atomic swap (pointers) + * + * @brief Atomically sets the address pointed to by *ppvDestination to the value + * of *pvExchange. + * + * @param[in, out] ppvDestination Pointer to memory location from where a pointer + * value is to be loaded and written back to. + * @param[in] pvExchange Pointer value to be written to *ppvDestination. + * + * @return The initial value of *ppvDestination. + */ +static portFORCE_INLINE void * Atomic_SwapPointers_p32( void * volatile * ppvDestination, + void * pvExchange ) +{ +void * pReturnValue; + + ATOMIC_ENTER_CRITICAL(); + { + pReturnValue = *ppvDestination; + *ppvDestination = pvExchange; + } + ATOMIC_EXIT_CRITICAL(); + + return pReturnValue; +} +/*-----------------------------------------------------------*/ + +/** + * Atomic compare-and-swap (pointers) + * + * @brief Performs an atomic compare-and-swap operation on the specified pointer + * values. + * + * @param[in, out] ppvDestination Pointer to memory location from where a pointer + * value is to be loaded and checked. + * @param[in] pvExchange If condition meets, write this value to memory. + * @param[in] pvComparand Swap condition. + * + * @return Unsigned integer of value 1 or 0. 1 for swapped, 0 for not swapped. + * + * @note This function only swaps *ppvDestination with pvExchange, if previous + * *ppvDestination value equals pvComparand. + */ +static portFORCE_INLINE uint32_t Atomic_CompareAndSwapPointers_p32( void * volatile * ppvDestination, + void * pvExchange, + void * pvComparand ) +{ +uint32_t ulReturnValue = ATOMIC_COMPARE_AND_SWAP_FAILURE; + + ATOMIC_ENTER_CRITICAL(); + { + if( *ppvDestination == pvComparand ) + { + *ppvDestination = pvExchange; + ulReturnValue = ATOMIC_COMPARE_AND_SWAP_SUCCESS; + } + } + ATOMIC_EXIT_CRITICAL(); + + return ulReturnValue; +} + + +/*----------------------------- Arithmetic ------------------------------*/ + +/** + * Atomic add + * + * @brief Atomically adds count to the value of the specified pointer points to. + * + * @param[in,out] pulAddend Pointer to memory location from where value is to be + * loaded and written back to. + * @param[in] ulCount Value to be added to *pulAddend. + * + * @return previous *pulAddend value. + */ +static portFORCE_INLINE uint32_t Atomic_Add_u32( uint32_t volatile * pulAddend, + uint32_t ulCount ) +{ + uint32_t ulCurrent; + + ATOMIC_ENTER_CRITICAL(); + { + ulCurrent = *pulAddend; + *pulAddend += ulCount; + } + ATOMIC_EXIT_CRITICAL(); + + return ulCurrent; +} +/*-----------------------------------------------------------*/ + +/** + * Atomic subtract + * + * @brief Atomically subtracts count from the value of the specified pointer + * pointers to. + * + * @param[in,out] pulAddend Pointer to memory location from where value is to be + * loaded and written back to. + * @param[in] ulCount Value to be subtract from *pulAddend. + * + * @return previous *pulAddend value. + */ +static portFORCE_INLINE uint32_t Atomic_Subtract_u32( uint32_t volatile * pulAddend, + uint32_t ulCount ) +{ + uint32_t ulCurrent; + + ATOMIC_ENTER_CRITICAL(); + { + ulCurrent = *pulAddend; + *pulAddend -= ulCount; + } + ATOMIC_EXIT_CRITICAL(); + + return ulCurrent; +} +/*-----------------------------------------------------------*/ + +/** + * Atomic increment + * + * @brief Atomically increments the value of the specified pointer points to. + * + * @param[in,out] pulAddend Pointer to memory location from where value is to be + * loaded and written back to. + * + * @return *pulAddend value before increment. + */ +static portFORCE_INLINE uint32_t Atomic_Increment_u32( uint32_t volatile * pulAddend ) +{ +uint32_t ulCurrent; + + ATOMIC_ENTER_CRITICAL(); + { + ulCurrent = *pulAddend; + *pulAddend += 1; + } + ATOMIC_EXIT_CRITICAL(); + + return ulCurrent; +} +/*-----------------------------------------------------------*/ + +/** + * Atomic decrement + * + * @brief Atomically decrements the value of the specified pointer points to + * + * @param[in,out] pulAddend Pointer to memory location from where value is to be + * loaded and written back to. + * + * @return *pulAddend value before decrement. + */ +static portFORCE_INLINE uint32_t Atomic_Decrement_u32( uint32_t volatile * pulAddend ) +{ +uint32_t ulCurrent; + + ATOMIC_ENTER_CRITICAL(); + { + ulCurrent = *pulAddend; + *pulAddend -= 1; + } + ATOMIC_EXIT_CRITICAL(); + + return ulCurrent; +} + +/*----------------------------- Bitwise Logical ------------------------------*/ + +/** + * Atomic OR + * + * @brief Performs an atomic OR operation on the specified values. + * + * @param [in, out] pulDestination Pointer to memory location from where value is + * to be loaded and written back to. + * @param [in] ulValue Value to be ORed with *pulDestination. + * + * @return The original value of *pulDestination. + */ +static portFORCE_INLINE uint32_t Atomic_OR_u32( uint32_t volatile * pulDestination, + uint32_t ulValue ) +{ +uint32_t ulCurrent; + + ATOMIC_ENTER_CRITICAL(); + { + ulCurrent = *pulDestination; + *pulDestination |= ulValue; + } + ATOMIC_EXIT_CRITICAL(); + + return ulCurrent; +} +/*-----------------------------------------------------------*/ + +/** + * Atomic AND + * + * @brief Performs an atomic AND operation on the specified values. + * + * @param [in, out] pulDestination Pointer to memory location from where value is + * to be loaded and written back to. + * @param [in] ulValue Value to be ANDed with *pulDestination. + * + * @return The original value of *pulDestination. + */ +static portFORCE_INLINE uint32_t Atomic_AND_u32( uint32_t volatile * pulDestination, + uint32_t ulValue ) +{ +uint32_t ulCurrent; + + ATOMIC_ENTER_CRITICAL(); + { + ulCurrent = *pulDestination; + *pulDestination &= ulValue; + } + ATOMIC_EXIT_CRITICAL(); + + return ulCurrent; +} +/*-----------------------------------------------------------*/ + +/** + * Atomic NAND + * + * @brief Performs an atomic NAND operation on the specified values. + * + * @param [in, out] pulDestination Pointer to memory location from where value is + * to be loaded and written back to. + * @param [in] ulValue Value to be NANDed with *pulDestination. + * + * @return The original value of *pulDestination. + */ +static portFORCE_INLINE uint32_t Atomic_NAND_u32( uint32_t volatile * pulDestination, + uint32_t ulValue ) +{ +uint32_t ulCurrent; + + ATOMIC_ENTER_CRITICAL(); + { + ulCurrent = *pulDestination; + *pulDestination = ~( ulCurrent & ulValue ); + } + ATOMIC_EXIT_CRITICAL(); + + return ulCurrent; +} +/*-----------------------------------------------------------*/ + +/** + * Atomic XOR + * + * @brief Performs an atomic XOR operation on the specified values. + * + * @param [in, out] pulDestination Pointer to memory location from where value is + * to be loaded and written back to. + * @param [in] ulValue Value to be XORed with *pulDestination. + * + * @return The original value of *pulDestination. + */ +static portFORCE_INLINE uint32_t Atomic_XOR_u32( uint32_t volatile * pulDestination, + uint32_t ulValue ) +{ +uint32_t ulCurrent; + + ATOMIC_ENTER_CRITICAL(); + { + ulCurrent = *pulDestination; + *pulDestination ^= ulValue; + } + ATOMIC_EXIT_CRITICAL(); + + return ulCurrent; +} + +#ifdef __cplusplus +} +#endif + +#endif /* ATOMIC_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/croutine.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/croutine.h new file mode 100644 index 0000000..7534115 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/croutine.h @@ -0,0 +1,720 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 CO_ROUTINE_H +#define CO_ROUTINE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include croutine.h" +#endif + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Used to hide the implementation of the co-routine control block. The +control block structure however has to be included in the header due to +the macro implementation of the co-routine functionality. */ +typedef void * CoRoutineHandle_t; + +/* Defines the prototype to which co-routine functions must conform. */ +typedef void (*crCOROUTINE_CODE)( CoRoutineHandle_t, UBaseType_t ); + +typedef struct corCoRoutineControlBlock +{ + crCOROUTINE_CODE pxCoRoutineFunction; + ListItem_t xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ + ListItem_t xEventListItem; /*< List item used to place the CRCB in event lists. */ + UBaseType_t uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ + UBaseType_t uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ + uint16_t uxState; /*< Used internally by the co-routine implementation. */ +} CRCB_t; /* Co-routine control block. Note must be identical in size down to uxPriority with TCB_t. */ + +/** + * croutine. h + *
+ BaseType_t xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 UBaseType_t uxPriority,
+                                 UBaseType_t uxIndex
+                               );
+ * + * Create a new co-routine and add it to the list of co-routines that are + * ready to run. + * + * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine + * functions require special syntax - see the co-routine section of the WEB + * documentation for more information. + * + * @param uxPriority The priority with respect to other co-routines at which + * the co-routine will run. + * + * @param uxIndex Used to distinguish between different co-routines that + * execute the same function. See the example below and the co-routine section + * of the WEB documentation for further information. + * + * @return pdPASS if the co-routine was successfully created and added to a ready + * list, otherwise an error code defined with ProjDefs.h. + * + * Example usage: +
+ // Co-routine to be created.
+ void vFlashCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const TickType_t uxFlashRates[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how int32_t to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ uint8_t ucParameterToPass;
+ TaskHandle_t xHandle;
+
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   
+ * \defgroup xCoRoutineCreate xCoRoutineCreate + * \ingroup Tasks + */ +BaseType_t xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, UBaseType_t uxPriority, UBaseType_t uxIndex ); + + +/** + * croutine. h + *
+ void vCoRoutineSchedule( void );
+ * + * Run a co-routine. + * + * vCoRoutineSchedule() executes the highest priority co-routine that is able + * to run. The co-routine will execute until it either blocks, yields or is + * preempted by a task. Co-routines execute cooperatively so one + * co-routine cannot be preempted by another, but can be preempted by a task. + * + * If an application comprises of both tasks and co-routines then + * vCoRoutineSchedule should be called from the idle task (in an idle task + * hook). + * + * Example usage: +
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineSchedule() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ 
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule + * \ingroup Tasks + */ +void vCoRoutineSchedule( void ); + +/** + * croutine. h + *
+ crSTART( CoRoutineHandle_t xHandle );
+ * + * This macro MUST always be called at the start of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static int32_t ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crSTART( pxCRCB ) switch( ( ( CRCB_t * )( pxCRCB ) )->uxState ) { case 0: + +/** + * croutine. h + *
+ crEND();
+ * + * This macro MUST always be called at the end of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static int32_t ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crEND() } + +/* + * These macros are intended for internal use by the co-routine implementation + * only. The macros should not be used directly by application writers. + */ +#define crSET_STATE0( xHandle ) ( ( CRCB_t * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): +#define crSET_STATE1( xHandle ) ( ( CRCB_t * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): + +/** + * croutine. h + *
+ crDELAY( CoRoutineHandle_t xHandle, TickType_t xTicksToDelay );
+ * + * Delay a co-routine for a fixed period of time. + * + * crDELAY can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * @param xHandle The handle of the co-routine to delay. This is the xHandle + * parameter of the co-routine function. + * + * @param xTickToDelay The number of ticks that the co-routine should delay + * for. The actual amount of time this equates to is defined by + * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_PERIOD_MS + * can be used to convert ticks to milliseconds. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_PERIOD_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crDELAY crDELAY + * \ingroup Tasks + */ +#define crDELAY( xHandle, xTicksToDelay ) \ + if( ( xTicksToDelay ) > 0 ) \ + { \ + vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ + } \ + crSET_STATE0( ( xHandle ) ); + +/** + *
+ crQUEUE_SEND(
+                  CoRoutineHandle_t xHandle,
+                  QueueHandle_t pxQueue,
+                  void *pvItemToQueue,
+                  TickType_t xTicksToWait,
+                  BaseType_t *pxResult
+             )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_SEND can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue on which the data will be posted. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvItemToQueue A pointer to the data being posted onto the queue. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied from pvItemToQueue into the queue + * itself. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for space to become available on the queue, should space not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_PERIOD_MS can be used to convert ticks to milliseconds (see example + * below). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully posted onto the queue, otherwise it will be set to an + * error defined within ProjDefs.h. + * + * Example usage: +
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static BaseType_t xNumberToPost = 0;
+ static BaseType_t xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }
+ * \defgroup crQUEUE_SEND crQUEUE_SEND + * \ingroup Tasks + */ +#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_RECEIVE(
+                     CoRoutineHandle_t xHandle,
+                     QueueHandle_t pxQueue,
+                     void *pvBuffer,
+                     TickType_t xTicksToWait,
+                     BaseType_t *pxResult
+                 )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_RECEIVE can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue from which the data will be received. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvBuffer The buffer into which the received item is to be copied. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied into pvBuffer. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for data to become available from the queue, should data not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_PERIOD_MS can be used to convert ticks to milliseconds (see the + * crQUEUE_SEND example). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully retrieved from the queue, otherwise it will be set to + * an error code as defined within ProjDefs.h. + * + * Example usage: +
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static BaseType_t xResult;
+ static UBaseType_t uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ + } \ + if( *( pxResult ) == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *( pxResult ) = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            QueueHandle_t pxQueue,
+                            void *pvItemToQueue,
+                            BaseType_t xCoRoutinePreviouslyWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue + * that is being used from within a co-routine. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto + * the same queue multiple times from a single interrupt. The first call + * should always pass in pdFALSE. Subsequent calls should pass in + * the value returned from the previous call. + * + * @return pdTRUE if a co-routine was woken by posting onto the queue. This is + * used by the ISR to determine if a context switch may be required following + * the ISR. + * + * Example usage: +
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ char cRxedChar;
+ BaseType_t xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ BaseType_t xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) + + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            QueueHandle_t pxQueue,
+                            void *pvBuffer,
+                            BaseType_t * pxCoRoutineWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data + * from a queue that is being used from within a co-routine (a co-routine + * posted to the queue). + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvBuffer A pointer to a buffer into which the received item will be + * placed. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from the queue into + * pvBuffer. + * + * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become + * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a + * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise + * *pxCoRoutineWoken will remain unchanged. + * + * @return pdTRUE an item was successfully received from the queue, otherwise + * pdFALSE. + * + * Example usage: +
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ BaseType_t xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ BaseType_t xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) + +/* + * This function is intended for internal use by the co-routine macros only. + * The macro nature of the co-routine implementation requires that the + * prototype appears here. The function should not be used by application + * writers. + * + * Removes the current co-routine from its ready list and places it in the + * appropriate delayed list. + */ +void vCoRoutineAddToDelayedList( TickType_t xTicksToDelay, List_t *pxEventList ); + +/* + * This function is intended for internal use by the queue implementation only. + * The function should not be used by application writers. + * + * Removes the highest priority co-routine from the event list and places it in + * the pending ready list. + */ +BaseType_t xCoRoutineRemoveFromEventList( const List_t *pxEventList ); + +#ifdef __cplusplus +} +#endif + +#endif /* CO_ROUTINE_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/deprecated_definitions.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/deprecated_definitions.h new file mode 100644 index 0000000..e791b9a --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/deprecated_definitions.h @@ -0,0 +1,279 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 DEPRECATED_DEFINITIONS_H +#define DEPRECATED_DEFINITIONS_H + + +/* Each FreeRTOS port has a unique portmacro.h header file. Originally a +pre-processor definition was used to ensure the pre-processor found the correct +portmacro.h file for the port being used. That scheme was deprecated in favour +of setting the compiler's include path such that it found the correct +portmacro.h file - removing the need for the constant and allowing the +portmacro.h file to be located anywhere in relation to the port being used. The +definitions below remain in the code for backward compatibility only. New +projects should not use them. */ + +#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT + #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT + #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef GCC_MEGA_AVR + #include "../portable/GCC/ATMega323/portmacro.h" +#endif + +#ifdef IAR_MEGA_AVR + #include "../portable/IAR/ATMega323/portmacro.h" +#endif + +#ifdef MPLAB_PIC24_PORT + #include "../../Source/portable/MPLAB/PIC24_dsPIC/portmacro.h" +#endif + +#ifdef MPLAB_DSPIC_PORT + #include "../../Source/portable/MPLAB/PIC24_dsPIC/portmacro.h" +#endif + +#ifdef MPLAB_PIC18F_PORT + #include "../../Source/portable/MPLAB/PIC18F/portmacro.h" +#endif + +#ifdef MPLAB_PIC32MX_PORT + #include "../../Source/portable/MPLAB/PIC32MX/portmacro.h" +#endif + +#ifdef _FEDPICC + #include "libFreeRTOS/Include/portmacro.h" +#endif + +#ifdef SDCC_CYGNAL + #include "../../Source/portable/SDCC/Cygnal/portmacro.h" +#endif + +#ifdef GCC_ARM7 + #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" +#endif + +#ifdef GCC_ARM7_ECLIPSE + #include "portmacro.h" +#endif + +#ifdef ROWLEY_LPC23xx + #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" +#endif + +#ifdef IAR_MSP430 + #include "..\..\Source\portable\IAR\MSP430\portmacro.h" +#endif + +#ifdef GCC_MSP430 + #include "../../Source/portable/GCC/MSP430F449/portmacro.h" +#endif + +#ifdef ROWLEY_MSP430 + #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" +#endif + +#ifdef ARM7_LPC21xx_KEIL_RVDS + #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" +#endif + +#ifdef SAM7_GCC + #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" +#endif + +#ifdef SAM7_IAR + #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" +#endif + +#ifdef SAM9XE_IAR + #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" +#endif + +#ifdef LPC2000_IAR + #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" +#endif + +#ifdef STR71X_IAR + #include "..\..\Source\portable\IAR\STR71x\portmacro.h" +#endif + +#ifdef STR75X_IAR + #include "..\..\Source\portable\IAR\STR75x\portmacro.h" +#endif + +#ifdef STR75X_GCC + #include "..\..\Source\portable\GCC\STR75x\portmacro.h" +#endif + +#ifdef STR91X_IAR + #include "..\..\Source\portable\IAR\STR91x\portmacro.h" +#endif + +#ifdef GCC_H8S + #include "../../Source/portable/GCC/H8S2329/portmacro.h" +#endif + +#ifdef GCC_AT91FR40008 + #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" +#endif + +#ifdef RVDS_ARMCM3_LM3S102 + #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3_LM3S102 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARM_CM3 + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARMCM3_LM + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef HCS12_CODE_WARRIOR + #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" +#endif + +#ifdef MICROBLAZE_GCC + #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" +#endif + +#ifdef TERN_EE + #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" +#endif + +#ifdef GCC_HCS12 + #include "../../Source/portable/GCC/HCS12/portmacro.h" +#endif + +#ifdef GCC_MCF5235 + #include "../../Source/portable/GCC/MCF5235/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_GCC + #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_CODEWARRIOR + #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" +#endif + +#ifdef GCC_PPC405 + #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" +#endif + +#ifdef GCC_PPC440 + #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" +#endif + +#ifdef _16FX_SOFTUNE + #include "..\..\Source\portable\Softune\MB96340\portmacro.h" +#endif + +#ifdef BCC_INDUSTRIAL_PC_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef BCC_FLASH_LITE_186_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef __GNUC__ + #ifdef __AVR32_AVR32A__ + #include "portmacro.h" + #endif +#endif + +#ifdef __ICCAVR32__ + #ifdef __CORE__ + #if __CORE__ == __AVR32A__ + #include "portmacro.h" + #endif + #endif +#endif + +#ifdef __91467D + #include "portmacro.h" +#endif + +#ifdef __96340 + #include "portmacro.h" +#endif + + +#ifdef __IAR_V850ES_Fx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3_L__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Hx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3L__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#endif /* DEPRECATED_DEFINITIONS_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/event_groups.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/event_groups.h new file mode 100644 index 0000000..ff8b0cc --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/event_groups.h @@ -0,0 +1,757 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 EVENT_GROUPS_H +#define EVENT_GROUPS_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include event_groups.h" +#endif + +/* FreeRTOS includes. */ +#include "timers.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * An event group is a collection of bits to which an application can assign a + * meaning. For example, an application may create an event group to convey + * the status of various CAN bus related events in which bit 0 might mean "A CAN + * message has been received and is ready for processing", bit 1 might mean "The + * application has queued a message that is ready for sending onto the CAN + * network", and bit 2 might mean "It is time to send a SYNC message onto the + * CAN network" etc. A task can then test the bit values to see which events + * are active, and optionally enter the Blocked state to wait for a specified + * bit or a group of specified bits to be active. To continue the CAN bus + * example, a CAN controlling task can enter the Blocked state (and therefore + * not consume any processing time) until either bit 0, bit 1 or bit 2 are + * active, at which time the bit that was actually active would inform the task + * which action it had to take (process a received message, send a message, or + * send a SYNC). + * + * The event groups implementation contains intelligence to avoid race + * conditions that would otherwise occur were an application to use a simple + * variable for the same purpose. This is particularly important with respect + * to when a bit within an event group is to be cleared, and when bits have to + * be set and then tested atomically - as is the case where event groups are + * used to create a synchronisation point between multiple tasks (a + * 'rendezvous'). + * + * \defgroup EventGroup + */ + + + +/** + * event_groups.h + * + * Type by which event groups are referenced. For example, a call to + * xEventGroupCreate() returns an EventGroupHandle_t variable that can then + * be used as a parameter to other event group functions. + * + * \defgroup EventGroupHandle_t EventGroupHandle_t + * \ingroup EventGroup + */ +struct EventGroupDef_t; +typedef struct EventGroupDef_t * EventGroupHandle_t; + +/* + * The type that holds event bits always matches TickType_t - therefore the + * number of bits it holds is set by configUSE_16_BIT_TICKS (16 bits if set to 1, + * 32 bits if set to 0. + * + * \defgroup EventBits_t EventBits_t + * \ingroup EventGroup + */ +typedef TickType_t EventBits_t; + +/** + * event_groups.h + *
+ EventGroupHandle_t xEventGroupCreate( void );
+ 
+ * + * Create a new event group. + * + * Internally, within the FreeRTOS implementation, event groups use a [small] + * block of memory, in which the event group's structure is stored. If an event + * groups is created using xEventGropuCreate() then the required memory is + * automatically dynamically allocated inside the xEventGroupCreate() function. + * (see http://www.freertos.org/a00111.html). If an event group is created + * using xEventGropuCreateStatic() then the application writer must instead + * provide the memory that will get used by the event group. + * xEventGroupCreateStatic() therefore allows an event group to be created + * without using any dynamic memory allocation. + * + * Although event groups are not related to ticks, for internal implementation + * reasons the number of bits available for use in an event group is dependent + * on the configUSE_16_BIT_TICKS setting in FreeRTOSConfig.h. If + * configUSE_16_BIT_TICKS is 1 then each event group contains 8 usable bits (bit + * 0 to bit 7). If configUSE_16_BIT_TICKS is set to 0 then each event group has + * 24 usable bits (bit 0 to bit 23). The EventBits_t type is used to store + * event bits within an event group. + * + * @return If the event group was created then a handle to the event group is + * returned. If there was insufficient FreeRTOS heap available to create the + * event group then NULL is returned. See http://www.freertos.org/a00111.html + * + * Example usage: +
+	// Declare a variable to hold the created event group.
+	EventGroupHandle_t xCreatedEventGroup;
+
+	// Attempt to create the event group.
+	xCreatedEventGroup = xEventGroupCreate();
+
+	// Was the event group created successfully?
+	if( xCreatedEventGroup == NULL )
+	{
+		// The event group was not created because there was insufficient
+		// FreeRTOS heap available.
+	}
+	else
+	{
+		// The event group was created.
+	}
+   
+ * \defgroup xEventGroupCreate xEventGroupCreate + * \ingroup EventGroup + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + EventGroupHandle_t xEventGroupCreate( void ) PRIVILEGED_FUNCTION; +#endif + +/** + * event_groups.h + *
+ EventGroupHandle_t xEventGroupCreateStatic( EventGroupHandle_t * pxEventGroupBuffer );
+ 
+ * + * Create a new event group. + * + * Internally, within the FreeRTOS implementation, event groups use a [small] + * block of memory, in which the event group's structure is stored. If an event + * groups is created using xEventGropuCreate() then the required memory is + * automatically dynamically allocated inside the xEventGroupCreate() function. + * (see http://www.freertos.org/a00111.html). If an event group is created + * using xEventGropuCreateStatic() then the application writer must instead + * provide the memory that will get used by the event group. + * xEventGroupCreateStatic() therefore allows an event group to be created + * without using any dynamic memory allocation. + * + * Although event groups are not related to ticks, for internal implementation + * reasons the number of bits available for use in an event group is dependent + * on the configUSE_16_BIT_TICKS setting in FreeRTOSConfig.h. If + * configUSE_16_BIT_TICKS is 1 then each event group contains 8 usable bits (bit + * 0 to bit 7). If configUSE_16_BIT_TICKS is set to 0 then each event group has + * 24 usable bits (bit 0 to bit 23). The EventBits_t type is used to store + * event bits within an event group. + * + * @param pxEventGroupBuffer pxEventGroupBuffer must point to a variable of type + * StaticEventGroup_t, which will be then be used to hold the event group's data + * structures, removing the need for the memory to be allocated dynamically. + * + * @return If the event group was created then a handle to the event group is + * returned. If pxEventGroupBuffer was NULL then NULL is returned. + * + * Example usage: +
+	// StaticEventGroup_t is a publicly accessible structure that has the same
+	// size and alignment requirements as the real event group structure.  It is
+	// provided as a mechanism for applications to know the size of the event
+	// group (which is dependent on the architecture and configuration file
+	// settings) without breaking the strict data hiding policy by exposing the
+	// real event group internals.  This StaticEventGroup_t variable is passed
+	// into the xSemaphoreCreateEventGroupStatic() function and is used to store
+	// the event group's data structures
+	StaticEventGroup_t xEventGroupBuffer;
+
+	// Create the event group without dynamically allocating any memory.
+	xEventGroup = xEventGroupCreateStatic( &xEventGroupBuffer );
+   
+ */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + EventGroupHandle_t xEventGroupCreateStatic( StaticEventGroup_t *pxEventGroupBuffer ) PRIVILEGED_FUNCTION; +#endif + +/** + * event_groups.h + *
+	EventBits_t xEventGroupWaitBits( 	EventGroupHandle_t xEventGroup,
+										const EventBits_t uxBitsToWaitFor,
+										const BaseType_t xClearOnExit,
+										const BaseType_t xWaitForAllBits,
+										const TickType_t xTicksToWait );
+ 
+ * + * [Potentially] block to wait for one or more bits to be set within a + * previously created event group. + * + * This function cannot be called from an interrupt. + * + * @param xEventGroup The event group in which the bits are being tested. The + * event group must have previously been created using a call to + * xEventGroupCreate(). + * + * @param uxBitsToWaitFor A bitwise value that indicates the bit or bits to test + * inside the event group. For example, to wait for bit 0 and/or bit 2 set + * uxBitsToWaitFor to 0x05. To wait for bits 0 and/or bit 1 and/or bit 2 set + * uxBitsToWaitFor to 0x07. Etc. + * + * @param xClearOnExit If xClearOnExit is set to pdTRUE then any bits within + * uxBitsToWaitFor that are set within the event group will be cleared before + * xEventGroupWaitBits() returns if the wait condition was met (if the function + * returns for a reason other than a timeout). If xClearOnExit is set to + * pdFALSE then the bits set in the event group are not altered when the call to + * xEventGroupWaitBits() returns. + * + * @param xWaitForAllBits If xWaitForAllBits is set to pdTRUE then + * xEventGroupWaitBits() will return when either all the bits in uxBitsToWaitFor + * are set or the specified block time expires. If xWaitForAllBits is set to + * pdFALSE then xEventGroupWaitBits() will return when any one of the bits set + * in uxBitsToWaitFor is set or the specified block time expires. The block + * time is specified by the xTicksToWait parameter. + * + * @param xTicksToWait The maximum amount of time (specified in 'ticks') to wait + * for one/all (depending on the xWaitForAllBits value) of the bits specified by + * uxBitsToWaitFor to become set. + * + * @return The value of the event group at the time either the bits being waited + * for became set, or the block time expired. Test the return value to know + * which bits were set. If xEventGroupWaitBits() returned because its timeout + * expired then not all the bits being waited for will be set. If + * xEventGroupWaitBits() returned because the bits it was waiting for were set + * then the returned value is the event group value before any bits were + * automatically cleared in the case that xClearOnExit parameter was set to + * pdTRUE. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+   const TickType_t xTicksToWait = 100 / portTICK_PERIOD_MS;
+
+		// Wait a maximum of 100ms for either bit 0 or bit 4 to be set within
+		// the event group.  Clear the bits before exiting.
+		uxBits = xEventGroupWaitBits(
+					xEventGroup,	// The event group being tested.
+					BIT_0 | BIT_4,	// The bits within the event group to wait for.
+					pdTRUE,			// BIT_0 and BIT_4 should be cleared before returning.
+					pdFALSE,		// Don't wait for both bits, either bit will do.
+					xTicksToWait );	// Wait a maximum of 100ms for either bit to be set.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// xEventGroupWaitBits() returned because both bits were set.
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// xEventGroupWaitBits() returned because just BIT_0 was set.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// xEventGroupWaitBits() returned because just BIT_4 was set.
+		}
+		else
+		{
+			// xEventGroupWaitBits() returned because xTicksToWait ticks passed
+			// without either BIT_0 or BIT_4 becoming set.
+		}
+   }
+   
+ * \defgroup xEventGroupWaitBits xEventGroupWaitBits + * \ingroup EventGroup + */ +EventBits_t xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * event_groups.h + *
+	EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear );
+ 
+ * + * Clear bits within an event group. This function cannot be called from an + * interrupt. + * + * @param xEventGroup The event group in which the bits are to be cleared. + * + * @param uxBitsToClear A bitwise value that indicates the bit or bits to clear + * in the event group. For example, to clear bit 3 only, set uxBitsToClear to + * 0x08. To clear bit 3 and bit 0 set uxBitsToClear to 0x09. + * + * @return The value of the event group before the specified bits were cleared. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+
+		// Clear bit 0 and bit 4 in xEventGroup.
+		uxBits = xEventGroupClearBits(
+								xEventGroup,	// The event group being updated.
+								BIT_0 | BIT_4 );// The bits being cleared.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// Both bit 0 and bit 4 were set before xEventGroupClearBits() was
+			// called.  Both will now be clear (not set).
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// Bit 0 was set before xEventGroupClearBits() was called.  It will
+			// now be clear.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// Bit 4 was set before xEventGroupClearBits() was called.  It will
+			// now be clear.
+		}
+		else
+		{
+			// Neither bit 0 nor bit 4 were set in the first place.
+		}
+   }
+   
+ * \defgroup xEventGroupClearBits xEventGroupClearBits + * \ingroup EventGroup + */ +EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) PRIVILEGED_FUNCTION; + +/** + * event_groups.h + *
+	BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet );
+ 
+ * + * A version of xEventGroupClearBits() that can be called from an interrupt. + * + * Setting bits in an event group is not a deterministic operation because there + * are an unknown number of tasks that may be waiting for the bit or bits being + * set. FreeRTOS does not allow nondeterministic operations to be performed + * while interrupts are disabled, so protects event groups that are accessed + * from tasks by suspending the scheduler rather than disabling interrupts. As + * a result event groups cannot be accessed directly from an interrupt service + * routine. Therefore xEventGroupClearBitsFromISR() sends a message to the + * timer task to have the clear operation performed in the context of the timer + * task. + * + * @param xEventGroup The event group in which the bits are to be cleared. + * + * @param uxBitsToClear A bitwise value that indicates the bit or bits to clear. + * For example, to clear bit 3 only, set uxBitsToClear to 0x08. To clear bit 3 + * and bit 0 set uxBitsToClear to 0x09. + * + * @return If the request to execute the function was posted successfully then + * pdPASS is returned, otherwise pdFALSE is returned. pdFALSE will be returned + * if the timer service queue was full. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   // An event group which it is assumed has already been created by a call to
+   // xEventGroupCreate().
+   EventGroupHandle_t xEventGroup;
+
+   void anInterruptHandler( void )
+   {
+		// Clear bit 0 and bit 4 in xEventGroup.
+		xResult = xEventGroupClearBitsFromISR(
+							xEventGroup,	 // The event group being updated.
+							BIT_0 | BIT_4 ); // The bits being set.
+
+		if( xResult == pdPASS )
+		{
+			// The message was posted successfully.
+		}
+  }
+   
+ * \defgroup xEventGroupClearBitsFromISR xEventGroupClearBitsFromISR + * \ingroup EventGroup + */ +#if( configUSE_TRACE_FACILITY == 1 ) + BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) PRIVILEGED_FUNCTION; +#else + #define xEventGroupClearBitsFromISR( xEventGroup, uxBitsToClear ) xTimerPendFunctionCallFromISR( vEventGroupClearBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToClear, NULL ) +#endif + +/** + * event_groups.h + *
+	EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet );
+ 
+ * + * Set bits within an event group. + * This function cannot be called from an interrupt. xEventGroupSetBitsFromISR() + * is a version that can be called from an interrupt. + * + * Setting bits in an event group will automatically unblock tasks that are + * blocked waiting for the bits. + * + * @param xEventGroup The event group in which the bits are to be set. + * + * @param uxBitsToSet A bitwise value that indicates the bit or bits to set. + * For example, to set bit 3 only, set uxBitsToSet to 0x08. To set bit 3 + * and bit 0 set uxBitsToSet to 0x09. + * + * @return The value of the event group at the time the call to + * xEventGroupSetBits() returns. There are two reasons why the returned value + * might have the bits specified by the uxBitsToSet parameter cleared. First, + * if setting a bit results in a task that was waiting for the bit leaving the + * blocked state then it is possible the bit will be cleared automatically + * (see the xClearBitOnExit parameter of xEventGroupWaitBits()). Second, any + * unblocked (or otherwise Ready state) task that has a priority above that of + * the task that called xEventGroupSetBits() will execute and may change the + * event group value before the call to xEventGroupSetBits() returns. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+
+		// Set bit 0 and bit 4 in xEventGroup.
+		uxBits = xEventGroupSetBits(
+							xEventGroup,	// The event group being updated.
+							BIT_0 | BIT_4 );// The bits being set.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// Both bit 0 and bit 4 remained set when the function returned.
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// Bit 0 remained set when the function returned, but bit 4 was
+			// cleared.  It might be that bit 4 was cleared automatically as a
+			// task that was waiting for bit 4 was removed from the Blocked
+			// state.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// Bit 4 remained set when the function returned, but bit 0 was
+			// cleared.  It might be that bit 0 was cleared automatically as a
+			// task that was waiting for bit 0 was removed from the Blocked
+			// state.
+		}
+		else
+		{
+			// Neither bit 0 nor bit 4 remained set.  It might be that a task
+			// was waiting for both of the bits to be set, and the bits were
+			// cleared as the task left the Blocked state.
+		}
+   }
+   
+ * \defgroup xEventGroupSetBits xEventGroupSetBits + * \ingroup EventGroup + */ +EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) PRIVILEGED_FUNCTION; + +/** + * event_groups.h + *
+	BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken );
+ 
+ * + * A version of xEventGroupSetBits() that can be called from an interrupt. + * + * Setting bits in an event group is not a deterministic operation because there + * are an unknown number of tasks that may be waiting for the bit or bits being + * set. FreeRTOS does not allow nondeterministic operations to be performed in + * interrupts or from critical sections. Therefore xEventGroupSetBitsFromISR() + * sends a message to the timer task to have the set operation performed in the + * context of the timer task - where a scheduler lock is used in place of a + * critical section. + * + * @param xEventGroup The event group in which the bits are to be set. + * + * @param uxBitsToSet A bitwise value that indicates the bit or bits to set. + * For example, to set bit 3 only, set uxBitsToSet to 0x08. To set bit 3 + * and bit 0 set uxBitsToSet to 0x09. + * + * @param pxHigherPriorityTaskWoken As mentioned above, calling this function + * will result in a message being sent to the timer daemon task. If the + * priority of the timer daemon task is higher than the priority of the + * currently running task (the task the interrupt interrupted) then + * *pxHigherPriorityTaskWoken will be set to pdTRUE by + * xEventGroupSetBitsFromISR(), indicating that a context switch should be + * requested before the interrupt exits. For that reason + * *pxHigherPriorityTaskWoken must be initialised to pdFALSE. See the + * example code below. + * + * @return If the request to execute the function was posted successfully then + * pdPASS is returned, otherwise pdFALSE is returned. pdFALSE will be returned + * if the timer service queue was full. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   // An event group which it is assumed has already been created by a call to
+   // xEventGroupCreate().
+   EventGroupHandle_t xEventGroup;
+
+   void anInterruptHandler( void )
+   {
+   BaseType_t xHigherPriorityTaskWoken, xResult;
+
+		// xHigherPriorityTaskWoken must be initialised to pdFALSE.
+		xHigherPriorityTaskWoken = pdFALSE;
+
+		// Set bit 0 and bit 4 in xEventGroup.
+		xResult = xEventGroupSetBitsFromISR(
+							xEventGroup,	// The event group being updated.
+							BIT_0 | BIT_4   // The bits being set.
+							&xHigherPriorityTaskWoken );
+
+		// Was the message posted successfully?
+		if( xResult == pdPASS )
+		{
+			// If xHigherPriorityTaskWoken is now set to pdTRUE then a context
+			// switch should be requested.  The macro used is port specific and
+			// will be either portYIELD_FROM_ISR() or portEND_SWITCHING_ISR() -
+			// refer to the documentation page for the port being used.
+			portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+		}
+  }
+   
+ * \defgroup xEventGroupSetBitsFromISR xEventGroupSetBitsFromISR + * \ingroup EventGroup + */ +#if( configUSE_TRACE_FACILITY == 1 ) + BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; +#else + #define xEventGroupSetBitsFromISR( xEventGroup, uxBitsToSet, pxHigherPriorityTaskWoken ) xTimerPendFunctionCallFromISR( vEventGroupSetBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToSet, pxHigherPriorityTaskWoken ) +#endif + +/** + * event_groups.h + *
+	EventBits_t xEventGroupSync(	EventGroupHandle_t xEventGroup,
+									const EventBits_t uxBitsToSet,
+									const EventBits_t uxBitsToWaitFor,
+									TickType_t xTicksToWait );
+ 
+ * + * Atomically set bits within an event group, then wait for a combination of + * bits to be set within the same event group. This functionality is typically + * used to synchronise multiple tasks, where each task has to wait for the other + * tasks to reach a synchronisation point before proceeding. + * + * This function cannot be used from an interrupt. + * + * The function will return before its block time expires if the bits specified + * by the uxBitsToWait parameter are set, or become set within that time. In + * this case all the bits specified by uxBitsToWait will be automatically + * cleared before the function returns. + * + * @param xEventGroup The event group in which the bits are being tested. The + * event group must have previously been created using a call to + * xEventGroupCreate(). + * + * @param uxBitsToSet The bits to set in the event group before determining + * if, and possibly waiting for, all the bits specified by the uxBitsToWait + * parameter are set. + * + * @param uxBitsToWaitFor A bitwise value that indicates the bit or bits to test + * inside the event group. For example, to wait for bit 0 and bit 2 set + * uxBitsToWaitFor to 0x05. To wait for bits 0 and bit 1 and bit 2 set + * uxBitsToWaitFor to 0x07. Etc. + * + * @param xTicksToWait The maximum amount of time (specified in 'ticks') to wait + * for all of the bits specified by uxBitsToWaitFor to become set. + * + * @return The value of the event group at the time either the bits being waited + * for became set, or the block time expired. Test the return value to know + * which bits were set. If xEventGroupSync() returned because its timeout + * expired then not all the bits being waited for will be set. If + * xEventGroupSync() returned because all the bits it was waiting for were + * set then the returned value is the event group value before any bits were + * automatically cleared. + * + * Example usage: +
+ // Bits used by the three tasks.
+ #define TASK_0_BIT		( 1 << 0 )
+ #define TASK_1_BIT		( 1 << 1 )
+ #define TASK_2_BIT		( 1 << 2 )
+
+ #define ALL_SYNC_BITS ( TASK_0_BIT | TASK_1_BIT | TASK_2_BIT )
+
+ // Use an event group to synchronise three tasks.  It is assumed this event
+ // group has already been created elsewhere.
+ EventGroupHandle_t xEventBits;
+
+ void vTask0( void *pvParameters )
+ {
+ EventBits_t uxReturn;
+ TickType_t xTicksToWait = 100 / portTICK_PERIOD_MS;
+
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 0 in the event flag to note this task has reached the
+		// sync point.  The other two tasks will set the other two bits defined
+		// by ALL_SYNC_BITS.  All three tasks have reached the synchronisation
+		// point when all the ALL_SYNC_BITS are set.  Wait a maximum of 100ms
+		// for this to happen.
+		uxReturn = xEventGroupSync( xEventBits, TASK_0_BIT, ALL_SYNC_BITS, xTicksToWait );
+
+		if( ( uxReturn & ALL_SYNC_BITS ) == ALL_SYNC_BITS )
+		{
+			// All three tasks reached the synchronisation point before the call
+			// to xEventGroupSync() timed out.
+		}
+	}
+ }
+
+ void vTask1( void *pvParameters )
+ {
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 1 in the event flag to note this task has reached the
+		// synchronisation point.  The other two tasks will set the other two
+		// bits defined by ALL_SYNC_BITS.  All three tasks have reached the
+		// synchronisation point when all the ALL_SYNC_BITS are set.  Wait
+		// indefinitely for this to happen.
+		xEventGroupSync( xEventBits, TASK_1_BIT, ALL_SYNC_BITS, portMAX_DELAY );
+
+		// xEventGroupSync() was called with an indefinite block time, so
+		// this task will only reach here if the syncrhonisation was made by all
+		// three tasks, so there is no need to test the return value.
+	 }
+ }
+
+ void vTask2( void *pvParameters )
+ {
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 2 in the event flag to note this task has reached the
+		// synchronisation point.  The other two tasks will set the other two
+		// bits defined by ALL_SYNC_BITS.  All three tasks have reached the
+		// synchronisation point when all the ALL_SYNC_BITS are set.  Wait
+		// indefinitely for this to happen.
+		xEventGroupSync( xEventBits, TASK_2_BIT, ALL_SYNC_BITS, portMAX_DELAY );
+
+		// xEventGroupSync() was called with an indefinite block time, so
+		// this task will only reach here if the syncrhonisation was made by all
+		// three tasks, so there is no need to test the return value.
+	}
+ }
+
+ 
+ * \defgroup xEventGroupSync xEventGroupSync + * \ingroup EventGroup + */ +EventBits_t xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + + +/** + * event_groups.h + *
+	EventBits_t xEventGroupGetBits( EventGroupHandle_t xEventGroup );
+ 
+ * + * Returns the current value of the bits in an event group. This function + * cannot be used from an interrupt. + * + * @param xEventGroup The event group being queried. + * + * @return The event group bits at the time xEventGroupGetBits() was called. + * + * \defgroup xEventGroupGetBits xEventGroupGetBits + * \ingroup EventGroup + */ +#define xEventGroupGetBits( xEventGroup ) xEventGroupClearBits( xEventGroup, 0 ) + +/** + * event_groups.h + *
+	EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup );
+ 
+ * + * A version of xEventGroupGetBits() that can be called from an ISR. + * + * @param xEventGroup The event group being queried. + * + * @return The event group bits at the time xEventGroupGetBitsFromISR() was called. + * + * \defgroup xEventGroupGetBitsFromISR xEventGroupGetBitsFromISR + * \ingroup EventGroup + */ +EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup ) PRIVILEGED_FUNCTION; + +/** + * event_groups.h + *
+	void xEventGroupDelete( EventGroupHandle_t xEventGroup );
+ 
+ * + * Delete an event group that was previously created by a call to + * xEventGroupCreate(). Tasks that are blocked on the event group will be + * unblocked and obtain 0 as the event group's value. + * + * @param xEventGroup The event group being deleted. + */ +void vEventGroupDelete( EventGroupHandle_t xEventGroup ) PRIVILEGED_FUNCTION; + +/* For internal use only. */ +void vEventGroupSetBitsCallback( void *pvEventGroup, const uint32_t ulBitsToSet ) PRIVILEGED_FUNCTION; +void vEventGroupClearBitsCallback( void *pvEventGroup, const uint32_t ulBitsToClear ) PRIVILEGED_FUNCTION; + + +#if (configUSE_TRACE_FACILITY == 1) + UBaseType_t uxEventGroupGetNumber( void* xEventGroup ) PRIVILEGED_FUNCTION; + void vEventGroupSetNumber( void* xEventGroup, UBaseType_t uxEventGroupNumber ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* EVENT_GROUPS_H */ + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/list.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/list.h new file mode 100644 index 0000000..7dc5a35 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/list.h @@ -0,0 +1,412 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* + * This is the list implementation used by the scheduler. While it is tailored + * heavily for the schedulers needs, it is also available for use by + * application code. + * + * list_ts can only store pointers to list_item_ts. Each ListItem_t contains a + * numeric value (xItemValue). Most of the time the lists are sorted in + * descending item value order. + * + * Lists are created already containing one list item. The value of this + * item is the maximum possible that can be stored, it is therefore always at + * the end of the list and acts as a marker. The list member pxHead always + * points to this marker - even though it is at the tail of the list. This + * is because the tail contains a wrap back pointer to the true head of + * the list. + * + * In addition to it's value, each list item contains a pointer to the next + * item in the list (pxNext), a pointer to the list it is in (pxContainer) + * and a pointer to back to the object that contains it. These later two + * pointers are included for efficiency of list manipulation. There is + * effectively a two way link between the object containing the list item and + * the list item itself. + * + * + * \page ListIntroduction List Implementation + * \ingroup FreeRTOSIntro + */ + +#ifndef INC_FREERTOS_H + #error FreeRTOS.h must be included before list.h +#endif + +#ifndef LIST_H +#define LIST_H + +/* + * The list structure members are modified from within interrupts, and therefore + * by rights should be declared volatile. However, they are only modified in a + * functionally atomic way (within critical sections of with the scheduler + * suspended) and are either passed by reference into a function or indexed via + * a volatile variable. Therefore, in all use cases tested so far, the volatile + * qualifier can be omitted in order to provide a moderate performance + * improvement without adversely affecting functional behaviour. The assembly + * instructions generated by the IAR, ARM and GCC compilers when the respective + * compiler's options were set for maximum optimisation has been inspected and + * deemed to be as intended. That said, as compiler technology advances, and + * especially if aggressive cross module optimisation is used (a use case that + * has not been exercised to any great extend) then it is feasible that the + * volatile qualifier will be needed for correct optimisation. It is expected + * that a compiler removing essential code because, without the volatile + * qualifier on the list structure members and with aggressive cross module + * optimisation, the compiler deemed the code unnecessary will result in + * complete and obvious failure of the scheduler. If this is ever experienced + * then the volatile qualifier can be inserted in the relevant places within the + * list structures by simply defining configLIST_VOLATILE to volatile in + * FreeRTOSConfig.h (as per the example at the bottom of this comment block). + * If configLIST_VOLATILE is not defined then the preprocessor directives below + * will simply #define configLIST_VOLATILE away completely. + * + * To use volatile list structure members then add the following line to + * FreeRTOSConfig.h (without the quotes): + * "#define configLIST_VOLATILE volatile" + */ +#ifndef configLIST_VOLATILE + #define configLIST_VOLATILE +#endif /* configSUPPORT_CROSS_MODULE_OPTIMISATION */ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Macros that can be used to place known values within the list structures, +then check that the known values do not get corrupted during the execution of +the application. These may catch the list data structures being overwritten in +memory. They will not catch data errors caused by incorrect configuration or +use of FreeRTOS.*/ +#if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 0 ) + /* Define the macros to do nothing. */ + #define listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE + #define listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE + #define listFIRST_LIST_INTEGRITY_CHECK_VALUE + #define listSECOND_LIST_INTEGRITY_CHECK_VALUE + #define listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ) + #define listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ) + #define listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList ) + #define listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList ) + #define listTEST_LIST_ITEM_INTEGRITY( pxItem ) + #define listTEST_LIST_INTEGRITY( pxList ) +#else + /* Define macros that add new members into the list structures. */ + #define listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE TickType_t xListItemIntegrityValue1; + #define listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE TickType_t xListItemIntegrityValue2; + #define listFIRST_LIST_INTEGRITY_CHECK_VALUE TickType_t xListIntegrityValue1; + #define listSECOND_LIST_INTEGRITY_CHECK_VALUE TickType_t xListIntegrityValue2; + + /* Define macros that set the new structure members to known values. */ + #define listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ) ( pxItem )->xListItemIntegrityValue1 = pdINTEGRITY_CHECK_VALUE + #define listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ) ( pxItem )->xListItemIntegrityValue2 = pdINTEGRITY_CHECK_VALUE + #define listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList ) ( pxList )->xListIntegrityValue1 = pdINTEGRITY_CHECK_VALUE + #define listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList ) ( pxList )->xListIntegrityValue2 = pdINTEGRITY_CHECK_VALUE + + /* Define macros that will assert if one of the structure members does not + contain its expected value. */ + #define listTEST_LIST_ITEM_INTEGRITY( pxItem ) configASSERT( ( ( pxItem )->xListItemIntegrityValue1 == pdINTEGRITY_CHECK_VALUE ) && ( ( pxItem )->xListItemIntegrityValue2 == pdINTEGRITY_CHECK_VALUE ) ) + #define listTEST_LIST_INTEGRITY( pxList ) configASSERT( ( ( pxList )->xListIntegrityValue1 == pdINTEGRITY_CHECK_VALUE ) && ( ( pxList )->xListIntegrityValue2 == pdINTEGRITY_CHECK_VALUE ) ) +#endif /* configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES */ + + +/* + * Definition of the only type of object that a list can contain. + */ +struct xLIST; +struct xLIST_ITEM +{ + listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + configLIST_VOLATILE TickType_t xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ + struct xLIST_ITEM * configLIST_VOLATILE pxNext; /*< Pointer to the next ListItem_t in the list. */ + struct xLIST_ITEM * configLIST_VOLATILE pxPrevious; /*< Pointer to the previous ListItem_t in the list. */ + void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ + struct xLIST * configLIST_VOLATILE pxContainer; /*< Pointer to the list in which this list item is placed (if any). */ + listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ +}; +typedef struct xLIST_ITEM ListItem_t; /* For some reason lint wants this as two separate definitions. */ + +struct xMINI_LIST_ITEM +{ + listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + configLIST_VOLATILE TickType_t xItemValue; + struct xLIST_ITEM * configLIST_VOLATILE pxNext; + struct xLIST_ITEM * configLIST_VOLATILE pxPrevious; +}; +typedef struct xMINI_LIST_ITEM MiniListItem_t; + +/* + * Definition of the type of queue used by the scheduler. + */ +typedef struct xLIST +{ + listFIRST_LIST_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + volatile UBaseType_t uxNumberOfItems; + ListItem_t * configLIST_VOLATILE pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to listGET_OWNER_OF_NEXT_ENTRY (). */ + MiniListItem_t xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ + listSECOND_LIST_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ +} List_t; + +/* + * Access macro to set the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) ) + +/* + * Access macro to get the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listGET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_OWNER( pxListItem ) ( ( pxListItem )->pvOwner ) + +/* + * Access macro to set the value of the list item. In most cases the value is + * used to sort the list in descending order. + * + * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( ( pxListItem )->xItemValue = ( xValue ) ) + +/* + * Access macro to retrieve the value of the list item. The value can + * represent anything - for example the priority of a task, or the time at + * which a task should be unblocked. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) + +/* + * Access macro to retrieve the value of the list item at the head of a given + * list. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( ( ( pxList )->xListEnd ).pxNext->xItemValue ) + +/* + * Return the list item at the head of the list. + * + * \page listGET_HEAD_ENTRY listGET_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_HEAD_ENTRY( pxList ) ( ( ( pxList )->xListEnd ).pxNext ) + +/* + * Return the next list item. + * + * \page listGET_NEXT listGET_NEXT + * \ingroup LinkedList + */ +#define listGET_NEXT( pxListItem ) ( ( pxListItem )->pxNext ) + +/* + * Return the list item that marks the end of the list + * + * \page listGET_END_MARKER listGET_END_MARKER + * \ingroup LinkedList + */ +#define listGET_END_MARKER( pxList ) ( ( ListItem_t const * ) ( &( ( pxList )->xListEnd ) ) ) + +/* + * Access macro to determine if a list contains any items. The macro will + * only have the value true if the list is empty. + * + * \page listLIST_IS_EMPTY listLIST_IS_EMPTY + * \ingroup LinkedList + */ +#define listLIST_IS_EMPTY( pxList ) ( ( ( pxList )->uxNumberOfItems == ( UBaseType_t ) 0 ) ? pdTRUE : pdFALSE ) + +/* + * Access macro to return the number of items in the list. + */ +#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) + +/* + * Access function to obtain the owner of the next entry in a list. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list + * and returns that entry's pxOwner parameter. Using multiple calls to this + * function it is therefore possible to move through every item contained in + * a list. + * + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxTCB pxTCB is set to the address of the owner of the next list item. + * @param pxList The list from which the next item owner is to be returned. + * + * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ +{ \ +List_t * const pxConstList = ( pxList ); \ + /* Increment the index to the next item and return the item, ensuring */ \ + /* we don't return the marker used at the end of the list. */ \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + if( ( void * ) ( pxConstList )->pxIndex == ( void * ) &( ( pxConstList )->xListEnd ) ) \ + { \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + } \ + ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ +} + + +/* + * Access function to obtain the owner of the first entry in a list. Lists + * are normally sorted in ascending item value order. + * + * This function returns the pxOwner member of the first item in the list. + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the owner of the head item is to be + * returned. + * + * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) + +/* + * Check to see if a list item is within a list. The list item maintains a + * "container" pointer that points to the list it is in. All this macro does + * is check to see if the container and the list match. + * + * @param pxList The list we want to know if the list item is within. + * @param pxListItem The list item we want to know if is in the list. + * @return pdTRUE if the list item is in the list, otherwise pdFALSE. + */ +#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( ( pxListItem )->pxContainer == ( pxList ) ) ? ( pdTRUE ) : ( pdFALSE ) ) + +/* + * Return the list a list item is contained within (referenced from). + * + * @param pxListItem The list item being queried. + * @return A pointer to the List_t object that references the pxListItem + */ +#define listLIST_ITEM_CONTAINER( pxListItem ) ( ( pxListItem )->pxContainer ) + +/* + * This provides a crude means of knowing if a list has been initialised, as + * pxList->xListEnd.xItemValue is set to portMAX_DELAY by the vListInitialise() + * function. + */ +#define listLIST_IS_INITIALISED( pxList ) ( ( pxList )->xListEnd.xItemValue == portMAX_DELAY ) + +/* + * Must be called before a list is used! This initialises all the members + * of the list structure and inserts the xListEnd item into the list as a + * marker to the back of the list. + * + * @param pxList Pointer to the list being initialised. + * + * \page vListInitialise vListInitialise + * \ingroup LinkedList + */ +void vListInitialise( List_t * const pxList ) PRIVILEGED_FUNCTION; + +/* + * Must be called before a list item is used. This sets the list container to + * null so the item does not think that it is already contained in a list. + * + * @param pxItem Pointer to the list item being initialised. + * + * \page vListInitialiseItem vListInitialiseItem + * \ingroup LinkedList + */ +void vListInitialiseItem( ListItem_t * const pxItem ) PRIVILEGED_FUNCTION; + +/* + * Insert a list item into a list. The item will be inserted into the list in + * a position determined by its item value (descending item value order). + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The item that is to be placed in the list. + * + * \page vListInsert vListInsert + * \ingroup LinkedList + */ +void vListInsert( List_t * const pxList, ListItem_t * const pxNewListItem ) PRIVILEGED_FUNCTION; + +/* + * Insert a list item into a list. The item will be inserted in a position + * such that it will be the last item within the list returned by multiple + * calls to listGET_OWNER_OF_NEXT_ENTRY. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list. + * Placing an item in a list using vListInsertEnd effectively places the item + * in the list position pointed to by pxIndex. This means that every other + * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before + * the pxIndex parameter again points to the item being inserted. + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The list item to be inserted into the list. + * + * \page vListInsertEnd vListInsertEnd + * \ingroup LinkedList + */ +void vListInsertEnd( List_t * const pxList, ListItem_t * const pxNewListItem ) PRIVILEGED_FUNCTION; + +/* + * Remove an item from a list. The list item has a pointer to the list that + * it is in, so only the list item need be passed into the function. + * + * @param uxListRemove The item to be removed. The item will remove itself from + * the list pointed to by it's pxContainer parameter. + * + * @return The number of items that remain in the list after the list item has + * been removed. + * + * \page uxListRemove uxListRemove + * \ingroup LinkedList + */ +UBaseType_t uxListRemove( ListItem_t * const pxItemToRemove ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/message_buffer.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/message_buffer.h new file mode 100644 index 0000000..d7fb403 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/message_buffer.h @@ -0,0 +1,803 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + + +/* + * Message buffers build functionality on top of FreeRTOS stream buffers. + * Whereas stream buffers are used to send a continuous stream of data from one + * task or interrupt to another, message buffers are used to send variable + * length discrete messages from one task or interrupt to another. Their + * implementation is light weight, making them particularly suited for interrupt + * to task and core to core communication scenarios. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xMessageBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xMessageBufferRead()) inside a critical section and set the receive + * timeout to 0. + * + * Message buffers hold variable length messages. To enable that, when a + * message is written to the message buffer an additional sizeof( size_t ) bytes + * are also written to store the message's length (that happens internally, with + * the API function). sizeof( size_t ) is typically 4 bytes on a 32-bit + * architecture, so writing a 10 byte message to a message buffer on a 32-bit + * architecture will actually reduce the available space in the message buffer + * by 14 bytes (10 byte are used by the message, and 4 bytes to hold the length + * of the message). + */ + +#ifndef FREERTOS_MESSAGE_BUFFER_H +#define FREERTOS_MESSAGE_BUFFER_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include message_buffer.h" +#endif + +/* Message buffers are built onto of stream buffers. */ +#include "stream_buffer.h" + +#if defined( __cplusplus ) +extern "C" { +#endif + +/** + * Type by which message buffers are referenced. For example, a call to + * xMessageBufferCreate() returns an MessageBufferHandle_t variable that can + * then be used as a parameter to xMessageBufferSend(), xMessageBufferReceive(), + * etc. + */ +typedef void * MessageBufferHandle_t; + +/*-----------------------------------------------------------*/ + +/** + * message_buffer.h + * +
+MessageBufferHandle_t xMessageBufferCreate( size_t xBufferSizeBytes );
+
+ * + * Creates a new message buffer using dynamically allocated memory. See + * xMessageBufferCreateStatic() for a version that uses statically allocated + * memory (memory that is allocated at compile time). + * + * configSUPPORT_DYNAMIC_ALLOCATION must be set to 1 or left undefined in + * FreeRTOSConfig.h for xMessageBufferCreate() to be available. + * + * @param xBufferSizeBytes The total number of bytes (not messages) the message + * buffer will be able to hold at any one time. When a message is written to + * the message buffer an additional sizeof( size_t ) bytes are also written to + * store the message's length. sizeof( size_t ) is typically 4 bytes on a + * 32-bit architecture, so on most 32-bit architectures a 10 byte message will + * take up 14 bytes of message buffer space. + * + * @return If NULL is returned, then the message buffer cannot be created + * because there is insufficient heap memory available for FreeRTOS to allocate + * the message buffer data structures and storage area. A non-NULL value being + * returned indicates that the message buffer has been created successfully - + * the returned value should be stored as the handle to the created message + * buffer. + * + * Example use: +
+
+void vAFunction( void )
+{
+MessageBufferHandle_t xMessageBuffer;
+const size_t xMessageBufferSizeBytes = 100;
+
+    // Create a message buffer that can hold 100 bytes.  The memory used to hold
+    // both the message buffer structure and the messages themselves is allocated
+    // dynamically.  Each message added to the buffer consumes an additional 4
+    // bytes which are used to hold the lengh of the message.
+    xMessageBuffer = xMessageBufferCreate( xMessageBufferSizeBytes );
+
+    if( xMessageBuffer == NULL )
+    {
+        // There was not enough heap memory space available to create the
+        // message buffer.
+    }
+    else
+    {
+        // The message buffer was created successfully and can now be used.
+    }
+
+
+ * \defgroup xMessageBufferCreate xMessageBufferCreate + * \ingroup MessageBufferManagement + */ +#define xMessageBufferCreate( xBufferSizeBytes ) ( MessageBufferHandle_t ) xStreamBufferGenericCreate( xBufferSizeBytes, ( size_t ) 0, pdTRUE ) + +/** + * message_buffer.h + * +
+MessageBufferHandle_t xMessageBufferCreateStatic( size_t xBufferSizeBytes,
+                                                  uint8_t *pucMessageBufferStorageArea,
+                                                  StaticMessageBuffer_t *pxStaticMessageBuffer );
+
+ * Creates a new message buffer using statically allocated memory. See + * xMessageBufferCreate() for a version that uses dynamically allocated memory. + * + * @param xBufferSizeBytes The size, in bytes, of the buffer pointed to by the + * pucMessageBufferStorageArea parameter. When a message is written to the + * message buffer an additional sizeof( size_t ) bytes are also written to store + * the message's length. sizeof( size_t ) is typically 4 bytes on a 32-bit + * architecture, so on most 32-bit architecture a 10 byte message will take up + * 14 bytes of message buffer space. The maximum number of bytes that can be + * stored in the message buffer is actually (xBufferSizeBytes - 1). + * + * @param pucMessageBufferStorageArea Must point to a uint8_t array that is at + * least xBufferSizeBytes + 1 big. This is the array to which messages are + * copied when they are written to the message buffer. + * + * @param pxStaticMessageBuffer Must point to a variable of type + * StaticMessageBuffer_t, which will be used to hold the message buffer's data + * structure. + * + * @return If the message buffer is created successfully then a handle to the + * created message buffer is returned. If either pucMessageBufferStorageArea or + * pxStaticmessageBuffer are NULL then NULL is returned. + * + * Example use: +
+
+// Used to dimension the array used to hold the messages.  The available space
+// will actually be one less than this, so 999.
+#define STORAGE_SIZE_BYTES 1000
+
+// Defines the memory that will actually hold the messages within the message
+// buffer.
+static uint8_t ucStorageBuffer[ STORAGE_SIZE_BYTES ];
+
+// The variable used to hold the message buffer structure.
+StaticMessageBuffer_t xMessageBufferStruct;
+
+void MyFunction( void )
+{
+MessageBufferHandle_t xMessageBuffer;
+
+    xMessageBuffer = xMessageBufferCreateStatic( sizeof( ucBufferStorage ),
+                                                 ucBufferStorage,
+                                                 &xMessageBufferStruct );
+
+    // As neither the pucMessageBufferStorageArea or pxStaticMessageBuffer
+    // parameters were NULL, xMessageBuffer will not be NULL, and can be used to
+    // reference the created message buffer in other message buffer API calls.
+
+    // Other code that uses the message buffer can go here.
+}
+
+
+ * \defgroup xMessageBufferCreateStatic xMessageBufferCreateStatic + * \ingroup MessageBufferManagement + */ +#define xMessageBufferCreateStatic( xBufferSizeBytes, pucMessageBufferStorageArea, pxStaticMessageBuffer ) ( MessageBufferHandle_t ) xStreamBufferGenericCreateStatic( xBufferSizeBytes, 0, pdTRUE, pucMessageBufferStorageArea, pxStaticMessageBuffer ) + +/** + * message_buffer.h + * +
+size_t xMessageBufferSend( MessageBufferHandle_t xMessageBuffer,
+                           const void *pvTxData,
+                           size_t xDataLengthBytes,
+                           TickType_t xTicksToWait );
+
+ *
+ * Sends a discrete message to the message buffer.  The message can be any
+ * length that fits within the buffer's free space, and is copied into the
+ * buffer.
+ *
+ * ***NOTE***:  Uniquely among FreeRTOS objects, the stream buffer
+ * implementation (so also the message buffer implementation, as message buffers
+ * are built on top of stream buffers) assumes there is only one task or
+ * interrupt that will write to the buffer (the writer), and only one task or
+ * interrupt that will read from the buffer (the reader).  It is safe for the
+ * writer and reader to be different tasks or interrupts, but, unlike other
+ * FreeRTOS objects, it is not safe to have multiple different writers or
+ * multiple different readers.  If there are to be multiple different writers
+ * then the application writer must place each call to a writing API function
+ * (such as xMessageBufferSend()) inside a critical section and set the send
+ * block time to 0.  Likewise, if there are to be multiple different readers
+ * then the application writer must place each call to a reading API function
+ * (such as xMessageBufferRead()) inside a critical section and set the receive
+ * block time to 0.
+ *
+ * Use xMessageBufferSend() to write to a message buffer from a task.  Use
+ * xMessageBufferSendFromISR() to write to a message buffer from an interrupt
+ * service routine (ISR).
+ *
+ * @param xMessageBuffer The handle of the message buffer to which a message is
+ * being sent.
+ *
+ * @param pvTxData A pointer to the message that is to be copied into the
+ * message buffer.
+ *
+ * @param xDataLengthBytes The length of the message.  That is, the number of
+ * bytes to copy from pvTxData into the message buffer.  When a message is
+ * written to the message buffer an additional sizeof( size_t ) bytes are also
+ * written to store the message's length.  sizeof( size_t ) is typically 4 bytes
+ * on a 32-bit architecture, so on most 32-bit architecture setting
+ * xDataLengthBytes to 20 will reduce the free space in the message buffer by 24
+ * bytes (20 bytes of message data and 4 bytes to hold the message length).
+ *
+ * @param xTicksToWait The maximum amount of time the calling task should remain
+ * in the Blocked state to wait for enough space to become available in the
+ * message buffer, should the message buffer have insufficient space when
+ * xMessageBufferSend() is called.  The calling task will never block if
+ * xTicksToWait is zero.  The block time is specified in tick periods, so the
+ * absolute time it represents is dependent on the tick frequency.  The macro
+ * pdMS_TO_TICKS() can be used to convert a time specified in milliseconds into
+ * a time specified in ticks.  Setting xTicksToWait to portMAX_DELAY will cause
+ * the task to wait indefinitely (without timing out), provided
+ * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h.  Tasks do not use any
+ * CPU time when they are in the Blocked state.
+ *
+ * @return The number of bytes written to the message buffer.  If the call to
+ * xMessageBufferSend() times out before there was enough space to write the
+ * message into the message buffer then zero is returned.  If the call did not
+ * time out then xDataLengthBytes is returned.
+ *
+ * Example use:
+
+void vAFunction( MessageBufferHandle_t xMessageBuffer )
+{
+size_t xBytesSent;
+uint8_t ucArrayToSend[] = { 0, 1, 2, 3 };
+char *pcStringToSend = "String to send";
+const TickType_t x100ms = pdMS_TO_TICKS( 100 );
+
+    // Send an array to the message buffer, blocking for a maximum of 100ms to
+    // wait for enough space to be available in the message buffer.
+    xBytesSent = xMessageBufferSend( xMessageBuffer, ( void * ) ucArrayToSend, sizeof( ucArrayToSend ), x100ms );
+
+    if( xBytesSent != sizeof( ucArrayToSend ) )
+    {
+        // The call to xMessageBufferSend() times out before there was enough
+        // space in the buffer for the data to be written.
+    }
+
+    // Send the string to the message buffer.  Return immediately if there is
+    // not enough space in the buffer.
+    xBytesSent = xMessageBufferSend( xMessageBuffer, ( void * ) pcStringToSend, strlen( pcStringToSend ), 0 );
+
+    if( xBytesSent != strlen( pcStringToSend ) )
+    {
+        // The string could not be added to the message buffer because there was
+        // not enough free space in the buffer.
+    }
+}
+
+ * \defgroup xMessageBufferSend xMessageBufferSend + * \ingroup MessageBufferManagement + */ +#define xMessageBufferSend( xMessageBuffer, pvTxData, xDataLengthBytes, xTicksToWait ) xStreamBufferSend( ( StreamBufferHandle_t ) xMessageBuffer, pvTxData, xDataLengthBytes, xTicksToWait ) + +/** + * message_buffer.h + * +
+size_t xMessageBufferSendFromISR( MessageBufferHandle_t xMessageBuffer,
+                                  const void *pvTxData,
+                                  size_t xDataLengthBytes,
+                                  BaseType_t *pxHigherPriorityTaskWoken );
+
+ *
+ * Interrupt safe version of the API function that sends a discrete message to
+ * the message buffer.  The message can be any length that fits within the
+ * buffer's free space, and is copied into the buffer.
+ *
+ * ***NOTE***:  Uniquely among FreeRTOS objects, the stream buffer
+ * implementation (so also the message buffer implementation, as message buffers
+ * are built on top of stream buffers) assumes there is only one task or
+ * interrupt that will write to the buffer (the writer), and only one task or
+ * interrupt that will read from the buffer (the reader).  It is safe for the
+ * writer and reader to be different tasks or interrupts, but, unlike other
+ * FreeRTOS objects, it is not safe to have multiple different writers or
+ * multiple different readers.  If there are to be multiple different writers
+ * then the application writer must place each call to a writing API function
+ * (such as xMessageBufferSend()) inside a critical section and set the send
+ * block time to 0.  Likewise, if there are to be multiple different readers
+ * then the application writer must place each call to a reading API function
+ * (such as xMessageBufferRead()) inside a critical section and set the receive
+ * block time to 0.
+ *
+ * Use xMessageBufferSend() to write to a message buffer from a task.  Use
+ * xMessageBufferSendFromISR() to write to a message buffer from an interrupt
+ * service routine (ISR).
+ *
+ * @param xMessageBuffer The handle of the message buffer to which a message is
+ * being sent.
+ *
+ * @param pvTxData A pointer to the message that is to be copied into the
+ * message buffer.
+ *
+ * @param xDataLengthBytes The length of the message.  That is, the number of
+ * bytes to copy from pvTxData into the message buffer.  When a message is
+ * written to the message buffer an additional sizeof( size_t ) bytes are also
+ * written to store the message's length.  sizeof( size_t ) is typically 4 bytes
+ * on a 32-bit architecture, so on most 32-bit architecture setting
+ * xDataLengthBytes to 20 will reduce the free space in the message buffer by 24
+ * bytes (20 bytes of message data and 4 bytes to hold the message length).
+ *
+ * @param pxHigherPriorityTaskWoken  It is possible that a message buffer will
+ * have a task blocked on it waiting for data.  Calling
+ * xMessageBufferSendFromISR() can make data available, and so cause a task that
+ * was waiting for data to leave the Blocked state.  If calling
+ * xMessageBufferSendFromISR() causes a task to leave the Blocked state, and the
+ * unblocked task has a priority higher than the currently executing task (the
+ * task that was interrupted), then, internally, xMessageBufferSendFromISR()
+ * will set *pxHigherPriorityTaskWoken to pdTRUE.  If
+ * xMessageBufferSendFromISR() sets this value to pdTRUE, then normally a
+ * context switch should be performed before the interrupt is exited.  This will
+ * ensure that the interrupt returns directly to the highest priority Ready
+ * state task.  *pxHigherPriorityTaskWoken should be set to pdFALSE before it
+ * is passed into the function.  See the code example below for an example.
+ *
+ * @return The number of bytes actually written to the message buffer.  If the
+ * message buffer didn't have enough free space for the message to be stored
+ * then 0 is returned, otherwise xDataLengthBytes is returned.
+ *
+ * Example use:
+
+// A message buffer that has already been created.
+MessageBufferHandle_t xMessageBuffer;
+
+void vAnInterruptServiceRoutine( void )
+{
+size_t xBytesSent;
+char *pcStringToSend = "String to send";
+BaseType_t xHigherPriorityTaskWoken = pdFALSE; // Initialised to pdFALSE.
+
+    // Attempt to send the string to the message buffer.
+    xBytesSent = xMessageBufferSendFromISR( xMessageBuffer,
+                                            ( void * ) pcStringToSend,
+                                            strlen( pcStringToSend ),
+                                            &xHigherPriorityTaskWoken );
+
+    if( xBytesSent != strlen( pcStringToSend ) )
+    {
+        // The string could not be added to the message buffer because there was
+        // not enough free space in the buffer.
+    }
+
+    // If xHigherPriorityTaskWoken was set to pdTRUE inside
+    // xMessageBufferSendFromISR() then a task that has a priority above the
+    // priority of the currently executing task was unblocked and a context
+    // switch should be performed to ensure the ISR returns to the unblocked
+    // task.  In most FreeRTOS ports this is done by simply passing
+    // xHigherPriorityTaskWoken into portYIELD_FROM_ISR(), which will test the
+    // variables value, and perform the context switch if necessary.  Check the
+    // documentation for the port in use for port specific instructions.
+    portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+}
+
+ * \defgroup xMessageBufferSendFromISR xMessageBufferSendFromISR + * \ingroup MessageBufferManagement + */ +#define xMessageBufferSendFromISR( xMessageBuffer, pvTxData, xDataLengthBytes, pxHigherPriorityTaskWoken ) xStreamBufferSendFromISR( ( StreamBufferHandle_t ) xMessageBuffer, pvTxData, xDataLengthBytes, pxHigherPriorityTaskWoken ) + +/** + * message_buffer.h + * +
+size_t xMessageBufferReceive( MessageBufferHandle_t xMessageBuffer,
+                              void *pvRxData,
+                              size_t xBufferLengthBytes,
+                              TickType_t xTicksToWait );
+
+ * + * Receives a discrete message from a message buffer. Messages can be of + * variable length and are copied out of the buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xMessageBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xMessageBufferRead()) inside a critical section and set the receive + * block time to 0. + * + * Use xMessageBufferReceive() to read from a message buffer from a task. Use + * xMessageBufferReceiveFromISR() to read from a message buffer from an + * interrupt service routine (ISR). + * + * @param xMessageBuffer The handle of the message buffer from which a message + * is being received. + * + * @param pvRxData A pointer to the buffer into which the received message is + * to be copied. + * + * @param xBufferLengthBytes The length of the buffer pointed to by the pvRxData + * parameter. This sets the maximum length of the message that can be received. + * If xBufferLengthBytes is too small to hold the next message then the message + * will be left in the message buffer and 0 will be returned. + * + * @param xTicksToWait The maximum amount of time the task should remain in the + * Blocked state to wait for a message, should the message buffer be empty. + * xMessageBufferReceive() will return immediately if xTicksToWait is zero and + * the message buffer is empty. The block time is specified in tick periods, so + * the absolute time it represents is dependent on the tick frequency. The + * macro pdMS_TO_TICKS() can be used to convert a time specified in milliseconds + * into a time specified in ticks. Setting xTicksToWait to portMAX_DELAY will + * cause the task to wait indefinitely (without timing out), provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h. Tasks do not use any + * CPU time when they are in the Blocked state. + * + * @return The length, in bytes, of the message read from the message buffer, if + * any. If xMessageBufferReceive() times out before a message became available + * then zero is returned. If the length of the message is greater than + * xBufferLengthBytes then the message will be left in the message buffer and + * zero is returned. + * + * Example use: +
+void vAFunction( MessageBuffer_t xMessageBuffer )
+{
+uint8_t ucRxData[ 20 ];
+size_t xReceivedBytes;
+const TickType_t xBlockTime = pdMS_TO_TICKS( 20 );
+
+    // Receive the next message from the message buffer.  Wait in the Blocked
+    // state (so not using any CPU processing time) for a maximum of 100ms for
+    // a message to become available.
+    xReceivedBytes = xMessageBufferReceive( xMessageBuffer,
+                                            ( void * ) ucRxData,
+                                            sizeof( ucRxData ),
+                                            xBlockTime );
+
+    if( xReceivedBytes > 0 )
+    {
+        // A ucRxData contains a message that is xReceivedBytes long.  Process
+        // the message here....
+    }
+}
+
+ * \defgroup xMessageBufferReceive xMessageBufferReceive + * \ingroup MessageBufferManagement + */ +#define xMessageBufferReceive( xMessageBuffer, pvRxData, xBufferLengthBytes, xTicksToWait ) xStreamBufferReceive( ( StreamBufferHandle_t ) xMessageBuffer, pvRxData, xBufferLengthBytes, xTicksToWait ) + + +/** + * message_buffer.h + * +
+size_t xMessageBufferReceiveFromISR( MessageBufferHandle_t xMessageBuffer,
+                                     void *pvRxData,
+                                     size_t xBufferLengthBytes,
+                                     BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * An interrupt safe version of the API function that receives a discrete + * message from a message buffer. Messages can be of variable length and are + * copied out of the buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xMessageBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xMessageBufferRead()) inside a critical section and set the receive + * block time to 0. + * + * Use xMessageBufferReceive() to read from a message buffer from a task. Use + * xMessageBufferReceiveFromISR() to read from a message buffer from an + * interrupt service routine (ISR). + * + * @param xMessageBuffer The handle of the message buffer from which a message + * is being received. + * + * @param pvRxData A pointer to the buffer into which the received message is + * to be copied. + * + * @param xBufferLengthBytes The length of the buffer pointed to by the pvRxData + * parameter. This sets the maximum length of the message that can be received. + * If xBufferLengthBytes is too small to hold the next message then the message + * will be left in the message buffer and 0 will be returned. + * + * @param pxHigherPriorityTaskWoken It is possible that a message buffer will + * have a task blocked on it waiting for space to become available. Calling + * xMessageBufferReceiveFromISR() can make space available, and so cause a task + * that is waiting for space to leave the Blocked state. If calling + * xMessageBufferReceiveFromISR() causes a task to leave the Blocked state, and + * the unblocked task has a priority higher than the currently executing task + * (the task that was interrupted), then, internally, + * xMessageBufferReceiveFromISR() will set *pxHigherPriorityTaskWoken to pdTRUE. + * If xMessageBufferReceiveFromISR() sets this value to pdTRUE, then normally a + * context switch should be performed before the interrupt is exited. That will + * ensure the interrupt returns directly to the highest priority Ready state + * task. *pxHigherPriorityTaskWoken should be set to pdFALSE before it is + * passed into the function. See the code example below for an example. + * + * @return The length, in bytes, of the message read from the message buffer, if + * any. + * + * Example use: +
+// A message buffer that has already been created.
+MessageBuffer_t xMessageBuffer;
+
+void vAnInterruptServiceRoutine( void )
+{
+uint8_t ucRxData[ 20 ];
+size_t xReceivedBytes;
+BaseType_t xHigherPriorityTaskWoken = pdFALSE;  // Initialised to pdFALSE.
+
+    // Receive the next message from the message buffer.
+    xReceivedBytes = xMessageBufferReceiveFromISR( xMessageBuffer,
+                                                  ( void * ) ucRxData,
+                                                  sizeof( ucRxData ),
+                                                  &xHigherPriorityTaskWoken );
+
+    if( xReceivedBytes > 0 )
+    {
+        // A ucRxData contains a message that is xReceivedBytes long.  Process
+        // the message here....
+    }
+
+    // If xHigherPriorityTaskWoken was set to pdTRUE inside
+    // xMessageBufferReceiveFromISR() then a task that has a priority above the
+    // priority of the currently executing task was unblocked and a context
+    // switch should be performed to ensure the ISR returns to the unblocked
+    // task.  In most FreeRTOS ports this is done by simply passing
+    // xHigherPriorityTaskWoken into portYIELD_FROM_ISR(), which will test the
+    // variables value, and perform the context switch if necessary.  Check the
+    // documentation for the port in use for port specific instructions.
+    portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+}
+
+ * \defgroup xMessageBufferReceiveFromISR xMessageBufferReceiveFromISR + * \ingroup MessageBufferManagement + */ +#define xMessageBufferReceiveFromISR( xMessageBuffer, pvRxData, xBufferLengthBytes, pxHigherPriorityTaskWoken ) xStreamBufferReceiveFromISR( ( StreamBufferHandle_t ) xMessageBuffer, pvRxData, xBufferLengthBytes, pxHigherPriorityTaskWoken ) + +/** + * message_buffer.h + * +
+void vMessageBufferDelete( MessageBufferHandle_t xMessageBuffer );
+
+ * + * Deletes a message buffer that was previously created using a call to + * xMessageBufferCreate() or xMessageBufferCreateStatic(). If the message + * buffer was created using dynamic memory (that is, by xMessageBufferCreate()), + * then the allocated memory is freed. + * + * A message buffer handle must not be used after the message buffer has been + * deleted. + * + * @param xMessageBuffer The handle of the message buffer to be deleted. + * + */ +#define vMessageBufferDelete( xMessageBuffer ) vStreamBufferDelete( ( StreamBufferHandle_t ) xMessageBuffer ) + +/** + * message_buffer.h +
+BaseType_t xMessageBufferIsFull( MessageBufferHandle_t xMessageBuffer ) );
+
+ * + * Tests to see if a message buffer is full. A message buffer is full if it + * cannot accept any more messages, of any size, until space is made available + * by a message being removed from the message buffer. + * + * @param xMessageBuffer The handle of the message buffer being queried. + * + * @return If the message buffer referenced by xMessageBuffer is full then + * pdTRUE is returned. Otherwise pdFALSE is returned. + */ +#define xMessageBufferIsFull( xMessageBuffer ) xStreamBufferIsFull( ( StreamBufferHandle_t ) xMessageBuffer ) + +/** + * message_buffer.h +
+BaseType_t xMessageBufferIsEmpty( MessageBufferHandle_t xMessageBuffer ) );
+
+ * + * Tests to see if a message buffer is empty (does not contain any messages). + * + * @param xMessageBuffer The handle of the message buffer being queried. + * + * @return If the message buffer referenced by xMessageBuffer is empty then + * pdTRUE is returned. Otherwise pdFALSE is returned. + * + */ +#define xMessageBufferIsEmpty( xMessageBuffer ) xStreamBufferIsEmpty( ( StreamBufferHandle_t ) xMessageBuffer ) + +/** + * message_buffer.h +
+BaseType_t xMessageBufferReset( MessageBufferHandle_t xMessageBuffer );
+
+ * + * Resets a message buffer to its initial empty state, discarding any message it + * contained. + * + * A message buffer can only be reset if there are no tasks blocked on it. + * + * @param xMessageBuffer The handle of the message buffer being reset. + * + * @return If the message buffer was reset then pdPASS is returned. If the + * message buffer could not be reset because either there was a task blocked on + * the message queue to wait for space to become available, or to wait for a + * a message to be available, then pdFAIL is returned. + * + * \defgroup xMessageBufferReset xMessageBufferReset + * \ingroup MessageBufferManagement + */ +#define xMessageBufferReset( xMessageBuffer ) xStreamBufferReset( ( StreamBufferHandle_t ) xMessageBuffer ) + + +/** + * message_buffer.h +
+size_t xMessageBufferSpaceAvailable( MessageBufferHandle_t xMessageBuffer ) );
+
+ * Returns the number of bytes of free space in the message buffer. + * + * @param xMessageBuffer The handle of the message buffer being queried. + * + * @return The number of bytes that can be written to the message buffer before + * the message buffer would be full. When a message is written to the message + * buffer an additional sizeof( size_t ) bytes are also written to store the + * message's length. sizeof( size_t ) is typically 4 bytes on a 32-bit + * architecture, so if xMessageBufferSpacesAvailable() returns 10, then the size + * of the largest message that can be written to the message buffer is 6 bytes. + * + * \defgroup xMessageBufferSpaceAvailable xMessageBufferSpaceAvailable + * \ingroup MessageBufferManagement + */ +#define xMessageBufferSpaceAvailable( xMessageBuffer ) xStreamBufferSpacesAvailable( ( StreamBufferHandle_t ) xMessageBuffer ) +#define xMessageBufferSpacesAvailable( xMessageBuffer ) xStreamBufferSpacesAvailable( ( StreamBufferHandle_t ) xMessageBuffer ) /* Corrects typo in original macro name. */ + +/** + * message_buffer.h +
+ size_t xMessageBufferNextLengthBytes( MessageBufferHandle_t xMessageBuffer ) );
+ 
+ * Returns the length (in bytes) of the next message in a message buffer. + * Useful if xMessageBufferReceive() returned 0 because the size of the buffer + * passed into xMessageBufferReceive() was too small to hold the next message. + * + * @param xMessageBuffer The handle of the message buffer being queried. + * + * @return The length (in bytes) of the next message in the message buffer, or 0 + * if the message buffer is empty. + * + * \defgroup xMessageBufferNextLengthBytes xMessageBufferNextLengthBytes + * \ingroup MessageBufferManagement + */ +#define xMessageBufferNextLengthBytes( xMessageBuffer ) xStreamBufferNextMessageLengthBytes( ( StreamBufferHandle_t ) xMessageBuffer ) PRIVILEGED_FUNCTION; + +/** + * message_buffer.h + * +
+BaseType_t xMessageBufferSendCompletedFromISR( MessageBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * For advanced users only. + * + * The sbSEND_COMPLETED() macro is called from within the FreeRTOS APIs when + * data is sent to a message buffer or stream buffer. If there was a task that + * was blocked on the message or stream buffer waiting for data to arrive then + * the sbSEND_COMPLETED() macro sends a notification to the task to remove it + * from the Blocked state. xMessageBufferSendCompletedFromISR() does the same + * thing. It is provided to enable application writers to implement their own + * version of sbSEND_COMPLETED(), and MUST NOT BE USED AT ANY OTHER TIME. + * + * See the example implemented in FreeRTOS/Demo/Minimal/MessageBufferAMP.c for + * additional information. + * + * @param xStreamBuffer The handle of the stream buffer to which data was + * written. + * + * @param pxHigherPriorityTaskWoken *pxHigherPriorityTaskWoken should be + * initialised to pdFALSE before it is passed into + * xMessageBufferSendCompletedFromISR(). If calling + * xMessageBufferSendCompletedFromISR() removes a task from the Blocked state, + * and the task has a priority above the priority of the currently running task, + * then *pxHigherPriorityTaskWoken will get set to pdTRUE indicating that a + * context switch should be performed before exiting the ISR. + * + * @return If a task was removed from the Blocked state then pdTRUE is returned. + * Otherwise pdFALSE is returned. + * + * \defgroup xMessageBufferSendCompletedFromISR xMessageBufferSendCompletedFromISR + * \ingroup StreamBufferManagement + */ +#define xMessageBufferSendCompletedFromISR( xMessageBuffer, pxHigherPriorityTaskWoken ) xStreamBufferSendCompletedFromISR( ( StreamBufferHandle_t ) xMessageBuffer, pxHigherPriorityTaskWoken ) + +/** + * message_buffer.h + * +
+BaseType_t xMessageBufferReceiveCompletedFromISR( MessageBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * For advanced users only. + * + * The sbRECEIVE_COMPLETED() macro is called from within the FreeRTOS APIs when + * data is read out of a message buffer or stream buffer. If there was a task + * that was blocked on the message or stream buffer waiting for data to arrive + * then the sbRECEIVE_COMPLETED() macro sends a notification to the task to + * remove it from the Blocked state. xMessageBufferReceiveCompletedFromISR() + * does the same thing. It is provided to enable application writers to + * implement their own version of sbRECEIVE_COMPLETED(), and MUST NOT BE USED AT + * ANY OTHER TIME. + * + * See the example implemented in FreeRTOS/Demo/Minimal/MessageBufferAMP.c for + * additional information. + * + * @param xStreamBuffer The handle of the stream buffer from which data was + * read. + * + * @param pxHigherPriorityTaskWoken *pxHigherPriorityTaskWoken should be + * initialised to pdFALSE before it is passed into + * xMessageBufferReceiveCompletedFromISR(). If calling + * xMessageBufferReceiveCompletedFromISR() removes a task from the Blocked state, + * and the task has a priority above the priority of the currently running task, + * then *pxHigherPriorityTaskWoken will get set to pdTRUE indicating that a + * context switch should be performed before exiting the ISR. + * + * @return If a task was removed from the Blocked state then pdTRUE is returned. + * Otherwise pdFALSE is returned. + * + * \defgroup xMessageBufferReceiveCompletedFromISR xMessageBufferReceiveCompletedFromISR + * \ingroup StreamBufferManagement + */ +#define xMessageBufferReceiveCompletedFromISR( xMessageBuffer, pxHigherPriorityTaskWoken ) xStreamBufferReceiveCompletedFromISR( ( StreamBufferHandle_t ) xMessageBuffer, pxHigherPriorityTaskWoken ) + +#if defined( __cplusplus ) +} /* extern "C" */ +#endif + +#endif /* !defined( FREERTOS_MESSAGE_BUFFER_H ) */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/mpu_prototypes.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/mpu_prototypes.h new file mode 100644 index 0000000..e6a4ea4 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/mpu_prototypes.h @@ -0,0 +1,160 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* + * When the MPU is used the standard (non MPU) API functions are mapped to + * equivalents that start "MPU_", the prototypes for which are defined in this + * header files. This will cause the application code to call the MPU_ version + * which wraps the non-MPU version with privilege promoting then demoting code, + * so the kernel code always runs will full privileges. + */ + + +#ifndef MPU_PROTOTYPES_H +#define MPU_PROTOTYPES_H + +/* MPU versions of tasks.h API functions. */ +BaseType_t MPU_xTaskCreate( TaskFunction_t pxTaskCode, const char * const pcName, const uint16_t usStackDepth, void * const pvParameters, UBaseType_t uxPriority, TaskHandle_t * const pxCreatedTask ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTaskCreateStatic( TaskFunction_t pxTaskCode, const char * const pcName, const uint32_t ulStackDepth, void * const pvParameters, UBaseType_t uxPriority, StackType_t * const puxStackBuffer, StaticTask_t * const pxTaskBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCreateRestricted( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCreateRestrictedStatic( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const pxRegions ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskDelete( TaskHandle_t xTaskToDelete ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskDelay( const TickType_t xTicksToDelay ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, const TickType_t xTimeIncrement ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskAbortDelay( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTaskPriorityGet( const TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +eTaskState MPU_eTaskGetState( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSuspend( TaskHandle_t xTaskToSuspend ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskResume( TaskHandle_t xTaskToResume ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskStartScheduler( void ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSuspendAll( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskResumeAll( void ) FREERTOS_SYSTEM_CALL; +TickType_t MPU_xTaskGetTickCount( void ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTaskGetNumberOfTasks( void ) FREERTOS_SYSTEM_CALL; +char * MPU_pcTaskGetName( TaskHandle_t xTaskToQuery ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTaskGetHandle( const char *pcNameToQuery ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTaskGetStackHighWaterMark( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +configSTACK_DEPTH_TYPE MPU_uxTaskGetStackHighWaterMark2( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction ) FREERTOS_SYSTEM_CALL; +TaskHookFunction_t MPU_xTaskGetApplicationTaskTag( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue ) FREERTOS_SYSTEM_CALL; +void * MPU_pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTaskGetIdleTaskHandle( void ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, const UBaseType_t uxArraySize, uint32_t * const pulTotalRunTime ) FREERTOS_SYSTEM_CALL; +uint32_t MPU_ulTaskGetIdleRunTimeCounter( void ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskList( char * pcWriteBuffer ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskGetRunTimeStats( char *pcWriteBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +uint32_t MPU_ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskNotifyStateClear( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +uint32_t MPU_ulTaskNotifyValueClear( TaskHandle_t xTask, uint32_t ulBitsToClear ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskIncrementTick( void ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTaskGetCurrentTaskHandle( void ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSetTimeOutState( TimeOut_t * const pxTimeOut ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskMissedYield( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskGetSchedulerState( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCatchUpTicks( TickType_t xTicksToCatchUp ) FREERTOS_SYSTEM_CALL; + +/* MPU versions of queue.h API functions. */ +BaseType_t MPU_xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, const BaseType_t xCopyPosition ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueuePeek( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueSemaphoreTake( QueueHandle_t xQueue, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxQueueMessagesWaiting( const QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxQueueSpacesAvailable( const QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +void MPU_vQueueDelete( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueCreateMutex( const uint8_t ucQueueType ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueCreateMutexStatic( const uint8_t ucQueueType, StaticQueue_t *pxStaticQueue ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueCreateCountingSemaphore( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueCreateCountingSemaphoreStatic( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount, StaticQueue_t *pxStaticQueue ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xQueueGetMutexHolder( QueueHandle_t xSemaphore ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueGiveMutexRecursive( QueueHandle_t pxMutex ) FREERTOS_SYSTEM_CALL; +void MPU_vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcName ) FREERTOS_SYSTEM_CALL; +void MPU_vQueueUnregisterQueue( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +const char * MPU_pcQueueGetName( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueGenericCreate( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueGenericCreateStatic( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, StaticQueue_t *pxStaticQueue, const uint8_t ucQueueType ) FREERTOS_SYSTEM_CALL; +QueueSetHandle_t MPU_xQueueCreateSet( const UBaseType_t uxEventQueueLength ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) FREERTOS_SYSTEM_CALL; +QueueSetMemberHandle_t MPU_xQueueSelectFromSet( QueueSetHandle_t xQueueSet, const TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueGenericReset( QueueHandle_t xQueue, BaseType_t xNewQueue ) FREERTOS_SYSTEM_CALL; +void MPU_vQueueSetQueueNumber( QueueHandle_t xQueue, UBaseType_t uxQueueNumber ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxQueueGetQueueNumber( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +uint8_t MPU_ucQueueGetQueueType( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; + +/* MPU versions of timers.h API functions. */ +TimerHandle_t MPU_xTimerCreate( const char * const pcTimerName, const TickType_t xTimerPeriodInTicks, const UBaseType_t uxAutoReload, void * const pvTimerID, TimerCallbackFunction_t pxCallbackFunction ) FREERTOS_SYSTEM_CALL; +TimerHandle_t MPU_xTimerCreateStatic( const char * const pcTimerName, const TickType_t xTimerPeriodInTicks, const UBaseType_t uxAutoReload, void * const pvTimerID, TimerCallbackFunction_t pxCallbackFunction, StaticTimer_t *pxTimerBuffer ) FREERTOS_SYSTEM_CALL; +void * MPU_pvTimerGetTimerID( const TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +void MPU_vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTimerIsTimerActive( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTimerGetTimerDaemonTaskHandle( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +const char * MPU_pcTimerGetName( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +void MPU_vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTimerGetReloadMode( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +TickType_t MPU_xTimerGetPeriod( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +TickType_t MPU_xTimerGetExpiryTime( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTimerCreateTimerTask( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; + +/* MPU versions of event_group.h API functions. */ +EventGroupHandle_t MPU_xEventGroupCreate( void ) FREERTOS_SYSTEM_CALL; +EventGroupHandle_t MPU_xEventGroupCreateStatic( StaticEventGroup_t *pxEventGroupBuffer ) FREERTOS_SYSTEM_CALL; +EventBits_t MPU_xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +EventBits_t MPU_xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) FREERTOS_SYSTEM_CALL; +EventBits_t MPU_xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) FREERTOS_SYSTEM_CALL; +EventBits_t MPU_xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +void MPU_vEventGroupDelete( EventGroupHandle_t xEventGroup ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxEventGroupGetNumber( void* xEventGroup ) FREERTOS_SYSTEM_CALL; + +/* MPU versions of message/stream_buffer.h API functions. */ +size_t MPU_xStreamBufferSend( StreamBufferHandle_t xStreamBuffer, const void *pvTxData, size_t xDataLengthBytes, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +size_t MPU_xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer, void *pvRxData, size_t xBufferLengthBytes, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +size_t MPU_xStreamBufferNextMessageLengthBytes( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +void MPU_vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xStreamBufferReset( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +size_t MPU_xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +size_t MPU_xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel ) FREERTOS_SYSTEM_CALL; +StreamBufferHandle_t MPU_xStreamBufferGenericCreate( size_t xBufferSizeBytes, size_t xTriggerLevelBytes, BaseType_t xIsMessageBuffer ) FREERTOS_SYSTEM_CALL; +StreamBufferHandle_t MPU_xStreamBufferGenericCreateStatic( size_t xBufferSizeBytes, size_t xTriggerLevelBytes, BaseType_t xIsMessageBuffer, uint8_t * const pucStreamBufferStorageArea, StaticStreamBuffer_t * const pxStaticStreamBuffer ) FREERTOS_SYSTEM_CALL; + + + +#endif /* MPU_PROTOTYPES_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/mpu_wrappers.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/mpu_wrappers.h new file mode 100644 index 0000000..08b0a61 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/mpu_wrappers.h @@ -0,0 +1,189 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 MPU_WRAPPERS_H +#define MPU_WRAPPERS_H + +/* This file redefines API functions to be called through a wrapper macro, but +only for ports that are using the MPU. */ +#ifdef portUSING_MPU_WRAPPERS + + /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is + included from queue.c or task.c to prevent it from having an effect within + those files. */ + #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + + /* + * Map standard (non MPU) API functions to equivalents that start + * "MPU_". This will cause the application code to call the MPU_ + * version, which wraps the non-MPU version with privilege promoting + * then demoting code, so the kernel code always runs will full + * privileges. + */ + + /* Map standard tasks.h API functions to the MPU equivalents. */ + #define xTaskCreate MPU_xTaskCreate + #define xTaskCreateStatic MPU_xTaskCreateStatic + #define xTaskCreateRestricted MPU_xTaskCreateRestricted + #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions + #define vTaskDelete MPU_vTaskDelete + #define vTaskDelay MPU_vTaskDelay + #define vTaskDelayUntil MPU_vTaskDelayUntil + #define xTaskAbortDelay MPU_xTaskAbortDelay + #define uxTaskPriorityGet MPU_uxTaskPriorityGet + #define eTaskGetState MPU_eTaskGetState + #define vTaskGetInfo MPU_vTaskGetInfo + #define vTaskPrioritySet MPU_vTaskPrioritySet + #define vTaskSuspend MPU_vTaskSuspend + #define vTaskResume MPU_vTaskResume + #define vTaskSuspendAll MPU_vTaskSuspendAll + #define xTaskResumeAll MPU_xTaskResumeAll + #define xTaskGetTickCount MPU_xTaskGetTickCount + #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks + #define pcTaskGetName MPU_pcTaskGetName + #define xTaskGetHandle MPU_xTaskGetHandle + #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark + #define uxTaskGetStackHighWaterMark2 MPU_uxTaskGetStackHighWaterMark2 + #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag + #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag + #define vTaskSetThreadLocalStoragePointer MPU_vTaskSetThreadLocalStoragePointer + #define pvTaskGetThreadLocalStoragePointer MPU_pvTaskGetThreadLocalStoragePointer + #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook + #define xTaskGetIdleTaskHandle MPU_xTaskGetIdleTaskHandle + #define uxTaskGetSystemState MPU_uxTaskGetSystemState + #define vTaskList MPU_vTaskList + #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats + #define ulTaskGetIdleRunTimeCounter MPU_ulTaskGetIdleRunTimeCounter + #define xTaskGenericNotify MPU_xTaskGenericNotify + #define xTaskNotifyWait MPU_xTaskNotifyWait + #define ulTaskNotifyTake MPU_ulTaskNotifyTake + #define xTaskNotifyStateClear MPU_xTaskNotifyStateClear + #define ulTaskNotifyValueClear MPU_ulTaskNotifyValueClear + #define xTaskCatchUpTicks MPU_xTaskCatchUpTicks + + #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle + #define vTaskSetTimeOutState MPU_vTaskSetTimeOutState + #define xTaskCheckForTimeOut MPU_xTaskCheckForTimeOut + #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState + + /* Map standard queue.h API functions to the MPU equivalents. */ + #define xQueueGenericSend MPU_xQueueGenericSend + #define xQueueReceive MPU_xQueueReceive + #define xQueuePeek MPU_xQueuePeek + #define xQueueSemaphoreTake MPU_xQueueSemaphoreTake + #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting + #define uxQueueSpacesAvailable MPU_uxQueueSpacesAvailable + #define vQueueDelete MPU_vQueueDelete + #define xQueueCreateMutex MPU_xQueueCreateMutex + #define xQueueCreateMutexStatic MPU_xQueueCreateMutexStatic + #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore + #define xQueueCreateCountingSemaphoreStatic MPU_xQueueCreateCountingSemaphoreStatic + #define xQueueGetMutexHolder MPU_xQueueGetMutexHolder + #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive + #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive + #define xQueueGenericCreate MPU_xQueueGenericCreate + #define xQueueGenericCreateStatic MPU_xQueueGenericCreateStatic + #define xQueueCreateSet MPU_xQueueCreateSet + #define xQueueAddToSet MPU_xQueueAddToSet + #define xQueueRemoveFromSet MPU_xQueueRemoveFromSet + #define xQueueSelectFromSet MPU_xQueueSelectFromSet + #define xQueueGenericReset MPU_xQueueGenericReset + + #if( configQUEUE_REGISTRY_SIZE > 0 ) + #define vQueueAddToRegistry MPU_vQueueAddToRegistry + #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue + #define pcQueueGetName MPU_pcQueueGetName + #endif + + /* Map standard timer.h API functions to the MPU equivalents. */ + #define xTimerCreate MPU_xTimerCreate + #define xTimerCreateStatic MPU_xTimerCreateStatic + #define pvTimerGetTimerID MPU_pvTimerGetTimerID + #define vTimerSetTimerID MPU_vTimerSetTimerID + #define xTimerIsTimerActive MPU_xTimerIsTimerActive + #define xTimerGetTimerDaemonTaskHandle MPU_xTimerGetTimerDaemonTaskHandle + #define xTimerPendFunctionCall MPU_xTimerPendFunctionCall + #define pcTimerGetName MPU_pcTimerGetName + #define vTimerSetReloadMode MPU_vTimerSetReloadMode + #define uxTimerGetReloadMode MPU_uxTimerGetReloadMode + #define xTimerGetPeriod MPU_xTimerGetPeriod + #define xTimerGetExpiryTime MPU_xTimerGetExpiryTime + #define xTimerGenericCommand MPU_xTimerGenericCommand + + /* Map standard event_group.h API functions to the MPU equivalents. */ + #define xEventGroupCreate MPU_xEventGroupCreate + #define xEventGroupCreateStatic MPU_xEventGroupCreateStatic + #define xEventGroupWaitBits MPU_xEventGroupWaitBits + #define xEventGroupClearBits MPU_xEventGroupClearBits + #define xEventGroupSetBits MPU_xEventGroupSetBits + #define xEventGroupSync MPU_xEventGroupSync + #define vEventGroupDelete MPU_vEventGroupDelete + + /* Map standard message/stream_buffer.h API functions to the MPU + equivalents. */ + #define xStreamBufferSend MPU_xStreamBufferSend + #define xStreamBufferReceive MPU_xStreamBufferReceive + #define xStreamBufferNextMessageLengthBytes MPU_xStreamBufferNextMessageLengthBytes + #define vStreamBufferDelete MPU_vStreamBufferDelete + #define xStreamBufferIsFull MPU_xStreamBufferIsFull + #define xStreamBufferIsEmpty MPU_xStreamBufferIsEmpty + #define xStreamBufferReset MPU_xStreamBufferReset + #define xStreamBufferSpacesAvailable MPU_xStreamBufferSpacesAvailable + #define xStreamBufferBytesAvailable MPU_xStreamBufferBytesAvailable + #define xStreamBufferSetTriggerLevel MPU_xStreamBufferSetTriggerLevel + #define xStreamBufferGenericCreate MPU_xStreamBufferGenericCreate + #define xStreamBufferGenericCreateStatic MPU_xStreamBufferGenericCreateStatic + + + /* Remove the privileged function macro, but keep the PRIVILEGED_DATA + macro so applications can place data in privileged access sections + (useful when using statically allocated objects). */ + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + #define FREERTOS_SYSTEM_CALL + + #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + + /* Ensure API functions go in the privileged execution section. */ + #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + #define FREERTOS_SYSTEM_CALL __attribute__((section( "freertos_system_calls"))) + + #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + +#else /* portUSING_MPU_WRAPPERS */ + + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA + #define FREERTOS_SYSTEM_CALL + #define portUSING_MPU_WRAPPERS 0 + +#endif /* portUSING_MPU_WRAPPERS */ + + +#endif /* MPU_WRAPPERS_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/portable.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/portable.h new file mode 100644 index 0000000..26ea870 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/portable.h @@ -0,0 +1,199 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/*----------------------------------------------------------- + * Portable layer API. Each function must be defined for each port. + *----------------------------------------------------------*/ + +#ifndef PORTABLE_H +#define PORTABLE_H + +/* Each FreeRTOS port has a unique portmacro.h header file. Originally a +pre-processor definition was used to ensure the pre-processor found the correct +portmacro.h file for the port being used. That scheme was deprecated in favour +of setting the compiler's include path such that it found the correct +portmacro.h file - removing the need for the constant and allowing the +portmacro.h file to be located anywhere in relation to the port being used. +Purely for reasons of backward compatibility the old method is still valid, but +to make it clear that new projects should not use it, support for the port +specific constants has been moved into the deprecated_definitions.h header +file. */ +#include "deprecated_definitions.h" + +/* If portENTER_CRITICAL is not defined then including deprecated_definitions.h +did not result in a portmacro.h header file being included - and it should be +included here. In this case the path to the correct portmacro.h header file +must be set in the compiler's include path. */ +#ifndef portENTER_CRITICAL + #include "portmacro.h" +#endif + +#if portBYTE_ALIGNMENT == 32 + #define portBYTE_ALIGNMENT_MASK ( 0x001f ) +#endif + +#if portBYTE_ALIGNMENT == 16 + #define portBYTE_ALIGNMENT_MASK ( 0x000f ) +#endif + +#if portBYTE_ALIGNMENT == 8 + #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) +#endif + +#if portBYTE_ALIGNMENT == 4 + #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) +#endif + +#if portBYTE_ALIGNMENT == 2 + #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) +#endif + +#if portBYTE_ALIGNMENT == 1 + #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) +#endif + +#ifndef portBYTE_ALIGNMENT_MASK + #error "Invalid portBYTE_ALIGNMENT definition" +#endif + +#ifndef portNUM_CONFIGURABLE_REGIONS + #define portNUM_CONFIGURABLE_REGIONS 1 +#endif + +#ifndef portHAS_STACK_OVERFLOW_CHECKING + #define portHAS_STACK_OVERFLOW_CHECKING 0 +#endif + +#ifndef portARCH_NAME + #define portARCH_NAME NULL +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "mpu_wrappers.h" + +/* + * Setup the stack of a new task so it is ready to be placed under the + * scheduler control. The registers have to be placed on the stack in + * the order that the port expects to find them. + * + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + #if( portHAS_STACK_OVERFLOW_CHECKING == 1 ) + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, StackType_t *pxEndOfStack, TaskFunction_t pxCode, void *pvParameters, BaseType_t xRunPrivileged ) PRIVILEGED_FUNCTION; + #else + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters, BaseType_t xRunPrivileged ) PRIVILEGED_FUNCTION; + #endif +#else + #if( portHAS_STACK_OVERFLOW_CHECKING == 1 ) + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, StackType_t *pxEndOfStack, TaskFunction_t pxCode, void *pvParameters ) PRIVILEGED_FUNCTION; + #else + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters ) PRIVILEGED_FUNCTION; + #endif +#endif + +/* Used by heap_5.c to define the start address and size of each memory region +that together comprise the total FreeRTOS heap space. */ +typedef struct HeapRegion +{ + uint8_t *pucStartAddress; + size_t xSizeInBytes; +} HeapRegion_t; + +/* Used to pass information about the heap out of vPortGetHeapStats(). */ +typedef struct xHeapStats +{ + size_t xAvailableHeapSpaceInBytes; /* The total heap size currently available - this is the sum of all the free blocks, not the largest block that can be allocated. */ + size_t xSizeOfLargestFreeBlockInBytes; /* The maximum size, in bytes, of all the free blocks within the heap at the time vPortGetHeapStats() is called. */ + size_t xSizeOfSmallestFreeBlockInBytes; /* The minimum size, in bytes, of all the free blocks within the heap at the time vPortGetHeapStats() is called. */ + size_t xNumberOfFreeBlocks; /* The number of free memory blocks within the heap at the time vPortGetHeapStats() is called. */ + size_t xMinimumEverFreeBytesRemaining; /* The minimum amount of total free memory (sum of all free blocks) there has been in the heap since the system booted. */ + size_t xNumberOfSuccessfulAllocations; /* The number of calls to pvPortMalloc() that have returned a valid memory block. */ + size_t xNumberOfSuccessfulFrees; /* The number of calls to vPortFree() that has successfully freed a block of memory. */ +} HeapStats_t; + +/* + * Used to define multiple heap regions for use by heap_5.c. This function + * must be called before any calls to pvPortMalloc() - not creating a task, + * queue, semaphore, mutex, software timer, event group, etc. will result in + * pvPortMalloc being called. + * + * pxHeapRegions passes in an array of HeapRegion_t structures - each of which + * defines a region of memory that can be used as the heap. The array is + * terminated by a HeapRegions_t structure that has a size of 0. The region + * with the lowest start address must appear first in the array. + */ +void vPortDefineHeapRegions( const HeapRegion_t * const pxHeapRegions ) PRIVILEGED_FUNCTION; + +/* + * Returns a HeapStats_t structure filled with information about the current + * heap state. + */ +void vPortGetHeapStats( HeapStats_t *pxHeapStats ); + +/* + * Map to the memory management routines required for the port. + */ +void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; +void vPortFree( void *pv ) PRIVILEGED_FUNCTION; +void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; +size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; +size_t xPortGetMinimumEverFreeHeapSize( void ) PRIVILEGED_FUNCTION; + +/* + * Setup the hardware ready for the scheduler to take control. This generally + * sets up a tick interrupt and sets timers for the correct tick frequency. + */ +BaseType_t xPortStartScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so + * the hardware is left in its original condition after the scheduler stops + * executing. + */ +void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * The structures and methods of manipulating the MPU are contained within the + * port layer. + * + * Fills the xMPUSettings structure with the memory region information + * contained in xRegions. + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + struct xMEMORY_REGION; + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, StackType_t *pxBottomOfStack, uint32_t ulStackDepth ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* PORTABLE_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/projdefs.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/projdefs.h new file mode 100644 index 0000000..1a842b3 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/projdefs.h @@ -0,0 +1,124 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 PROJDEFS_H +#define PROJDEFS_H + +/* + * Defines the prototype to which task functions must conform. Defined in this + * file to ensure the type is known before portable.h is included. + */ +typedef void (*TaskFunction_t)( void * ); + +/* Converts a time in milliseconds to a time in ticks. This macro can be +overridden by a macro of the same name defined in FreeRTOSConfig.h in case the +definition here is not suitable for your application. */ +#ifndef pdMS_TO_TICKS + #define pdMS_TO_TICKS( xTimeInMs ) ( ( TickType_t ) ( ( ( TickType_t ) ( xTimeInMs ) * ( TickType_t ) configTICK_RATE_HZ ) / ( TickType_t ) 1000 ) ) +#endif + +#define pdFALSE ( ( BaseType_t ) 0 ) +#define pdTRUE ( ( BaseType_t ) 1 ) + +#define pdPASS ( pdTRUE ) +#define pdFAIL ( pdFALSE ) +#define errQUEUE_EMPTY ( ( BaseType_t ) 0 ) +#define errQUEUE_FULL ( ( BaseType_t ) 0 ) + +/* FreeRTOS error definitions. */ +#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) +#define errQUEUE_BLOCKED ( -4 ) +#define errQUEUE_YIELD ( -5 ) + +/* Macros used for basic data corruption checks. */ +#ifndef configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES + #define configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES 0 +#endif + +#if( configUSE_16_BIT_TICKS == 1 ) + #define pdINTEGRITY_CHECK_VALUE 0x5a5a +#else + #define pdINTEGRITY_CHECK_VALUE 0x5a5a5a5aUL +#endif + +/* The following errno values are used by FreeRTOS+ components, not FreeRTOS +itself. */ +#define pdFREERTOS_ERRNO_NONE 0 /* No errors */ +#define pdFREERTOS_ERRNO_ENOENT 2 /* No such file or directory */ +#define pdFREERTOS_ERRNO_EINTR 4 /* Interrupted system call */ +#define pdFREERTOS_ERRNO_EIO 5 /* I/O error */ +#define pdFREERTOS_ERRNO_ENXIO 6 /* No such device or address */ +#define pdFREERTOS_ERRNO_EBADF 9 /* Bad file number */ +#define pdFREERTOS_ERRNO_EAGAIN 11 /* No more processes */ +#define pdFREERTOS_ERRNO_EWOULDBLOCK 11 /* Operation would block */ +#define pdFREERTOS_ERRNO_ENOMEM 12 /* Not enough memory */ +#define pdFREERTOS_ERRNO_EACCES 13 /* Permission denied */ +#define pdFREERTOS_ERRNO_EFAULT 14 /* Bad address */ +#define pdFREERTOS_ERRNO_EBUSY 16 /* Mount device busy */ +#define pdFREERTOS_ERRNO_EEXIST 17 /* File exists */ +#define pdFREERTOS_ERRNO_EXDEV 18 /* Cross-device link */ +#define pdFREERTOS_ERRNO_ENODEV 19 /* No such device */ +#define pdFREERTOS_ERRNO_ENOTDIR 20 /* Not a directory */ +#define pdFREERTOS_ERRNO_EISDIR 21 /* Is a directory */ +#define pdFREERTOS_ERRNO_EINVAL 22 /* Invalid argument */ +#define pdFREERTOS_ERRNO_ENOSPC 28 /* No space left on device */ +#define pdFREERTOS_ERRNO_ESPIPE 29 /* Illegal seek */ +#define pdFREERTOS_ERRNO_EROFS 30 /* Read only file system */ +#define pdFREERTOS_ERRNO_EUNATCH 42 /* Protocol driver not attached */ +#define pdFREERTOS_ERRNO_EBADE 50 /* Invalid exchange */ +#define pdFREERTOS_ERRNO_EFTYPE 79 /* Inappropriate file type or format */ +#define pdFREERTOS_ERRNO_ENMFILE 89 /* No more files */ +#define pdFREERTOS_ERRNO_ENOTEMPTY 90 /* Directory not empty */ +#define pdFREERTOS_ERRNO_ENAMETOOLONG 91 /* File or path name too long */ +#define pdFREERTOS_ERRNO_EOPNOTSUPP 95 /* Operation not supported on transport endpoint */ +#define pdFREERTOS_ERRNO_ENOBUFS 105 /* No buffer space available */ +#define pdFREERTOS_ERRNO_ENOPROTOOPT 109 /* Protocol not available */ +#define pdFREERTOS_ERRNO_EADDRINUSE 112 /* Address already in use */ +#define pdFREERTOS_ERRNO_ETIMEDOUT 116 /* Connection timed out */ +#define pdFREERTOS_ERRNO_EINPROGRESS 119 /* Connection already in progress */ +#define pdFREERTOS_ERRNO_EALREADY 120 /* Socket already connected */ +#define pdFREERTOS_ERRNO_EADDRNOTAVAIL 125 /* Address not available */ +#define pdFREERTOS_ERRNO_EISCONN 127 /* Socket is already connected */ +#define pdFREERTOS_ERRNO_ENOTCONN 128 /* Socket is not connected */ +#define pdFREERTOS_ERRNO_ENOMEDIUM 135 /* No medium inserted */ +#define pdFREERTOS_ERRNO_EILSEQ 138 /* An invalid UTF-16 sequence was encountered. */ +#define pdFREERTOS_ERRNO_ECANCELED 140 /* Operation canceled. */ + +/* The following endian values are used by FreeRTOS+ components, not FreeRTOS +itself. */ +#define pdFREERTOS_LITTLE_ENDIAN 0 +#define pdFREERTOS_BIG_ENDIAN 1 + +/* Re-defining endian values for generic naming. */ +#define pdLITTLE_ENDIAN pdFREERTOS_LITTLE_ENDIAN +#define pdBIG_ENDIAN pdFREERTOS_BIG_ENDIAN + + +#endif /* PROJDEFS_H */ + + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/queue.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/queue.h new file mode 100644 index 0000000..ca25266 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/queue.h @@ -0,0 +1,1655 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 QUEUE_H +#define QUEUE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include queue.h" +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "task.h" + +/** + * Type by which queues are referenced. For example, a call to xQueueCreate() + * returns an QueueHandle_t variable that can then be used as a parameter to + * xQueueSend(), xQueueReceive(), etc. + */ +struct QueueDefinition; /* Using old naming convention so as not to break kernel aware debuggers. */ +typedef struct QueueDefinition * QueueHandle_t; + +/** + * Type by which queue sets are referenced. For example, a call to + * xQueueCreateSet() returns an xQueueSet variable that can then be used as a + * parameter to xQueueSelectFromSet(), xQueueAddToSet(), etc. + */ +typedef struct QueueDefinition * QueueSetHandle_t; + +/** + * Queue sets can contain both queues and semaphores, so the + * QueueSetMemberHandle_t is defined as a type to be used where a parameter or + * return value can be either an QueueHandle_t or an SemaphoreHandle_t. + */ +typedef struct QueueDefinition * QueueSetMemberHandle_t; + +/* For internal use only. */ +#define queueSEND_TO_BACK ( ( BaseType_t ) 0 ) +#define queueSEND_TO_FRONT ( ( BaseType_t ) 1 ) +#define queueOVERWRITE ( ( BaseType_t ) 2 ) + +/* For internal use only. These definitions *must* match those in queue.c. */ +#define queueQUEUE_TYPE_BASE ( ( uint8_t ) 0U ) +#define queueQUEUE_TYPE_SET ( ( uint8_t ) 0U ) +#define queueQUEUE_TYPE_MUTEX ( ( uint8_t ) 1U ) +#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( ( uint8_t ) 2U ) +#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( ( uint8_t ) 3U ) +#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( ( uint8_t ) 4U ) + +/** + * queue. h + *
+ QueueHandle_t xQueueCreate(
+							  UBaseType_t uxQueueLength,
+							  UBaseType_t uxItemSize
+						  );
+ * 
+ * + * Creates a new queue instance, and returns a handle by which the new queue + * can be referenced. + * + * Internally, within the FreeRTOS implementation, queues use two blocks of + * memory. The first block is used to hold the queue's data structures. The + * second block is used to hold items placed into the queue. If a queue is + * created using xQueueCreate() then both blocks of memory are automatically + * dynamically allocated inside the xQueueCreate() function. (see + * http://www.freertos.org/a00111.html). If a queue is created using + * xQueueCreateStatic() then the application writer must provide the memory that + * will get used by the queue. xQueueCreateStatic() therefore allows a queue to + * be created without using any dynamic memory allocation. + * + * http://www.FreeRTOS.org/Embedded-RTOS-Queues.html + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @return If the queue is successfully create then a handle to the newly + * created queue is returned. If the queue cannot be created then 0 is + * returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreate xQueueCreate + * \ingroup QueueManagement + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define xQueueCreate( uxQueueLength, uxItemSize ) xQueueGenericCreate( ( uxQueueLength ), ( uxItemSize ), ( queueQUEUE_TYPE_BASE ) ) +#endif + +/** + * queue. h + *
+ QueueHandle_t xQueueCreateStatic(
+							  UBaseType_t uxQueueLength,
+							  UBaseType_t uxItemSize,
+							  uint8_t *pucQueueStorageBuffer,
+							  StaticQueue_t *pxQueueBuffer
+						  );
+ * 
+ * + * Creates a new queue instance, and returns a handle by which the new queue + * can be referenced. + * + * Internally, within the FreeRTOS implementation, queues use two blocks of + * memory. The first block is used to hold the queue's data structures. The + * second block is used to hold items placed into the queue. If a queue is + * created using xQueueCreate() then both blocks of memory are automatically + * dynamically allocated inside the xQueueCreate() function. (see + * http://www.freertos.org/a00111.html). If a queue is created using + * xQueueCreateStatic() then the application writer must provide the memory that + * will get used by the queue. xQueueCreateStatic() therefore allows a queue to + * be created without using any dynamic memory allocation. + * + * http://www.FreeRTOS.org/Embedded-RTOS-Queues.html + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @param pucQueueStorageBuffer If uxItemSize is not zero then + * pucQueueStorageBuffer must point to a uint8_t array that is at least large + * enough to hold the maximum number of items that can be in the queue at any + * one time - which is ( uxQueueLength * uxItemsSize ) bytes. If uxItemSize is + * zero then pucQueueStorageBuffer can be NULL. + * + * @param pxQueueBuffer Must point to a variable of type StaticQueue_t, which + * will be used to hold the queue's data structure. + * + * @return If the queue is created then a handle to the created queue is + * returned. If pxQueueBuffer is NULL then NULL is returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ #define QUEUE_LENGTH 10
+ #define ITEM_SIZE sizeof( uint32_t )
+
+ // xQueueBuffer will hold the queue structure.
+ StaticQueue_t xQueueBuffer;
+
+ // ucQueueStorage will hold the items posted to the queue.  Must be at least
+ // [(queue length) * ( queue item size)] bytes long.
+ uint8_t ucQueueStorage[ QUEUE_LENGTH * ITEM_SIZE ];
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( QUEUE_LENGTH, // The number of items the queue can hold.
+							ITEM_SIZE	  // The size of each item in the queue
+							&( ucQueueStorage[ 0 ] ), // The buffer that will hold the items in the queue.
+							&xQueueBuffer ); // The buffer that will hold the queue structure.
+
+	// The queue is guaranteed to be created successfully as no dynamic memory
+	// allocation is used.  Therefore xQueue1 is now a handle to a valid queue.
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreateStatic xQueueCreateStatic + * \ingroup QueueManagement + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + #define xQueueCreateStatic( uxQueueLength, uxItemSize, pucQueueStorage, pxQueueBuffer ) xQueueGenericCreateStatic( ( uxQueueLength ), ( uxItemSize ), ( pucQueueStorage ), ( pxQueueBuffer ), ( queueQUEUE_TYPE_BASE ) ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * queue. h + *
+ BaseType_t xQueueSendToToFront(
+								   QueueHandle_t	xQueue,
+								   const void		*pvItemToQueue,
+								   TickType_t		xTicksToWait
+							   );
+ * 
+ * + * Post an item to the front of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) + +/** + * queue. h + *
+ BaseType_t xQueueSendToBack(
+								   QueueHandle_t	xQueue,
+								   const void		*pvItemToQueue,
+								   TickType_t		xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the back of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the queue + * is full. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ BaseType_t xQueueSend(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue,
+							  TickType_t xTicksToWait
+						 );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). It is included for + * backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToFront() and xQueueSendToBack() macros. It is + * equivalent to xQueueSendToBack(). + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ BaseType_t xQueueOverwrite(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue
+						 );
+ * 
+ * + * Only for use with queues that have a length of one - so the queue is either + * empty or full. + * + * Post an item on a queue. If the queue is already full then overwrite the + * value held in the queue. The item is queued by copy, not by reference. + * + * This function must not be called from an interrupt service routine. + * See xQueueOverwriteFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle of the queue to which the data is being sent. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @return xQueueOverwrite() is a macro that calls xQueueGenericSend(), and + * therefore has the same return values as xQueueSendToFront(). However, pdPASS + * is the only value that can be returned because xQueueOverwrite() will write + * to the queue even when the queue is already full. + * + * Example usage: +
+
+ void vFunction( void *pvParameters )
+ {
+ QueueHandle_t xQueue;
+ uint32_t ulVarToSend, ulValReceived;
+
+	// Create a queue to hold one uint32_t value.  It is strongly
+	// recommended *not* to use xQueueOverwrite() on queues that can
+	// contain more than one value, and doing so will trigger an assertion
+	// if configASSERT() is defined.
+	xQueue = xQueueCreate( 1, sizeof( uint32_t ) );
+
+	// Write the value 10 to the queue using xQueueOverwrite().
+	ulVarToSend = 10;
+	xQueueOverwrite( xQueue, &ulVarToSend );
+
+	// Peeking the queue should now return 10, but leave the value 10 in
+	// the queue.  A block time of zero is used as it is known that the
+	// queue holds a value.
+	ulValReceived = 0;
+	xQueuePeek( xQueue, &ulValReceived, 0 );
+
+	if( ulValReceived != 10 )
+	{
+		// Error unless the item was removed by a different task.
+	}
+
+	// The queue is still full.  Use xQueueOverwrite() to overwrite the
+	// value held in the queue with 100.
+	ulVarToSend = 100;
+	xQueueOverwrite( xQueue, &ulVarToSend );
+
+	// This time read from the queue, leaving the queue empty once more.
+	// A block time of 0 is used again.
+	xQueueReceive( xQueue, &ulValReceived, 0 );
+
+	// The value read should be the last value written, even though the
+	// queue was already full when the value was written.
+	if( ulValReceived != 100 )
+	{
+		// Error!
+	}
+
+	// ...
+}
+ 
+ * \defgroup xQueueOverwrite xQueueOverwrite + * \ingroup QueueManagement + */ +#define xQueueOverwrite( xQueue, pvItemToQueue ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), 0, queueOVERWRITE ) + + +/** + * queue. h + *
+ BaseType_t xQueueGenericSend(
+									QueueHandle_t xQueue,
+									const void * pvItemToQueue,
+									TickType_t xTicksToWait
+									BaseType_t xCopyPosition
+								);
+ * 
+ * + * It is preferred that the macros xQueueSend(), xQueueSendToFront() and + * xQueueSendToBack() are used in place of calling this function directly. + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +BaseType_t xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, const BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueuePeek(
+							 QueueHandle_t xQueue,
+							 void * const pvBuffer,
+							 TickType_t xTicksToWait
+						 );
+ * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * This macro must not be used in an interrupt service routine. See + * xQueuePeekFromISR() for an alternative that can be called from an interrupt + * service routine. + * + * @param xQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue + * is empty. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ QueueHandle_t xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( TickType_t ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( TickType_t ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueuePeek xQueuePeek + * \ingroup QueueManagement + */ +BaseType_t xQueuePeek( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueuePeekFromISR(
+									QueueHandle_t xQueue,
+									void *pvBuffer,
+								);
+ * + * A version of xQueuePeek() that can be called from an interrupt service + * routine (ISR). + * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * @param xQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * \defgroup xQueuePeekFromISR xQueuePeekFromISR + * \ingroup QueueManagement + */ +BaseType_t xQueuePeekFromISR( QueueHandle_t xQueue, void * const pvBuffer ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueueReceive(
+								 QueueHandle_t xQueue,
+								 void *pvBuffer,
+								 TickType_t xTicksToWait
+							);
+ * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * Successfully received items are removed from the queue. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param xQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. xQueueReceive() will return immediately if xTicksToWait + * is zero and the queue is empty. The time is defined in tick periods so the + * constant portTICK_PERIOD_MS should be used to convert to real time if this is + * required. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ QueueHandle_t xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( TickType_t ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( TickType_t ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +BaseType_t xQueueReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue );
+ * + * Return the number of messages stored in a queue. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of messages available in the queue. + * + * \defgroup uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue );
+ * + * Return the number of free spaces available in a queue. This is equal to the + * number of items that can be sent to the queue before the queue becomes full + * if no items are removed. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of spaces available in the queue. + * + * \defgroup uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
void vQueueDelete( QueueHandle_t xQueue );
+ * + * Delete a queue - freeing all the memory allocated for storing of items + * placed on the queue. + * + * @param xQueue A handle to the queue to be deleted. + * + * \defgroup vQueueDelete vQueueDelete + * \ingroup QueueManagement + */ +void vQueueDelete( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueueSendToFrontFromISR(
+										 QueueHandle_t xQueue,
+										 const void *pvItemToQueue,
+										 BaseType_t *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the front of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToFrontFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) + + +/** + * queue. h + *
+ BaseType_t xQueueSendToBackFromISR(
+										 QueueHandle_t xQueue,
+										 const void *pvItemToQueue,
+										 BaseType_t *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the back of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToBackFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ BaseType_t xQueueOverwriteFromISR(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue,
+							  BaseType_t *pxHigherPriorityTaskWoken
+						 );
+ * 
+ * + * A version of xQueueOverwrite() that can be used in an interrupt service + * routine (ISR). + * + * Only for use with queues that can hold a single item - so the queue is either + * empty or full. + * + * Post an item on a queue. If the queue is already full then overwrite the + * value held in the queue. The item is queued by copy, not by reference. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueOverwriteFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueOverwriteFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return xQueueOverwriteFromISR() is a macro that calls + * xQueueGenericSendFromISR(), and therefore has the same return values as + * xQueueSendToFrontFromISR(). However, pdPASS is the only value that can be + * returned because xQueueOverwriteFromISR() will write to the queue even when + * the queue is already full. + * + * Example usage: +
+
+ QueueHandle_t xQueue;
+
+ void vFunction( void *pvParameters )
+ {
+ 	// Create a queue to hold one uint32_t value.  It is strongly
+	// recommended *not* to use xQueueOverwriteFromISR() on queues that can
+	// contain more than one value, and doing so will trigger an assertion
+	// if configASSERT() is defined.
+	xQueue = xQueueCreate( 1, sizeof( uint32_t ) );
+}
+
+void vAnInterruptHandler( void )
+{
+// xHigherPriorityTaskWoken must be set to pdFALSE before it is used.
+BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+uint32_t ulVarToSend, ulValReceived;
+
+	// Write the value 10 to the queue using xQueueOverwriteFromISR().
+	ulVarToSend = 10;
+	xQueueOverwriteFromISR( xQueue, &ulVarToSend, &xHigherPriorityTaskWoken );
+
+	// The queue is full, but calling xQueueOverwriteFromISR() again will still
+	// pass because the value held in the queue will be overwritten with the
+	// new value.
+	ulVarToSend = 100;
+	xQueueOverwriteFromISR( xQueue, &ulVarToSend, &xHigherPriorityTaskWoken );
+
+	// Reading from the queue will now return 100.
+
+	// ...
+
+	if( xHigherPrioritytaskWoken == pdTRUE )
+	{
+		// Writing to the queue caused a task to unblock and the unblocked task
+		// has a priority higher than or equal to the priority of the currently
+		// executing task (the task this interrupt interrupted).  Perform a context
+		// switch so this interrupt returns directly to the unblocked task.
+		portYIELD_FROM_ISR(); // or portEND_SWITCHING_ISR() depending on the port.
+	}
+}
+ 
+ * \defgroup xQueueOverwriteFromISR xQueueOverwriteFromISR + * \ingroup QueueManagement + */ +#define xQueueOverwriteFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueOVERWRITE ) + +/** + * queue. h + *
+ BaseType_t xQueueSendFromISR(
+									 QueueHandle_t xQueue,
+									 const void *pvItemToQueue,
+									 BaseType_t *pxHigherPriorityTaskWoken
+								);
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). It is included + * for backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() + * macros. + * + * Post an item to the back of a queue. It is safe to use this function from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		portYIELD_FROM_ISR ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ BaseType_t xQueueGenericSendFromISR(
+										   QueueHandle_t		xQueue,
+										   const	void	*pvItemToQueue,
+										   BaseType_t	*pxHigherPriorityTaskWoken,
+										   BaseType_t	xCopyPosition
+									   );
+ 
+ * + * It is preferred that the macros xQueueSendFromISR(), + * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place + * of calling this function directly. xQueueGiveFromISR() is an + * equivalent for use by semaphores that don't actually copy any data. + * + * Post an item on a queue. It is safe to use this function from within an + * interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		portYIELD_FROM_ISR();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +BaseType_t xQueueGenericSendFromISR( QueueHandle_t xQueue, const void * const pvItemToQueue, BaseType_t * const pxHigherPriorityTaskWoken, const BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION; +BaseType_t xQueueGiveFromISR( QueueHandle_t xQueue, BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueueReceiveFromISR(
+									   QueueHandle_t	xQueue,
+									   void	*pvBuffer,
+									   BaseType_t *pxTaskWoken
+								   );
+ * 
+ * + * Receive an item from a queue. It is safe to use this function from within an + * interrupt service routine. + * + * @param xQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param pxTaskWoken A task may be blocked waiting for space to become + * available on the queue. If xQueueReceiveFromISR causes such a task to + * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will + * remain unchanged. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+
+ QueueHandle_t xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const TickType_t xTicksToWait = ( TickType_t )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xTicksToWait ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ BaseType_t xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR + * \ingroup QueueManagement + */ +BaseType_t xQueueReceiveFromISR( QueueHandle_t xQueue, void * const pvBuffer, BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/* + * Utilities to query queues that are safe to use from an ISR. These utilities + * should be used only from witin an ISR, or within a critical section. + */ +BaseType_t xQueueIsQueueEmptyFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; +BaseType_t xQueueIsQueueFullFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; +UBaseType_t uxQueueMessagesWaitingFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + +/* + * The functions defined above are for passing data to and from tasks. The + * functions below are the equivalents for passing data to and from + * co-routines. + * + * These functions are called from the co-routine macro implementation and + * should not be called directly from application code. Instead use the macro + * wrappers defined within croutine.h. + */ +BaseType_t xQueueCRSendFromISR( QueueHandle_t xQueue, const void *pvItemToQueue, BaseType_t xCoRoutinePreviouslyWoken ); +BaseType_t xQueueCRReceiveFromISR( QueueHandle_t xQueue, void *pvBuffer, BaseType_t *pxTaskWoken ); +BaseType_t xQueueCRSend( QueueHandle_t xQueue, const void *pvItemToQueue, TickType_t xTicksToWait ); +BaseType_t xQueueCRReceive( QueueHandle_t xQueue, void *pvBuffer, TickType_t xTicksToWait ); + +/* + * For internal use only. Use xSemaphoreCreateMutex(), + * xSemaphoreCreateCounting() or xSemaphoreGetMutexHolder() instead of calling + * these functions directly. + */ +QueueHandle_t xQueueCreateMutex( const uint8_t ucQueueType ) PRIVILEGED_FUNCTION; +QueueHandle_t xQueueCreateMutexStatic( const uint8_t ucQueueType, StaticQueue_t *pxStaticQueue ) PRIVILEGED_FUNCTION; +QueueHandle_t xQueueCreateCountingSemaphore( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount ) PRIVILEGED_FUNCTION; +QueueHandle_t xQueueCreateCountingSemaphoreStatic( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount, StaticQueue_t *pxStaticQueue ) PRIVILEGED_FUNCTION; +BaseType_t xQueueSemaphoreTake( QueueHandle_t xQueue, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; +TaskHandle_t xQueueGetMutexHolder( QueueHandle_t xSemaphore ) PRIVILEGED_FUNCTION; +TaskHandle_t xQueueGetMutexHolderFromISR( QueueHandle_t xSemaphore ) PRIVILEGED_FUNCTION; + +/* + * For internal use only. Use xSemaphoreTakeMutexRecursive() or + * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. + */ +BaseType_t xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; +BaseType_t xQueueGiveMutexRecursive( QueueHandle_t xMutex ) PRIVILEGED_FUNCTION; + +/* + * Reset a queue back to its original empty state. The return value is now + * obsolete and is always set to pdPASS. + */ +#define xQueueReset( xQueue ) xQueueGenericReset( xQueue, pdFALSE ) + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger. If you are not using a kernel + * aware debugger then this function can be ignored. + * + * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the + * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 + * within FreeRTOSConfig.h for the registry to be available. Its value + * does not effect the number of queues, semaphores and mutexes that can be + * created - just the number that the registry can hold. + * + * @param xQueue The handle of the queue being added to the registry. This + * is the handle returned by a call to xQueueCreate(). Semaphore and mutex + * handles can also be passed in here. + * + * @param pcName The name to be associated with the handle. This is the + * name that the kernel aware debugger will display. The queue registry only + * stores a pointer to the string - so the string must be persistent (global or + * preferably in ROM/Flash), not on the stack. + */ +#if( configQUEUE_REGISTRY_SIZE > 0 ) + void vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcQueueName ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ +#endif + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger, and vQueueUnregisterQueue() to + * remove the queue, semaphore or mutex from the register. If you are not using + * a kernel aware debugger then this function can be ignored. + * + * @param xQueue The handle of the queue being removed from the registry. + */ +#if( configQUEUE_REGISTRY_SIZE > 0 ) + void vQueueUnregisterQueue( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; +#endif + +/* + * The queue registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call pcQueueGetName() to look + * up and return the name of a queue in the queue registry from the queue's + * handle. + * + * @param xQueue The handle of the queue the name of which will be returned. + * @return If the queue is in the registry then a pointer to the name of the + * queue is returned. If the queue is not in the registry then NULL is + * returned. + */ +#if( configQUEUE_REGISTRY_SIZE > 0 ) + const char *pcQueueGetName( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ +#endif + +/* + * Generic version of the function used to creaet a queue using dynamic memory + * allocation. This is called by other functions and macros that create other + * RTOS objects that use the queue structure as their base. + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + QueueHandle_t xQueueGenericCreate( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType ) PRIVILEGED_FUNCTION; +#endif + +/* + * Generic version of the function used to creaet a queue using dynamic memory + * allocation. This is called by other functions and macros that create other + * RTOS objects that use the queue structure as their base. + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + QueueHandle_t xQueueGenericCreateStatic( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, StaticQueue_t *pxStaticQueue, const uint8_t ucQueueType ) PRIVILEGED_FUNCTION; +#endif + +/* + * Queue sets provide a mechanism to allow a task to block (pend) on a read + * operation from multiple queues or semaphores simultaneously. + * + * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this + * function. + * + * A queue set must be explicitly created using a call to xQueueCreateSet() + * before it can be used. Once created, standard FreeRTOS queues and semaphores + * can be added to the set using calls to xQueueAddToSet(). + * xQueueSelectFromSet() is then used to determine which, if any, of the queues + * or semaphores contained in the set is in a state where a queue read or + * semaphore take operation would be successful. + * + * Note 1: See the documentation on http://wwwFreeRTOS.org/RTOS-queue-sets.html + * for reasons why queue sets are very rarely needed in practice as there are + * simpler methods of blocking on multiple objects. + * + * Note 2: Blocking on a queue set that contains a mutex will not cause the + * mutex holder to inherit the priority of the blocked task. + * + * Note 3: An additional 4 bytes of RAM is required for each space in a every + * queue added to a queue set. Therefore counting semaphores that have a high + * maximum count value should not be added to a queue set. + * + * Note 4: A receive (in the case of a queue) or take (in the case of a + * semaphore) operation must not be performed on a member of a queue set unless + * a call to xQueueSelectFromSet() has first returned a handle to that set member. + * + * @param uxEventQueueLength Queue sets store events that occur on + * the queues and semaphores contained in the set. uxEventQueueLength specifies + * the maximum number of events that can be queued at once. To be absolutely + * certain that events are not lost uxEventQueueLength should be set to the + * total sum of the length of the queues added to the set, where binary + * semaphores and mutexes have a length of 1, and counting semaphores have a + * length set by their maximum count value. Examples: + * + If a queue set is to hold a queue of length 5, another queue of length 12, + * and a binary semaphore, then uxEventQueueLength should be set to + * (5 + 12 + 1), or 18. + * + If a queue set is to hold three binary semaphores then uxEventQueueLength + * should be set to (1 + 1 + 1 ), or 3. + * + If a queue set is to hold a counting semaphore that has a maximum count of + * 5, and a counting semaphore that has a maximum count of 3, then + * uxEventQueueLength should be set to (5 + 3), or 8. + * + * @return If the queue set is created successfully then a handle to the created + * queue set is returned. Otherwise NULL is returned. + */ +QueueSetHandle_t xQueueCreateSet( const UBaseType_t uxEventQueueLength ) PRIVILEGED_FUNCTION; + +/* + * Adds a queue or semaphore to a queue set that was previously created by a + * call to xQueueCreateSet(). + * + * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this + * function. + * + * Note 1: A receive (in the case of a queue) or take (in the case of a + * semaphore) operation must not be performed on a member of a queue set unless + * a call to xQueueSelectFromSet() has first returned a handle to that set member. + * + * @param xQueueOrSemaphore The handle of the queue or semaphore being added to + * the queue set (cast to an QueueSetMemberHandle_t type). + * + * @param xQueueSet The handle of the queue set to which the queue or semaphore + * is being added. + * + * @return If the queue or semaphore was successfully added to the queue set + * then pdPASS is returned. If the queue could not be successfully added to the + * queue set because it is already a member of a different queue set then pdFAIL + * is returned. + */ +BaseType_t xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION; + +/* + * Removes a queue or semaphore from a queue set. A queue or semaphore can only + * be removed from a set if the queue or semaphore is empty. + * + * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this + * function. + * + * @param xQueueOrSemaphore The handle of the queue or semaphore being removed + * from the queue set (cast to an QueueSetMemberHandle_t type). + * + * @param xQueueSet The handle of the queue set in which the queue or semaphore + * is included. + * + * @return If the queue or semaphore was successfully removed from the queue set + * then pdPASS is returned. If the queue was not in the queue set, or the + * queue (or semaphore) was not empty, then pdFAIL is returned. + */ +BaseType_t xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION; + +/* + * xQueueSelectFromSet() selects from the members of a queue set a queue or + * semaphore that either contains data (in the case of a queue) or is available + * to take (in the case of a semaphore). xQueueSelectFromSet() effectively + * allows a task to block (pend) on a read operation on all the queues and + * semaphores in a queue set simultaneously. + * + * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this + * function. + * + * Note 1: See the documentation on http://wwwFreeRTOS.org/RTOS-queue-sets.html + * for reasons why queue sets are very rarely needed in practice as there are + * simpler methods of blocking on multiple objects. + * + * Note 2: Blocking on a queue set that contains a mutex will not cause the + * mutex holder to inherit the priority of the blocked task. + * + * Note 3: A receive (in the case of a queue) or take (in the case of a + * semaphore) operation must not be performed on a member of a queue set unless + * a call to xQueueSelectFromSet() has first returned a handle to that set member. + * + * @param xQueueSet The queue set on which the task will (potentially) block. + * + * @param xTicksToWait The maximum time, in ticks, that the calling task will + * remain in the Blocked state (with other tasks executing) to wait for a member + * of the queue set to be ready for a successful queue read or semaphore take + * operation. + * + * @return xQueueSelectFromSet() will return the handle of a queue (cast to + * a QueueSetMemberHandle_t type) contained in the queue set that contains data, + * or the handle of a semaphore (cast to a QueueSetMemberHandle_t type) contained + * in the queue set that is available, or NULL if no such queue or semaphore + * exists before before the specified block time expires. + */ +QueueSetMemberHandle_t xQueueSelectFromSet( QueueSetHandle_t xQueueSet, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * A version of xQueueSelectFromSet() that can be used from an ISR. + */ +QueueSetMemberHandle_t xQueueSelectFromSetFromISR( QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION; + +/* Not public API functions. */ +void vQueueWaitForMessageRestricted( QueueHandle_t xQueue, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) PRIVILEGED_FUNCTION; +BaseType_t xQueueGenericReset( QueueHandle_t xQueue, BaseType_t xNewQueue ) PRIVILEGED_FUNCTION; +void vQueueSetQueueNumber( QueueHandle_t xQueue, UBaseType_t uxQueueNumber ) PRIVILEGED_FUNCTION; +UBaseType_t uxQueueGetQueueNumber( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; +uint8_t ucQueueGetQueueType( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + + +#ifdef __cplusplus +} +#endif + +#endif /* QUEUE_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/semphr.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/semphr.h new file mode 100644 index 0000000..9e86ee8 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/semphr.h @@ -0,0 +1,1140 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 SEMAPHORE_H +#define SEMAPHORE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include semphr.h" +#endif + +#include "queue.h" + +typedef QueueHandle_t SemaphoreHandle_t; + +#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( uint8_t ) 1U ) +#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( uint8_t ) 0U ) +#define semGIVE_BLOCK_TIME ( ( TickType_t ) 0U ) + + +/** + * semphr. h + *
vSemaphoreCreateBinary( SemaphoreHandle_t xSemaphore )
+ * + * In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a binary semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * This old vSemaphoreCreateBinary() macro is now deprecated in favour of the + * xSemaphoreCreateBinary() function. Note that binary semaphores created using + * the vSemaphoreCreateBinary() macro are created in a state such that the + * first call to 'take' the semaphore would pass, whereas binary semaphores + * created using xSemaphoreCreateBinary() are created in a state such that the + * the semaphore must first be 'given' before it can be 'taken'. + * + * Macro that implements a semaphore by using the existing queue mechanism. + * The queue length is 1 as this is a binary semaphore. The data size is 0 + * as we don't want to actually store any data - we just want to know if the + * queue is empty or full. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param xSemaphore Handle to the created semaphore. Should be of type SemaphoreHandle_t. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary + * \ingroup Semaphores + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define vSemaphoreCreateBinary( xSemaphore ) \ + { \ + ( xSemaphore ) = xQueueGenericCreate( ( UBaseType_t ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ); \ + if( ( xSemaphore ) != NULL ) \ + { \ + ( void ) xSemaphoreGive( ( xSemaphore ) ); \ + } \ + } +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateBinary( void )
+ * + * Creates a new binary semaphore instance, and returns a handle by which the + * new semaphore can be referenced. + * + * In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a binary semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * Internally, within the FreeRTOS implementation, binary semaphores use a block + * of memory, in which the semaphore structure is stored. If a binary semaphore + * is created using xSemaphoreCreateBinary() then the required memory is + * automatically dynamically allocated inside the xSemaphoreCreateBinary() + * function. (see http://www.freertos.org/a00111.html). If a binary semaphore + * is created using xSemaphoreCreateBinaryStatic() then the application writer + * must provide the memory. xSemaphoreCreateBinaryStatic() therefore allows a + * binary semaphore to be created without using any dynamic memory allocation. + * + * The old vSemaphoreCreateBinary() macro is now deprecated in favour of this + * xSemaphoreCreateBinary() function. Note that binary semaphores created using + * the vSemaphoreCreateBinary() macro are created in a state such that the + * first call to 'take' the semaphore would pass, whereas binary semaphores + * created using xSemaphoreCreateBinary() are created in a state such that the + * the semaphore must first be 'given' before it can be 'taken'. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @return Handle to the created semaphore, or NULL if the memory required to + * hold the semaphore's data structures could not be allocated. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateBinary().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateBinary();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateBinary xSemaphoreCreateBinary + * \ingroup Semaphores + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define xSemaphoreCreateBinary() xQueueGenericCreate( ( UBaseType_t ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ) +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateBinaryStatic( StaticSemaphore_t *pxSemaphoreBuffer )
+ * + * Creates a new binary semaphore instance, and returns a handle by which the + * new semaphore can be referenced. + * + * NOTE: In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a binary semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * Internally, within the FreeRTOS implementation, binary semaphores use a block + * of memory, in which the semaphore structure is stored. If a binary semaphore + * is created using xSemaphoreCreateBinary() then the required memory is + * automatically dynamically allocated inside the xSemaphoreCreateBinary() + * function. (see http://www.freertos.org/a00111.html). If a binary semaphore + * is created using xSemaphoreCreateBinaryStatic() then the application writer + * must provide the memory. xSemaphoreCreateBinaryStatic() therefore allows a + * binary semaphore to be created without using any dynamic memory allocation. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param pxSemaphoreBuffer Must point to a variable of type StaticSemaphore_t, + * which will then be used to hold the semaphore's data structure, removing the + * need for the memory to be allocated dynamically. + * + * @return If the semaphore is created then a handle to the created semaphore is + * returned. If pxSemaphoreBuffer is NULL then NULL is returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+ StaticSemaphore_t xSemaphoreBuffer;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateBinary().
+    // The semaphore's data structures will be placed in the xSemaphoreBuffer
+    // variable, the address of which is passed into the function.  The
+    // function's parameter is not NULL, so the function will not attempt any
+    // dynamic memory allocation, and therefore the function will not return
+    // return NULL.
+    xSemaphore = xSemaphoreCreateBinary( &xSemaphoreBuffer );
+
+    // Rest of task code goes here.
+ }
+ 
+ * \defgroup xSemaphoreCreateBinaryStatic xSemaphoreCreateBinaryStatic + * \ingroup Semaphores + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + #define xSemaphoreCreateBinaryStatic( pxStaticSemaphore ) xQueueGenericCreateStatic( ( UBaseType_t ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, NULL, pxStaticSemaphore, queueQUEUE_TYPE_BINARY_SEMAPHORE ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * semphr. h + *
xSemaphoreTake(
+ *                   SemaphoreHandle_t xSemaphore,
+ *                   TickType_t xBlockTime
+ *               )
+ * + * Macro to obtain a semaphore. The semaphore must have previously been + * created with a call to xSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). + * + * @param xSemaphore A handle to the semaphore being taken - obtained when + * the semaphore was created. + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_PERIOD_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. A block + * time of portMAX_DELAY can be used to block indefinitely (provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). + * + * @return pdTRUE if the semaphore was obtained. pdFALSE + * if xBlockTime expired without the semaphore becoming available. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    xSemaphore = xSemaphoreCreateBinary();
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTake( xSemaphore, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTake xSemaphoreTake + * \ingroup Semaphores + */ +#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueSemaphoreTake( ( xSemaphore ), ( xBlockTime ) ) + +/** + * semphr. h + * xSemaphoreTakeRecursive( + * SemaphoreHandle_t xMutex, + * TickType_t xBlockTime + * ) + * + * Macro to recursively obtain, or 'take', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being obtained. This is the + * handle returned by xSemaphoreCreateRecursiveMutex(); + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_PERIOD_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. If + * the task already owns the semaphore then xSemaphoreTakeRecursive() will + * return immediately no matter what the value of xBlockTime. + * + * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime + * expired without the semaphore becoming available. + * + * Example usage: +
+ SemaphoreHandle_t xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTakeRecursive( xSemaphore, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to
+            // xSemaphoreTakeRecursive() are made on the same mutex.  In real
+            // code these would not be just sequential calls as this would make
+            // no sense.  Instead the calls are likely to be buried inside
+            // a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be
+            // available to another task until it has also been given back
+            // three times.  Again it is unlikely that real code would have
+            // these calls sequentially, but instead buried in a more complex
+            // call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+            xSemaphoreGiveRecursive( xMutex );
+            xSemaphoreGiveRecursive( xMutex );
+
+            // Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive + * \ingroup Semaphores + */ +#if( configUSE_RECURSIVE_MUTEXES == 1 ) + #define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) +#endif + +/** + * semphr. h + *
xSemaphoreGive( SemaphoreHandle_t xSemaphore )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to xSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). + * + * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for + * an alternative which can be used from an ISR. + * + * This macro must also not be used on semaphores created using + * xSemaphoreCreateRecursiveMutex(). + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. + * Semaphores are implemented using queues. An error can occur if there is + * no space on the queue to post a message - indicating that the + * semaphore was not first obtained correctly. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    xSemaphore = vSemaphoreCreateBinary();
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( TickType_t ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGive xSemaphoreGive + * \ingroup Semaphores + */ +#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( QueueHandle_t ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreGiveRecursive( SemaphoreHandle_t xMutex )
+ * + * Macro to recursively release, or 'give', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being released, or 'given'. This is the + * handle returned by xSemaphoreCreateMutex(); + * + * @return pdTRUE if the semaphore was given. + * + * Example usage: +
+ SemaphoreHandle_t xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive + * \ingroup Semaphores + */ +#if( configUSE_RECURSIVE_MUTEXES == 1 ) + #define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) +#endif + +/** + * semphr. h + *
+ xSemaphoreGiveFromISR(
+                          SemaphoreHandle_t xSemaphore,
+                          BaseType_t *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to xSemaphoreCreateBinary() or xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR. + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. + * + * Example usage: +
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static uint8_t ucLocalTickCount = 0;
+ static BaseType_t xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR + * \ingroup Semaphores + */ +#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGiveFromISR( ( QueueHandle_t ) ( xSemaphore ), ( pxHigherPriorityTaskWoken ) ) + +/** + * semphr. h + *
+ xSemaphoreTakeFromISR(
+                          SemaphoreHandle_t xSemaphore,
+                          BaseType_t *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to take a semaphore from an ISR. The semaphore must have + * previously been created with a call to xSemaphoreCreateBinary() or + * xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR, however taking a semaphore from an ISR + * is not a common operation. It is likely to only be useful when taking a + * counting semaphore when an interrupt is obtaining an object from a resource + * pool (when the semaphore count indicates the number of resources available). + * + * @param xSemaphore A handle to the semaphore being taken. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreTakeFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if taking the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreTakeFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully taken, otherwise + * pdFALSE + */ +#define xSemaphoreTakeFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueReceiveFromISR( ( QueueHandle_t ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ) ) + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateMutex( void )
+ * + * Creates a new mutex type semaphore instance, and returns a handle by which + * the new mutex can be referenced. + * + * Internally, within the FreeRTOS implementation, mutex semaphores use a block + * of memory, in which the mutex structure is stored. If a mutex is created + * using xSemaphoreCreateMutex() then the required memory is automatically + * dynamically allocated inside the xSemaphoreCreateMutex() function. (see + * http://www.freertos.org/a00111.html). If a mutex is created using + * xSemaphoreCreateMutexStatic() then the application writer must provided the + * memory. xSemaphoreCreateMutexStatic() therefore allows a mutex to be created + * without using any dynamic memory allocation. + * + * Mutexes created using this function can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros must not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See xSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return If the mutex was successfully created then a handle to the created + * semaphore is returned. If there was not enough heap to allocate the mutex + * data structures then NULL is returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateMutex xSemaphoreCreateMutex + * \ingroup Semaphores + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define xSemaphoreCreateMutex() xQueueCreateMutex( queueQUEUE_TYPE_MUTEX ) +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateMutexStatic( StaticSemaphore_t *pxMutexBuffer )
+ * + * Creates a new mutex type semaphore instance, and returns a handle by which + * the new mutex can be referenced. + * + * Internally, within the FreeRTOS implementation, mutex semaphores use a block + * of memory, in which the mutex structure is stored. If a mutex is created + * using xSemaphoreCreateMutex() then the required memory is automatically + * dynamically allocated inside the xSemaphoreCreateMutex() function. (see + * http://www.freertos.org/a00111.html). If a mutex is created using + * xSemaphoreCreateMutexStatic() then the application writer must provided the + * memory. xSemaphoreCreateMutexStatic() therefore allows a mutex to be created + * without using any dynamic memory allocation. + * + * Mutexes created using this function can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros must not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See xSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @param pxMutexBuffer Must point to a variable of type StaticSemaphore_t, + * which will be used to hold the mutex's data structure, removing the need for + * the memory to be allocated dynamically. + * + * @return If the mutex was successfully created then a handle to the created + * mutex is returned. If pxMutexBuffer was NULL then NULL is returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+ StaticSemaphore_t xMutexBuffer;
+
+ void vATask( void * pvParameters )
+ {
+    // A mutex cannot be used before it has been created.  xMutexBuffer is
+    // into xSemaphoreCreateMutexStatic() so no dynamic memory allocation is
+    // attempted.
+    xSemaphore = xSemaphoreCreateMutexStatic( &xMutexBuffer );
+
+    // As no dynamic memory allocation was performed, xSemaphore cannot be NULL,
+    // so there is no need to check it.
+ }
+ 
+ * \defgroup xSemaphoreCreateMutexStatic xSemaphoreCreateMutexStatic + * \ingroup Semaphores + */ + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + #define xSemaphoreCreateMutexStatic( pxMutexBuffer ) xQueueCreateMutexStatic( queueQUEUE_TYPE_MUTEX, ( pxMutexBuffer ) ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateRecursiveMutex( void )
+ * + * Creates a new recursive mutex type semaphore instance, and returns a handle + * by which the new recursive mutex can be referenced. + * + * Internally, within the FreeRTOS implementation, recursive mutexs use a block + * of memory, in which the mutex structure is stored. If a recursive mutex is + * created using xSemaphoreCreateRecursiveMutex() then the required memory is + * automatically dynamically allocated inside the + * xSemaphoreCreateRecursiveMutex() function. (see + * http://www.freertos.org/a00111.html). If a recursive mutex is created using + * xSemaphoreCreateRecursiveMutexStatic() then the application writer must + * provide the memory that will get used by the mutex. + * xSemaphoreCreateRecursiveMutexStatic() therefore allows a recursive mutex to + * be created without using any dynamic memory allocation. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros must not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See xSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * SemaphoreHandle_t. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateRecursiveMutex xSemaphoreCreateRecursiveMutex + * \ingroup Semaphores + */ +#if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configUSE_RECURSIVE_MUTEXES == 1 ) ) + #define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX ) +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateRecursiveMutexStatic( StaticSemaphore_t *pxMutexBuffer )
+ * + * Creates a new recursive mutex type semaphore instance, and returns a handle + * by which the new recursive mutex can be referenced. + * + * Internally, within the FreeRTOS implementation, recursive mutexs use a block + * of memory, in which the mutex structure is stored. If a recursive mutex is + * created using xSemaphoreCreateRecursiveMutex() then the required memory is + * automatically dynamically allocated inside the + * xSemaphoreCreateRecursiveMutex() function. (see + * http://www.freertos.org/a00111.html). If a recursive mutex is created using + * xSemaphoreCreateRecursiveMutexStatic() then the application writer must + * provide the memory that will get used by the mutex. + * xSemaphoreCreateRecursiveMutexStatic() therefore allows a recursive mutex to + * be created without using any dynamic memory allocation. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros must not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See xSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @param pxMutexBuffer Must point to a variable of type StaticSemaphore_t, + * which will then be used to hold the recursive mutex's data structure, + * removing the need for the memory to be allocated dynamically. + * + * @return If the recursive mutex was successfully created then a handle to the + * created recursive mutex is returned. If pxMutexBuffer was NULL then NULL is + * returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+ StaticSemaphore_t xMutexBuffer;
+
+ void vATask( void * pvParameters )
+ {
+    // A recursive semaphore cannot be used before it is created.  Here a
+    // recursive mutex is created using xSemaphoreCreateRecursiveMutexStatic().
+    // The address of xMutexBuffer is passed into the function, and will hold
+    // the mutexes data structures - so no dynamic memory allocation will be
+    // attempted.
+    xSemaphore = xSemaphoreCreateRecursiveMutexStatic( &xMutexBuffer );
+
+    // As no dynamic memory allocation was performed, xSemaphore cannot be NULL,
+    // so there is no need to check it.
+ }
+ 
+ * \defgroup xSemaphoreCreateRecursiveMutexStatic xSemaphoreCreateRecursiveMutexStatic + * \ingroup Semaphores + */ +#if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configUSE_RECURSIVE_MUTEXES == 1 ) ) + #define xSemaphoreCreateRecursiveMutexStatic( pxStaticSemaphore ) xQueueCreateMutexStatic( queueQUEUE_TYPE_RECURSIVE_MUTEX, pxStaticSemaphore ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateCounting( UBaseType_t uxMaxCount, UBaseType_t uxInitialCount )
+ * + * Creates a new counting semaphore instance, and returns a handle by which the + * new counting semaphore can be referenced. + * + * In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a counting semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * Internally, within the FreeRTOS implementation, counting semaphores use a + * block of memory, in which the counting semaphore structure is stored. If a + * counting semaphore is created using xSemaphoreCreateCounting() then the + * required memory is automatically dynamically allocated inside the + * xSemaphoreCreateCounting() function. (see + * http://www.freertos.org/a00111.html). If a counting semaphore is created + * using xSemaphoreCreateCountingStatic() then the application writer can + * instead optionally provide the memory that will get used by the counting + * semaphore. xSemaphoreCreateCountingStatic() therefore allows a counting + * semaphore to be created without using any dynamic memory allocation. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @return Handle to the created semaphore. Null if the semaphore could not be + * created. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ SemaphoreHandle_t xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting + * \ingroup Semaphores + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateCountingStatic( UBaseType_t uxMaxCount, UBaseType_t uxInitialCount, StaticSemaphore_t *pxSemaphoreBuffer )
+ * + * Creates a new counting semaphore instance, and returns a handle by which the + * new counting semaphore can be referenced. + * + * In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a counting semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * Internally, within the FreeRTOS implementation, counting semaphores use a + * block of memory, in which the counting semaphore structure is stored. If a + * counting semaphore is created using xSemaphoreCreateCounting() then the + * required memory is automatically dynamically allocated inside the + * xSemaphoreCreateCounting() function. (see + * http://www.freertos.org/a00111.html). If a counting semaphore is created + * using xSemaphoreCreateCountingStatic() then the application writer must + * provide the memory. xSemaphoreCreateCountingStatic() therefore allows a + * counting semaphore to be created without using any dynamic memory allocation. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @param pxSemaphoreBuffer Must point to a variable of type StaticSemaphore_t, + * which will then be used to hold the semaphore's data structure, removing the + * need for the memory to be allocated dynamically. + * + * @return If the counting semaphore was successfully created then a handle to + * the created counting semaphore is returned. If pxSemaphoreBuffer was NULL + * then NULL is returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+ StaticSemaphore_t xSemaphoreBuffer;
+
+ void vATask( void * pvParameters )
+ {
+ SemaphoreHandle_t xSemaphore = NULL;
+
+    // Counting semaphore cannot be used before they have been created.  Create
+    // a counting semaphore using xSemaphoreCreateCountingStatic().  The max
+    // value to which the semaphore can count is 10, and the initial value
+    // assigned to the count will be 0.  The address of xSemaphoreBuffer is
+    // passed in and will be used to hold the semaphore structure, so no dynamic
+    // memory allocation will be used.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0, &xSemaphoreBuffer );
+
+    // No memory allocation was attempted so xSemaphore cannot be NULL, so there
+    // is no need to check its value.
+ }
+ 
+ * \defgroup xSemaphoreCreateCountingStatic xSemaphoreCreateCountingStatic + * \ingroup Semaphores + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + #define xSemaphoreCreateCountingStatic( uxMaxCount, uxInitialCount, pxSemaphoreBuffer ) xQueueCreateCountingSemaphoreStatic( ( uxMaxCount ), ( uxInitialCount ), ( pxSemaphoreBuffer ) ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * semphr. h + *
void vSemaphoreDelete( SemaphoreHandle_t xSemaphore );
+ * + * Delete a semaphore. This function must be used with care. For example, + * do not delete a mutex type semaphore if the mutex is held by a task. + * + * @param xSemaphore A handle to the semaphore to be deleted. + * + * \defgroup vSemaphoreDelete vSemaphoreDelete + * \ingroup Semaphores + */ +#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( QueueHandle_t ) ( xSemaphore ) ) + +/** + * semphr.h + *
TaskHandle_t xSemaphoreGetMutexHolder( SemaphoreHandle_t xMutex );
+ * + * If xMutex is indeed a mutex type semaphore, return the current mutex holder. + * If xMutex is not a mutex type semaphore, or the mutex is available (not held + * by a task), return NULL. + * + * Note: This is a good way of determining if the calling task is the mutex + * holder, but not a good way of determining the identity of the mutex holder as + * the holder may change between the function exiting and the returned value + * being tested. + */ +#define xSemaphoreGetMutexHolder( xSemaphore ) xQueueGetMutexHolder( ( xSemaphore ) ) + +/** + * semphr.h + *
TaskHandle_t xSemaphoreGetMutexHolderFromISR( SemaphoreHandle_t xMutex );
+ * + * If xMutex is indeed a mutex type semaphore, return the current mutex holder. + * If xMutex is not a mutex type semaphore, or the mutex is available (not held + * by a task), return NULL. + * + */ +#define xSemaphoreGetMutexHolderFromISR( xSemaphore ) xQueueGetMutexHolderFromISR( ( xSemaphore ) ) + +/** + * semphr.h + *
UBaseType_t uxSemaphoreGetCount( SemaphoreHandle_t xSemaphore );
+ * + * If the semaphore is a counting semaphore then uxSemaphoreGetCount() returns + * its current count value. If the semaphore is a binary semaphore then + * uxSemaphoreGetCount() returns 1 if the semaphore is available, and 0 if the + * semaphore is not available. + * + */ +#define uxSemaphoreGetCount( xSemaphore ) uxQueueMessagesWaiting( ( QueueHandle_t ) ( xSemaphore ) ) + +#endif /* SEMAPHORE_H */ + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stack_macros.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stack_macros.h new file mode 100644 index 0000000..d8b5467 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stack_macros.h @@ -0,0 +1,129 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 STACK_MACROS_H +#define STACK_MACROS_H + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + const uint32_t * const pulStack = ( uint32_t * ) pxCurrentTCB->pxStack; \ + const uint32_t ulCheckValue = ( uint32_t ) 0xa5a5a5a5; \ + \ + if( ( pulStack[ 0 ] != ulCheckValue ) || \ + ( pulStack[ 1 ] != ulCheckValue ) || \ + ( pulStack[ 2 ] != ulCheckValue ) || \ + ( pulStack[ 3 ] != ulCheckValue ) ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + int8_t *pcEndOfStack = ( int8_t * ) pxCurrentTCB->pxEndOfStack; \ + static const uint8_t ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +/* Remove stack overflow macro if not being used. */ +#ifndef taskCHECK_FOR_STACK_OVERFLOW + #define taskCHECK_FOR_STACK_OVERFLOW() +#endif + + + +#endif /* STACK_MACROS_H */ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stdint.readme b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stdint.readme new file mode 100644 index 0000000..4414c29 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stdint.readme @@ -0,0 +1,27 @@ + +#ifndef FREERTOS_STDINT +#define FREERTOS_STDINT + +/******************************************************************************* + * THIS IS NOT A FULL stdint.h IMPLEMENTATION - It only contains the definitions + * necessary to build the FreeRTOS code. It is provided to allow FreeRTOS to be + * built using compilers that do not provide their own stdint.h definition. + * + * To use this file: + * + * 1) Copy this file into the directory that contains your FreeRTOSConfig.h + * header file, as that directory will already be in the compilers include + * path. + * + * 2) Rename the copied file stdint.h. + * + */ + +typedef signed char int8_t; +typedef unsigned char uint8_t; +typedef short int16_t; +typedef unsigned short uint16_t; +typedef long int32_t; +typedef unsigned long uint32_t; + +#endif /* FREERTOS_STDINT */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stream_buffer.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stream_buffer.h new file mode 100644 index 0000000..606e84d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/stream_buffer.h @@ -0,0 +1,859 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* + * Stream buffers are used to send a continuous stream of data from one task or + * interrupt to another. Their implementation is light weight, making them + * particularly suited for interrupt to task and core to core communication + * scenarios. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xStreamBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xStreamBufferReceive()) inside a critical section section and set the + * receive block time to 0. + * + */ + +#ifndef STREAM_BUFFER_H +#define STREAM_BUFFER_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include stream_buffer.h" +#endif + +#if defined( __cplusplus ) +extern "C" { +#endif + +/** + * Type by which stream buffers are referenced. For example, a call to + * xStreamBufferCreate() returns an StreamBufferHandle_t variable that can + * then be used as a parameter to xStreamBufferSend(), xStreamBufferReceive(), + * etc. + */ +struct StreamBufferDef_t; +typedef struct StreamBufferDef_t * StreamBufferHandle_t; + + +/** + * message_buffer.h + * +
+StreamBufferHandle_t xStreamBufferCreate( size_t xBufferSizeBytes, size_t xTriggerLevelBytes );
+
+ * + * Creates a new stream buffer using dynamically allocated memory. See + * xStreamBufferCreateStatic() for a version that uses statically allocated + * memory (memory that is allocated at compile time). + * + * configSUPPORT_DYNAMIC_ALLOCATION must be set to 1 or left undefined in + * FreeRTOSConfig.h for xStreamBufferCreate() to be available. + * + * @param xBufferSizeBytes The total number of bytes the stream buffer will be + * able to hold at any one time. + * + * @param xTriggerLevelBytes The number of bytes that must be in the stream + * buffer before a task that is blocked on the stream buffer to wait for data is + * moved out of the blocked state. For example, if a task is blocked on a read + * of an empty stream buffer that has a trigger level of 1 then the task will be + * unblocked when a single byte is written to the buffer or the task's block + * time expires. As another example, if a task is blocked on a read of an empty + * stream buffer that has a trigger level of 10 then the task will not be + * unblocked until the stream buffer contains at least 10 bytes or the task's + * block time expires. If a reading task's block time expires before the + * trigger level is reached then the task will still receive however many bytes + * are actually available. Setting a trigger level of 0 will result in a + * trigger level of 1 being used. It is not valid to specify a trigger level + * that is greater than the buffer size. + * + * @return If NULL is returned, then the stream buffer cannot be created + * because there is insufficient heap memory available for FreeRTOS to allocate + * the stream buffer data structures and storage area. A non-NULL value being + * returned indicates that the stream buffer has been created successfully - + * the returned value should be stored as the handle to the created stream + * buffer. + * + * Example use: +
+
+void vAFunction( void )
+{
+StreamBufferHandle_t xStreamBuffer;
+const size_t xStreamBufferSizeBytes = 100, xTriggerLevel = 10;
+
+    // Create a stream buffer that can hold 100 bytes.  The memory used to hold
+    // both the stream buffer structure and the data in the stream buffer is
+    // allocated dynamically.
+    xStreamBuffer = xStreamBufferCreate( xStreamBufferSizeBytes, xTriggerLevel );
+
+    if( xStreamBuffer == NULL )
+    {
+        // There was not enough heap memory space available to create the
+        // stream buffer.
+    }
+    else
+    {
+        // The stream buffer was created successfully and can now be used.
+    }
+}
+
+ * \defgroup xStreamBufferCreate xStreamBufferCreate + * \ingroup StreamBufferManagement + */ +#define xStreamBufferCreate( xBufferSizeBytes, xTriggerLevelBytes ) xStreamBufferGenericCreate( xBufferSizeBytes, xTriggerLevelBytes, pdFALSE ) + +/** + * stream_buffer.h + * +
+StreamBufferHandle_t xStreamBufferCreateStatic( size_t xBufferSizeBytes,
+                                                size_t xTriggerLevelBytes,
+                                                uint8_t *pucStreamBufferStorageArea,
+                                                StaticStreamBuffer_t *pxStaticStreamBuffer );
+
+ * Creates a new stream buffer using statically allocated memory. See + * xStreamBufferCreate() for a version that uses dynamically allocated memory. + * + * configSUPPORT_STATIC_ALLOCATION must be set to 1 in FreeRTOSConfig.h for + * xStreamBufferCreateStatic() to be available. + * + * @param xBufferSizeBytes The size, in bytes, of the buffer pointed to by the + * pucStreamBufferStorageArea parameter. + * + * @param xTriggerLevelBytes The number of bytes that must be in the stream + * buffer before a task that is blocked on the stream buffer to wait for data is + * moved out of the blocked state. For example, if a task is blocked on a read + * of an empty stream buffer that has a trigger level of 1 then the task will be + * unblocked when a single byte is written to the buffer or the task's block + * time expires. As another example, if a task is blocked on a read of an empty + * stream buffer that has a trigger level of 10 then the task will not be + * unblocked until the stream buffer contains at least 10 bytes or the task's + * block time expires. If a reading task's block time expires before the + * trigger level is reached then the task will still receive however many bytes + * are actually available. Setting a trigger level of 0 will result in a + * trigger level of 1 being used. It is not valid to specify a trigger level + * that is greater than the buffer size. + * + * @param pucStreamBufferStorageArea Must point to a uint8_t array that is at + * least xBufferSizeBytes + 1 big. This is the array to which streams are + * copied when they are written to the stream buffer. + * + * @param pxStaticStreamBuffer Must point to a variable of type + * StaticStreamBuffer_t, which will be used to hold the stream buffer's data + * structure. + * + * @return If the stream buffer is created successfully then a handle to the + * created stream buffer is returned. If either pucStreamBufferStorageArea or + * pxStaticstreamBuffer are NULL then NULL is returned. + * + * Example use: +
+
+// Used to dimension the array used to hold the streams.  The available space
+// will actually be one less than this, so 999.
+#define STORAGE_SIZE_BYTES 1000
+
+// Defines the memory that will actually hold the streams within the stream
+// buffer.
+static uint8_t ucStorageBuffer[ STORAGE_SIZE_BYTES ];
+
+// The variable used to hold the stream buffer structure.
+StaticStreamBuffer_t xStreamBufferStruct;
+
+void MyFunction( void )
+{
+StreamBufferHandle_t xStreamBuffer;
+const size_t xTriggerLevel = 1;
+
+    xStreamBuffer = xStreamBufferCreateStatic( sizeof( ucBufferStorage ),
+                                               xTriggerLevel,
+                                               ucBufferStorage,
+                                               &xStreamBufferStruct );
+
+    // As neither the pucStreamBufferStorageArea or pxStaticStreamBuffer
+    // parameters were NULL, xStreamBuffer will not be NULL, and can be used to
+    // reference the created stream buffer in other stream buffer API calls.
+
+    // Other code that uses the stream buffer can go here.
+}
+
+
+ * \defgroup xStreamBufferCreateStatic xStreamBufferCreateStatic + * \ingroup StreamBufferManagement + */ +#define xStreamBufferCreateStatic( xBufferSizeBytes, xTriggerLevelBytes, pucStreamBufferStorageArea, pxStaticStreamBuffer ) xStreamBufferGenericCreateStatic( xBufferSizeBytes, xTriggerLevelBytes, pdFALSE, pucStreamBufferStorageArea, pxStaticStreamBuffer ) + +/** + * stream_buffer.h + * +
+size_t xStreamBufferSend( StreamBufferHandle_t xStreamBuffer,
+                          const void *pvTxData,
+                          size_t xDataLengthBytes,
+                          TickType_t xTicksToWait );
+
+ * + * Sends bytes to a stream buffer. The bytes are copied into the stream buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xStreamBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xStreamBufferReceive()) inside a critical section and set the receive + * block time to 0. + * + * Use xStreamBufferSend() to write to a stream buffer from a task. Use + * xStreamBufferSendFromISR() to write to a stream buffer from an interrupt + * service routine (ISR). + * + * @param xStreamBuffer The handle of the stream buffer to which a stream is + * being sent. + * + * @param pvTxData A pointer to the buffer that holds the bytes to be copied + * into the stream buffer. + * + * @param xDataLengthBytes The maximum number of bytes to copy from pvTxData + * into the stream buffer. + * + * @param xTicksToWait The maximum amount of time the task should remain in the + * Blocked state to wait for enough space to become available in the stream + * buffer, should the stream buffer contain too little space to hold the + * another xDataLengthBytes bytes. The block time is specified in tick periods, + * so the absolute time it represents is dependent on the tick frequency. The + * macro pdMS_TO_TICKS() can be used to convert a time specified in milliseconds + * into a time specified in ticks. Setting xTicksToWait to portMAX_DELAY will + * cause the task to wait indefinitely (without timing out), provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h. If a task times out + * before it can write all xDataLengthBytes into the buffer it will still write + * as many bytes as possible. A task does not use any CPU time when it is in + * the blocked state. + * + * @return The number of bytes written to the stream buffer. If a task times + * out before it can write all xDataLengthBytes into the buffer it will still + * write as many bytes as possible. + * + * Example use: +
+void vAFunction( StreamBufferHandle_t xStreamBuffer )
+{
+size_t xBytesSent;
+uint8_t ucArrayToSend[] = { 0, 1, 2, 3 };
+char *pcStringToSend = "String to send";
+const TickType_t x100ms = pdMS_TO_TICKS( 100 );
+
+    // Send an array to the stream buffer, blocking for a maximum of 100ms to
+    // wait for enough space to be available in the stream buffer.
+    xBytesSent = xStreamBufferSend( xStreamBuffer, ( void * ) ucArrayToSend, sizeof( ucArrayToSend ), x100ms );
+
+    if( xBytesSent != sizeof( ucArrayToSend ) )
+    {
+        // The call to xStreamBufferSend() times out before there was enough
+        // space in the buffer for the data to be written, but it did
+        // successfully write xBytesSent bytes.
+    }
+
+    // Send the string to the stream buffer.  Return immediately if there is not
+    // enough space in the buffer.
+    xBytesSent = xStreamBufferSend( xStreamBuffer, ( void * ) pcStringToSend, strlen( pcStringToSend ), 0 );
+
+    if( xBytesSent != strlen( pcStringToSend ) )
+    {
+        // The entire string could not be added to the stream buffer because
+        // there was not enough free space in the buffer, but xBytesSent bytes
+        // were sent.  Could try again to send the remaining bytes.
+    }
+}
+
+ * \defgroup xStreamBufferSend xStreamBufferSend + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferSend( StreamBufferHandle_t xStreamBuffer, + const void *pvTxData, + size_t xDataLengthBytes, + TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferSendFromISR( StreamBufferHandle_t xStreamBuffer,
+                                 const void *pvTxData,
+                                 size_t xDataLengthBytes,
+                                 BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * Interrupt safe version of the API function that sends a stream of bytes to + * the stream buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xStreamBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xStreamBufferReceive()) inside a critical section and set the receive + * block time to 0. + * + * Use xStreamBufferSend() to write to a stream buffer from a task. Use + * xStreamBufferSendFromISR() to write to a stream buffer from an interrupt + * service routine (ISR). + * + * @param xStreamBuffer The handle of the stream buffer to which a stream is + * being sent. + * + * @param pvTxData A pointer to the data that is to be copied into the stream + * buffer. + * + * @param xDataLengthBytes The maximum number of bytes to copy from pvTxData + * into the stream buffer. + * + * @param pxHigherPriorityTaskWoken It is possible that a stream buffer will + * have a task blocked on it waiting for data. Calling + * xStreamBufferSendFromISR() can make data available, and so cause a task that + * was waiting for data to leave the Blocked state. If calling + * xStreamBufferSendFromISR() causes a task to leave the Blocked state, and the + * unblocked task has a priority higher than the currently executing task (the + * task that was interrupted), then, internally, xStreamBufferSendFromISR() + * will set *pxHigherPriorityTaskWoken to pdTRUE. If + * xStreamBufferSendFromISR() sets this value to pdTRUE, then normally a + * context switch should be performed before the interrupt is exited. This will + * ensure that the interrupt returns directly to the highest priority Ready + * state task. *pxHigherPriorityTaskWoken should be set to pdFALSE before it + * is passed into the function. See the example code below for an example. + * + * @return The number of bytes actually written to the stream buffer, which will + * be less than xDataLengthBytes if the stream buffer didn't have enough free + * space for all the bytes to be written. + * + * Example use: +
+// A stream buffer that has already been created.
+StreamBufferHandle_t xStreamBuffer;
+
+void vAnInterruptServiceRoutine( void )
+{
+size_t xBytesSent;
+char *pcStringToSend = "String to send";
+BaseType_t xHigherPriorityTaskWoken = pdFALSE; // Initialised to pdFALSE.
+
+    // Attempt to send the string to the stream buffer.
+    xBytesSent = xStreamBufferSendFromISR( xStreamBuffer,
+                                           ( void * ) pcStringToSend,
+                                           strlen( pcStringToSend ),
+                                           &xHigherPriorityTaskWoken );
+
+    if( xBytesSent != strlen( pcStringToSend ) )
+    {
+        // There was not enough free space in the stream buffer for the entire
+        // string to be written, ut xBytesSent bytes were written.
+    }
+
+    // If xHigherPriorityTaskWoken was set to pdTRUE inside
+    // xStreamBufferSendFromISR() then a task that has a priority above the
+    // priority of the currently executing task was unblocked and a context
+    // switch should be performed to ensure the ISR returns to the unblocked
+    // task.  In most FreeRTOS ports this is done by simply passing
+    // xHigherPriorityTaskWoken into taskYIELD_FROM_ISR(), which will test the
+    // variables value, and perform the context switch if necessary.  Check the
+    // documentation for the port in use for port specific instructions.
+    taskYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+}
+
+ * \defgroup xStreamBufferSendFromISR xStreamBufferSendFromISR + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferSendFromISR( StreamBufferHandle_t xStreamBuffer, + const void *pvTxData, + size_t xDataLengthBytes, + BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer,
+                             void *pvRxData,
+                             size_t xBufferLengthBytes,
+                             TickType_t xTicksToWait );
+
+ * + * Receives bytes from a stream buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xStreamBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xStreamBufferReceive()) inside a critical section and set the receive + * block time to 0. + * + * Use xStreamBufferReceive() to read from a stream buffer from a task. Use + * xStreamBufferReceiveFromISR() to read from a stream buffer from an + * interrupt service routine (ISR). + * + * @param xStreamBuffer The handle of the stream buffer from which bytes are to + * be received. + * + * @param pvRxData A pointer to the buffer into which the received bytes will be + * copied. + * + * @param xBufferLengthBytes The length of the buffer pointed to by the + * pvRxData parameter. This sets the maximum number of bytes to receive in one + * call. xStreamBufferReceive will return as many bytes as possible up to a + * maximum set by xBufferLengthBytes. + * + * @param xTicksToWait The maximum amount of time the task should remain in the + * Blocked state to wait for data to become available if the stream buffer is + * empty. xStreamBufferReceive() will return immediately if xTicksToWait is + * zero. The block time is specified in tick periods, so the absolute time it + * represents is dependent on the tick frequency. The macro pdMS_TO_TICKS() can + * be used to convert a time specified in milliseconds into a time specified in + * ticks. Setting xTicksToWait to portMAX_DELAY will cause the task to wait + * indefinitely (without timing out), provided INCLUDE_vTaskSuspend is set to 1 + * in FreeRTOSConfig.h. A task does not use any CPU time when it is in the + * Blocked state. + * + * @return The number of bytes actually read from the stream buffer, which will + * be less than xBufferLengthBytes if the call to xStreamBufferReceive() timed + * out before xBufferLengthBytes were available. + * + * Example use: +
+void vAFunction( StreamBuffer_t xStreamBuffer )
+{
+uint8_t ucRxData[ 20 ];
+size_t xReceivedBytes;
+const TickType_t xBlockTime = pdMS_TO_TICKS( 20 );
+
+    // Receive up to another sizeof( ucRxData ) bytes from the stream buffer.
+    // Wait in the Blocked state (so not using any CPU processing time) for a
+    // maximum of 100ms for the full sizeof( ucRxData ) number of bytes to be
+    // available.
+    xReceivedBytes = xStreamBufferReceive( xStreamBuffer,
+                                           ( void * ) ucRxData,
+                                           sizeof( ucRxData ),
+                                           xBlockTime );
+
+    if( xReceivedBytes > 0 )
+    {
+        // A ucRxData contains another xRecievedBytes bytes of data, which can
+        // be processed here....
+    }
+}
+
+ * \defgroup xStreamBufferReceive xStreamBufferReceive + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferReceiveFromISR( StreamBufferHandle_t xStreamBuffer,
+                                    void *pvRxData,
+                                    size_t xBufferLengthBytes,
+                                    BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * An interrupt safe version of the API function that receives bytes from a + * stream buffer. + * + * Use xStreamBufferReceive() to read bytes from a stream buffer from a task. + * Use xStreamBufferReceiveFromISR() to read bytes from a stream buffer from an + * interrupt service routine (ISR). + * + * @param xStreamBuffer The handle of the stream buffer from which a stream + * is being received. + * + * @param pvRxData A pointer to the buffer into which the received bytes are + * copied. + * + * @param xBufferLengthBytes The length of the buffer pointed to by the + * pvRxData parameter. This sets the maximum number of bytes to receive in one + * call. xStreamBufferReceive will return as many bytes as possible up to a + * maximum set by xBufferLengthBytes. + * + * @param pxHigherPriorityTaskWoken It is possible that a stream buffer will + * have a task blocked on it waiting for space to become available. Calling + * xStreamBufferReceiveFromISR() can make space available, and so cause a task + * that is waiting for space to leave the Blocked state. If calling + * xStreamBufferReceiveFromISR() causes a task to leave the Blocked state, and + * the unblocked task has a priority higher than the currently executing task + * (the task that was interrupted), then, internally, + * xStreamBufferReceiveFromISR() will set *pxHigherPriorityTaskWoken to pdTRUE. + * If xStreamBufferReceiveFromISR() sets this value to pdTRUE, then normally a + * context switch should be performed before the interrupt is exited. That will + * ensure the interrupt returns directly to the highest priority Ready state + * task. *pxHigherPriorityTaskWoken should be set to pdFALSE before it is + * passed into the function. See the code example below for an example. + * + * @return The number of bytes read from the stream buffer, if any. + * + * Example use: +
+// A stream buffer that has already been created.
+StreamBuffer_t xStreamBuffer;
+
+void vAnInterruptServiceRoutine( void )
+{
+uint8_t ucRxData[ 20 ];
+size_t xReceivedBytes;
+BaseType_t xHigherPriorityTaskWoken = pdFALSE;  // Initialised to pdFALSE.
+
+    // Receive the next stream from the stream buffer.
+    xReceivedBytes = xStreamBufferReceiveFromISR( xStreamBuffer,
+                                                  ( void * ) ucRxData,
+                                                  sizeof( ucRxData ),
+                                                  &xHigherPriorityTaskWoken );
+
+    if( xReceivedBytes > 0 )
+    {
+        // ucRxData contains xReceivedBytes read from the stream buffer.
+        // Process the stream here....
+    }
+
+    // If xHigherPriorityTaskWoken was set to pdTRUE inside
+    // xStreamBufferReceiveFromISR() then a task that has a priority above the
+    // priority of the currently executing task was unblocked and a context
+    // switch should be performed to ensure the ISR returns to the unblocked
+    // task.  In most FreeRTOS ports this is done by simply passing
+    // xHigherPriorityTaskWoken into taskYIELD_FROM_ISR(), which will test the
+    // variables value, and perform the context switch if necessary.  Check the
+    // documentation for the port in use for port specific instructions.
+    taskYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+}
+
+ * \defgroup xStreamBufferReceiveFromISR xStreamBufferReceiveFromISR + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferReceiveFromISR( StreamBufferHandle_t xStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+void vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Deletes a stream buffer that was previously created using a call to + * xStreamBufferCreate() or xStreamBufferCreateStatic(). If the stream + * buffer was created using dynamic memory (that is, by xStreamBufferCreate()), + * then the allocated memory is freed. + * + * A stream buffer handle must not be used after the stream buffer has been + * deleted. + * + * @param xStreamBuffer The handle of the stream buffer to be deleted. + * + * \defgroup vStreamBufferDelete vStreamBufferDelete + * \ingroup StreamBufferManagement + */ +void vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Queries a stream buffer to see if it is full. A stream buffer is full if it + * does not have any free space, and therefore cannot accept any more data. + * + * @param xStreamBuffer The handle of the stream buffer being queried. + * + * @return If the stream buffer is full then pdTRUE is returned. Otherwise + * pdFALSE is returned. + * + * \defgroup xStreamBufferIsFull xStreamBufferIsFull + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Queries a stream buffer to see if it is empty. A stream buffer is empty if + * it does not contain any data. + * + * @param xStreamBuffer The handle of the stream buffer being queried. + * + * @return If the stream buffer is empty then pdTRUE is returned. Otherwise + * pdFALSE is returned. + * + * \defgroup xStreamBufferIsEmpty xStreamBufferIsEmpty + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferReset( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Resets a stream buffer to its initial, empty, state. Any data that was in + * the stream buffer is discarded. A stream buffer can only be reset if there + * are no tasks blocked waiting to either send to or receive from the stream + * buffer. + * + * @param xStreamBuffer The handle of the stream buffer being reset. + * + * @return If the stream buffer is reset then pdPASS is returned. If there was + * a task blocked waiting to send to or read from the stream buffer then the + * stream buffer is not reset and pdFAIL is returned. + * + * \defgroup xStreamBufferReset xStreamBufferReset + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferReset( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Queries a stream buffer to see how much free space it contains, which is + * equal to the amount of data that can be sent to the stream buffer before it + * is full. + * + * @param xStreamBuffer The handle of the stream buffer being queried. + * + * @return The number of bytes that can be written to the stream buffer before + * the stream buffer would be full. + * + * \defgroup xStreamBufferSpacesAvailable xStreamBufferSpacesAvailable + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Queries a stream buffer to see how much data it contains, which is equal to + * the number of bytes that can be read from the stream buffer before the stream + * buffer would be empty. + * + * @param xStreamBuffer The handle of the stream buffer being queried. + * + * @return The number of bytes that can be read from the stream buffer before + * the stream buffer would be empty. + * + * \defgroup xStreamBufferBytesAvailable xStreamBufferBytesAvailable + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel );
+
+ * + * A stream buffer's trigger level is the number of bytes that must be in the + * stream buffer before a task that is blocked on the stream buffer to + * wait for data is moved out of the blocked state. For example, if a task is + * blocked on a read of an empty stream buffer that has a trigger level of 1 + * then the task will be unblocked when a single byte is written to the buffer + * or the task's block time expires. As another example, if a task is blocked + * on a read of an empty stream buffer that has a trigger level of 10 then the + * task will not be unblocked until the stream buffer contains at least 10 bytes + * or the task's block time expires. If a reading task's block time expires + * before the trigger level is reached then the task will still receive however + * many bytes are actually available. Setting a trigger level of 0 will result + * in a trigger level of 1 being used. It is not valid to specify a trigger + * level that is greater than the buffer size. + * + * A trigger level is set when the stream buffer is created, and can be modified + * using xStreamBufferSetTriggerLevel(). + * + * @param xStreamBuffer The handle of the stream buffer being updated. + * + * @param xTriggerLevel The new trigger level for the stream buffer. + * + * @return If xTriggerLevel was less than or equal to the stream buffer's length + * then the trigger level will be updated and pdTRUE is returned. Otherwise + * pdFALSE is returned. + * + * \defgroup xStreamBufferSetTriggerLevel xStreamBufferSetTriggerLevel + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferSendCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * For advanced users only. + * + * The sbSEND_COMPLETED() macro is called from within the FreeRTOS APIs when + * data is sent to a message buffer or stream buffer. If there was a task that + * was blocked on the message or stream buffer waiting for data to arrive then + * the sbSEND_COMPLETED() macro sends a notification to the task to remove it + * from the Blocked state. xStreamBufferSendCompletedFromISR() does the same + * thing. It is provided to enable application writers to implement their own + * version of sbSEND_COMPLETED(), and MUST NOT BE USED AT ANY OTHER TIME. + * + * See the example implemented in FreeRTOS/Demo/Minimal/MessageBufferAMP.c for + * additional information. + * + * @param xStreamBuffer The handle of the stream buffer to which data was + * written. + * + * @param pxHigherPriorityTaskWoken *pxHigherPriorityTaskWoken should be + * initialised to pdFALSE before it is passed into + * xStreamBufferSendCompletedFromISR(). If calling + * xStreamBufferSendCompletedFromISR() removes a task from the Blocked state, + * and the task has a priority above the priority of the currently running task, + * then *pxHigherPriorityTaskWoken will get set to pdTRUE indicating that a + * context switch should be performed before exiting the ISR. + * + * @return If a task was removed from the Blocked state then pdTRUE is returned. + * Otherwise pdFALSE is returned. + * + * \defgroup xStreamBufferSendCompletedFromISR xStreamBufferSendCompletedFromISR + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferSendCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferReceiveCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * For advanced users only. + * + * The sbRECEIVE_COMPLETED() macro is called from within the FreeRTOS APIs when + * data is read out of a message buffer or stream buffer. If there was a task + * that was blocked on the message or stream buffer waiting for data to arrive + * then the sbRECEIVE_COMPLETED() macro sends a notification to the task to + * remove it from the Blocked state. xStreamBufferReceiveCompletedFromISR() + * does the same thing. It is provided to enable application writers to + * implement their own version of sbRECEIVE_COMPLETED(), and MUST NOT BE USED AT + * ANY OTHER TIME. + * + * See the example implemented in FreeRTOS/Demo/Minimal/MessageBufferAMP.c for + * additional information. + * + * @param xStreamBuffer The handle of the stream buffer from which data was + * read. + * + * @param pxHigherPriorityTaskWoken *pxHigherPriorityTaskWoken should be + * initialised to pdFALSE before it is passed into + * xStreamBufferReceiveCompletedFromISR(). If calling + * xStreamBufferReceiveCompletedFromISR() removes a task from the Blocked state, + * and the task has a priority above the priority of the currently running task, + * then *pxHigherPriorityTaskWoken will get set to pdTRUE indicating that a + * context switch should be performed before exiting the ISR. + * + * @return If a task was removed from the Blocked state then pdTRUE is returned. + * Otherwise pdFALSE is returned. + * + * \defgroup xStreamBufferReceiveCompletedFromISR xStreamBufferReceiveCompletedFromISR + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferReceiveCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/* Functions below here are not part of the public API. */ +StreamBufferHandle_t xStreamBufferGenericCreate( size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + BaseType_t xIsMessageBuffer ) PRIVILEGED_FUNCTION; + +StreamBufferHandle_t xStreamBufferGenericCreateStatic( size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + BaseType_t xIsMessageBuffer, + uint8_t * const pucStreamBufferStorageArea, + StaticStreamBuffer_t * const pxStaticStreamBuffer ) PRIVILEGED_FUNCTION; + +size_t xStreamBufferNextMessageLengthBytes( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +#if( configUSE_TRACE_FACILITY == 1 ) + void vStreamBufferSetStreamBufferNumber( StreamBufferHandle_t xStreamBuffer, UBaseType_t uxStreamBufferNumber ) PRIVILEGED_FUNCTION; + UBaseType_t uxStreamBufferGetStreamBufferNumber( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + uint8_t ucStreamBufferGetStreamBufferType( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; +#endif + +#if defined( __cplusplus ) +} +#endif + +#endif /* !defined( STREAM_BUFFER_H ) */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/task.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/task.h new file mode 100644 index 0000000..ae1605f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/task.h @@ -0,0 +1,2543 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 INC_TASK_H +#define INC_TASK_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include task.h" +#endif + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +#define tskKERNEL_VERSION_NUMBER "V10.3.1" +#define tskKERNEL_VERSION_MAJOR 10 +#define tskKERNEL_VERSION_MINOR 3 +#define tskKERNEL_VERSION_BUILD 1 + +/* MPU region parameters passed in ulParameters + * of MemoryRegion_t struct. */ +#define tskMPU_REGION_READ_ONLY ( 1UL << 0UL ) +#define tskMPU_REGION_READ_WRITE ( 1UL << 1UL ) +#define tskMPU_REGION_EXECUTE_NEVER ( 1UL << 2UL ) +#define tskMPU_REGION_NORMAL_MEMORY ( 1UL << 3UL ) +#define tskMPU_REGION_DEVICE_MEMORY ( 1UL << 4UL ) + +/** + * task. h + * + * Type by which tasks are referenced. For example, a call to xTaskCreate + * returns (via a pointer parameter) an TaskHandle_t variable that can then + * be used as a parameter to vTaskDelete to delete the task. + * + * \defgroup TaskHandle_t TaskHandle_t + * \ingroup Tasks + */ +struct tskTaskControlBlock; /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +typedef struct tskTaskControlBlock* TaskHandle_t; + +/* + * Defines the prototype to which the application task hook function must + * conform. + */ +typedef BaseType_t (*TaskHookFunction_t)( void * ); + +/* Task states returned by eTaskGetState. */ +typedef enum +{ + eRunning = 0, /* A task is querying the state of itself, so must be running. */ + eReady, /* The task being queried is in a read or pending ready list. */ + eBlocked, /* The task being queried is in the Blocked state. */ + eSuspended, /* The task being queried is in the Suspended state, or is in the Blocked state with an infinite time out. */ + eDeleted, /* The task being queried has been deleted, but its TCB has not yet been freed. */ + eInvalid /* Used as an 'invalid state' value. */ +} eTaskState; + +/* Actions that can be performed when vTaskNotify() is called. */ +typedef enum +{ + eNoAction = 0, /* Notify the task without updating its notify value. */ + eSetBits, /* Set bits in the task's notification value. */ + eIncrement, /* Increment the task's notification value. */ + eSetValueWithOverwrite, /* Set the task's notification value to a specific value even if the previous value has not yet been read by the task. */ + eSetValueWithoutOverwrite /* Set the task's notification value if the previous value has been read by the task. */ +} eNotifyAction; + +/* + * Used internally only. + */ +typedef struct xTIME_OUT +{ + BaseType_t xOverflowCount; + TickType_t xTimeOnEntering; +} TimeOut_t; + +/* + * Defines the memory ranges allocated to the task when an MPU is used. + */ +typedef struct xMEMORY_REGION +{ + void *pvBaseAddress; + uint32_t ulLengthInBytes; + uint32_t ulParameters; +} MemoryRegion_t; + +/* + * Parameters required to create an MPU protected task. + */ +typedef struct xTASK_PARAMETERS +{ + TaskFunction_t pvTaskCode; + const char * const pcName; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + configSTACK_DEPTH_TYPE usStackDepth; + void *pvParameters; + UBaseType_t uxPriority; + StackType_t *puxStackBuffer; + MemoryRegion_t xRegions[ portNUM_CONFIGURABLE_REGIONS ]; + #if ( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + StaticTask_t * const pxTaskBuffer; + #endif +} TaskParameters_t; + +/* Used with the uxTaskGetSystemState() function to return the state of each task +in the system. */ +typedef struct xTASK_STATUS +{ + TaskHandle_t xHandle; /* The handle of the task to which the rest of the information in the structure relates. */ + const char *pcTaskName; /* A pointer to the task's name. This value will be invalid if the task was deleted since the structure was populated! */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + UBaseType_t xTaskNumber; /* A number unique to the task. */ + eTaskState eCurrentState; /* The state in which the task existed when the structure was populated. */ + UBaseType_t uxCurrentPriority; /* The priority at which the task was running (may be inherited) when the structure was populated. */ + UBaseType_t uxBasePriority; /* The priority to which the task will return if the task's current priority has been inherited to avoid unbounded priority inversion when obtaining a mutex. Only valid if configUSE_MUTEXES is defined as 1 in FreeRTOSConfig.h. */ + uint32_t ulRunTimeCounter; /* The total run time allocated to the task so far, as defined by the run time stats clock. See http://www.freertos.org/rtos-run-time-stats.html. Only valid when configGENERATE_RUN_TIME_STATS is defined as 1 in FreeRTOSConfig.h. */ + StackType_t *pxStackBase; /* Points to the lowest address of the task's stack area. */ + configSTACK_DEPTH_TYPE usStackHighWaterMark; /* The minimum amount of stack space that has remained for the task since the task was created. The closer this value is to zero the closer the task has come to overflowing its stack. */ +} TaskStatus_t; + +/* Possible return values for eTaskConfirmSleepModeStatus(). */ +typedef enum +{ + eAbortSleep = 0, /* A task has been made ready or a context switch pended since portSUPPORESS_TICKS_AND_SLEEP() was called - abort entering a sleep mode. */ + eStandardSleep, /* Enter a sleep mode that will not last any longer than the expected idle time. */ + eNoTasksWaitingTimeout /* No tasks are waiting for a timeout so it is safe to enter a sleep mode that can only be exited by an external interrupt. */ +} eSleepModeStatus; + +/** + * Defines the priority used by the idle task. This must not be modified. + * + * \ingroup TaskUtils + */ +#define tskIDLE_PRIORITY ( ( UBaseType_t ) 0U ) + +/** + * task. h + * + * Macro for forcing a context switch. + * + * \defgroup taskYIELD taskYIELD + * \ingroup SchedulerControl + */ +#define taskYIELD() portYIELD() + +/** + * task. h + * + * Macro to mark the start of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \defgroup taskENTER_CRITICAL taskENTER_CRITICAL + * \ingroup SchedulerControl + */ +#define taskENTER_CRITICAL() portENTER_CRITICAL() +#define taskENTER_CRITICAL_FROM_ISR() portSET_INTERRUPT_MASK_FROM_ISR() + +/** + * task. h + * + * Macro to mark the end of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \defgroup taskEXIT_CRITICAL taskEXIT_CRITICAL + * \ingroup SchedulerControl + */ +#define taskEXIT_CRITICAL() portEXIT_CRITICAL() +#define taskEXIT_CRITICAL_FROM_ISR( x ) portCLEAR_INTERRUPT_MASK_FROM_ISR( x ) +/** + * task. h + * + * Macro to disable all maskable interrupts. + * + * \defgroup taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() + +/** + * task. h + * + * Macro to enable microcontroller interrupts. + * + * \defgroup taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() + +/* Definitions returned by xTaskGetSchedulerState(). taskSCHEDULER_SUSPENDED is +0 to generate more optimal code when configASSERT() is defined as the constant +is used in assert() statements. */ +#define taskSCHEDULER_SUSPENDED ( ( BaseType_t ) 0 ) +#define taskSCHEDULER_NOT_STARTED ( ( BaseType_t ) 1 ) +#define taskSCHEDULER_RUNNING ( ( BaseType_t ) 2 ) + + +/*----------------------------------------------------------- + * TASK CREATION API + *----------------------------------------------------------*/ + +/** + * task. h + *
+ BaseType_t xTaskCreate(
+							  TaskFunction_t pvTaskCode,
+							  const char * const pcName,
+							  configSTACK_DEPTH_TYPE usStackDepth,
+							  void *pvParameters,
+							  UBaseType_t uxPriority,
+							  TaskHandle_t *pvCreatedTask
+						  );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * Internally, within the FreeRTOS implementation, tasks use two blocks of + * memory. The first block is used to hold the task's data structures. The + * second block is used by the task as its stack. If a task is created using + * xTaskCreate() then both blocks of memory are automatically dynamically + * allocated inside the xTaskCreate() function. (see + * http://www.freertos.org/a00111.html). If a task is created using + * xTaskCreateStatic() then the application writer must provide the required + * memory. xTaskCreateStatic() therefore allows a task to be created without + * using any dynamic memory allocation. + * + * See xTaskCreateStatic() for a version that does not use any dynamic memory + * allocation. + * + * xTaskCreate() can only be used to create a task that has unrestricted + * access to the entire microcontroller memory map. Systems that include MPU + * support can alternatively create an MPU constrained task using + * xTaskCreateRestricted(). + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. Max length defined by configMAX_TASK_NAME_LEN - default + * is 16. + * + * @param usStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task should run. Systems that + * include MPU support can optionally create tasks in a privileged (system) + * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For + * example, to create a privileged task at priority 2 the uxPriority parameter + * should be set to ( 2 | portPRIVILEGE_BIT ). + * + * @param pvCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file projdefs.h + * + * Example usage: +
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static uint8_t ucParameterToPass;
+ TaskHandle_t xHandle = NULL;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+	 configASSERT( xHandle );
+
+	 // Use the handle to delete the task.
+	 if( xHandle != NULL )
+	 {
+	 	vTaskDelete( xHandle );
+	 }
+ }
+   
+ * \defgroup xTaskCreate xTaskCreate + * \ingroup Tasks + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + BaseType_t xTaskCreate( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const configSTACK_DEPTH_TYPE usStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t * const pxCreatedTask ) PRIVILEGED_FUNCTION; +#endif + +/** + * task. h + *
+ TaskHandle_t xTaskCreateStatic( TaskFunction_t pvTaskCode,
+								 const char * const pcName,
+								 uint32_t ulStackDepth,
+								 void *pvParameters,
+								 UBaseType_t uxPriority,
+								 StackType_t *pxStackBuffer,
+								 StaticTask_t *pxTaskBuffer );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * Internally, within the FreeRTOS implementation, tasks use two blocks of + * memory. The first block is used to hold the task's data structures. The + * second block is used by the task as its stack. If a task is created using + * xTaskCreate() then both blocks of memory are automatically dynamically + * allocated inside the xTaskCreate() function. (see + * http://www.freertos.org/a00111.html). If a task is created using + * xTaskCreateStatic() then the application writer must provide the required + * memory. xTaskCreateStatic() therefore allows a task to be created without + * using any dynamic memory allocation. + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. The maximum length of the string is defined by + * configMAX_TASK_NAME_LEN in FreeRTOSConfig.h. + * + * @param ulStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 32-bits wide and ulStackDepth is defined as 100 then 400 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task will run. + * + * @param pxStackBuffer Must point to a StackType_t array that has at least + * ulStackDepth indexes - the array will then be used as the task's stack, + * removing the need for the stack to be allocated dynamically. + * + * @param pxTaskBuffer Must point to a variable of type StaticTask_t, which will + * then be used to hold the task's data structures, removing the need for the + * memory to be allocated dynamically. + * + * @return If neither pxStackBuffer or pxTaskBuffer are NULL, then the task will + * be created and a handle to the created task is returned. If either + * pxStackBuffer or pxTaskBuffer are NULL then the task will not be created and + * NULL is returned. + * + * Example usage: +
+
+    // Dimensions the buffer that the task being created will use as its stack.
+    // NOTE:  This is the number of words the stack will hold, not the number of
+    // bytes.  For example, if each stack item is 32-bits, and this is set to 100,
+    // then 400 bytes (100 * 32-bits) will be allocated.
+    #define STACK_SIZE 200
+
+    // Structure that will hold the TCB of the task being created.
+    StaticTask_t xTaskBuffer;
+
+    // Buffer that the task being created will use as its stack.  Note this is
+    // an array of StackType_t variables.  The size of StackType_t is dependent on
+    // the RTOS port.
+    StackType_t xStack[ STACK_SIZE ];
+
+    // Function that implements the task being created.
+    void vTaskCode( void * pvParameters )
+    {
+        // The parameter value is expected to be 1 as 1 is passed in the
+        // pvParameters value in the call to xTaskCreateStatic().
+        configASSERT( ( uint32_t ) pvParameters == 1UL );
+
+        for( ;; )
+        {
+            // Task code goes here.
+        }
+    }
+
+    // Function that creates a task.
+    void vOtherFunction( void )
+    {
+        TaskHandle_t xHandle = NULL;
+
+        // Create the task without using any dynamic memory allocation.
+        xHandle = xTaskCreateStatic(
+                      vTaskCode,       // Function that implements the task.
+                      "NAME",          // Text name for the task.
+                      STACK_SIZE,      // Stack size in words, not bytes.
+                      ( void * ) 1,    // Parameter passed into the task.
+                      tskIDLE_PRIORITY,// Priority at which the task is created.
+                      xStack,          // Array to use as the task's stack.
+                      &xTaskBuffer );  // Variable to hold the task's data structure.
+
+        // puxStackBuffer and pxTaskBuffer were not NULL, so the task will have
+        // been created, and xHandle will be the task's handle.  Use the handle
+        // to suspend the task.
+        vTaskSuspend( xHandle );
+    }
+   
+ * \defgroup xTaskCreateStatic xTaskCreateStatic + * \ingroup Tasks + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + TaskHandle_t xTaskCreateStatic( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const uint32_t ulStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + StackType_t * const puxStackBuffer, + StaticTask_t * const pxTaskBuffer ) PRIVILEGED_FUNCTION; +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * task. h + *
+ BaseType_t xTaskCreateRestricted( TaskParameters_t *pxTaskDefinition, TaskHandle_t *pxCreatedTask );
+ * + * Only available when configSUPPORT_DYNAMIC_ALLOCATION is set to 1. + * + * xTaskCreateRestricted() should only be used in systems that include an MPU + * implementation. + * + * Create a new task and add it to the list of tasks that are ready to run. + * The function parameters define the memory regions and associated access + * permissions allocated to the task. + * + * See xTaskCreateRestrictedStatic() for a version that does not use any + * dynamic memory allocation. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file projdefs.h + * + * Example usage: +
+// Create an TaskParameters_t structure that defines the task to be created.
+static const TaskParameters_t xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{
+		// Base address					Length	Parameters
+		{ cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+		{ cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+		{ cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+TaskHandle_t xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// and/or timer task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + BaseType_t xTaskCreateRestricted( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) PRIVILEGED_FUNCTION; +#endif + +/** + * task. h + *
+ BaseType_t xTaskCreateRestrictedStatic( TaskParameters_t *pxTaskDefinition, TaskHandle_t *pxCreatedTask );
+ * + * Only available when configSUPPORT_STATIC_ALLOCATION is set to 1. + * + * xTaskCreateRestrictedStatic() should only be used in systems that include an + * MPU implementation. + * + * Internally, within the FreeRTOS implementation, tasks use two blocks of + * memory. The first block is used to hold the task's data structures. The + * second block is used by the task as its stack. If a task is created using + * xTaskCreateRestricted() then the stack is provided by the application writer, + * and the memory used to hold the task's data structure is automatically + * dynamically allocated inside the xTaskCreateRestricted() function. If a task + * is created using xTaskCreateRestrictedStatic() then the application writer + * must provide the memory used to hold the task's data structures too. + * xTaskCreateRestrictedStatic() therefore allows a memory protected task to be + * created without using any dynamic memory allocation. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. If configSUPPORT_STATIC_ALLOCATION is set to 1 the structure + * contains an additional member, which is used to point to a variable of type + * StaticTask_t - which is then used to hold the task's data structure. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file projdefs.h + * + * Example usage: +
+// Create an TaskParameters_t structure that defines the task to be created.
+// The StaticTask_t variable is only included in the structure when
+// configSUPPORT_STATIC_ALLOCATION is set to 1.  The PRIVILEGED_DATA macro can
+// be used to force the variable into the RTOS kernel's privileged data area.
+static PRIVILEGED_DATA StaticTask_t xTaskBuffer;
+static const TaskParameters_t xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{
+		// Base address					Length	Parameters
+		{ cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+		{ cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+		{ cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+
+	&xTaskBuffer; // Holds the task's data structure.
+};
+
+int main( void )
+{
+TaskHandle_t xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// and/or timer task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestrictedStatic xTaskCreateRestrictedStatic + * \ingroup Tasks + */ +#if( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + BaseType_t xTaskCreateRestrictedStatic( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) PRIVILEGED_FUNCTION; +#endif + +/** + * task. h + *
+ void vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const pxRegions );
+ * + * Memory regions are assigned to a restricted task when the task is created by + * a call to xTaskCreateRestricted(). These regions can be redefined using + * vTaskAllocateMPURegions(). + * + * @param xTask The handle of the task being updated. + * + * @param xRegions A pointer to an MemoryRegion_t structure that contains the + * new memory region definitions. + * + * Example usage: +
+// Define an array of MemoryRegion_t structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const MemoryRegion_t xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +void vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const pxRegions ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelete( TaskHandle_t xTask );
+ * + * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Remove a task from the RTOS real time kernel's management. The task being + * deleted will be removed from all ready, blocked, suspended and event lists. + * + * NOTE: The idle task is responsible for freeing the kernel allocated + * memory from tasks that have been deleted. It is therefore important that + * the idle task is not starved of microcontroller processing time if your + * application makes any calls to vTaskDelete (). Memory allocated by the + * task code is not automatically freed, and should be freed before the task + * is deleted. + * + * See the demo application file death.c for sample code that utilises + * vTaskDelete (). + * + * @param xTask The handle of the task to be deleted. Passing NULL will + * cause the calling task to be deleted. + * + * Example usage: +
+ void vOtherFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup vTaskDelete vTaskDelete + * \ingroup Tasks + */ +void vTaskDelete( TaskHandle_t xTaskToDelete ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK CONTROL API + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskDelay( const TickType_t xTicksToDelay );
+ * + * Delay a task for a given number of ticks. The actual time that the + * task remains blocked depends on the tick rate. The constant + * portTICK_PERIOD_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * + * vTaskDelay() specifies a time at which the task wishes to unblock relative to + * the time at which vTaskDelay() is called. For example, specifying a block + * period of 100 ticks will cause the task to unblock 100 ticks after + * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method + * of controlling the frequency of a periodic task as the path taken through the + * code, as well as other task and interrupt activity, will effect the frequency + * at which vTaskDelay() gets called and therefore the time at which the task + * next executes. See vTaskDelayUntil() for an alternative API function designed + * to facilitate fixed frequency execution. It does this by specifying an + * absolute time (rather than a relative time) at which the calling task should + * unblock. + * + * @param xTicksToDelay The amount of time, in tick periods, that + * the calling task should block. + * + * Example usage: + + void vTaskFunction( void * pvParameters ) + { + // Block for 500ms. + const TickType_t xDelay = 500 / portTICK_PERIOD_MS; + + for( ;; ) + { + // Simply toggle the LED every 500ms, blocking between each toggle. + vToggleLED(); + vTaskDelay( xDelay ); + } + } + + * \defgroup vTaskDelay vTaskDelay + * \ingroup TaskCtrl + */ +void vTaskDelay( const TickType_t xTicksToDelay ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelayUntil( TickType_t *pxPreviousWakeTime, const TickType_t xTimeIncrement );
+ * + * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Delay a task until a specified time. This function can be used by periodic + * tasks to ensure a constant execution frequency. + * + * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will + * cause a task to block for the specified number of ticks from the time vTaskDelay () is + * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed + * execution frequency as the time between a task starting to execute and that task + * calling vTaskDelay () may not be fixed [the task may take a different path though the + * code between calls, or may get interrupted or preempted a different number of times + * each time it executes]. + * + * Whereas vTaskDelay () specifies a wake time relative to the time at which the function + * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to + * unblock. + * + * The constant portTICK_PERIOD_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the + * task was last unblocked. The variable must be initialised with the current time + * prior to its first use (see the example below). Following this the variable is + * automatically updated within vTaskDelayUntil (). + * + * @param xTimeIncrement The cycle time period. The task will be unblocked at + * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the + * same xTimeIncrement parameter value will cause the task to execute with + * a fixed interface period. + * + * Example usage: +
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   
+ * \defgroup vTaskDelayUntil vTaskDelayUntil + * \ingroup TaskCtrl + */ +void vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, const TickType_t xTimeIncrement ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskAbortDelay( TaskHandle_t xTask );
+ * + * INCLUDE_xTaskAbortDelay must be defined as 1 in FreeRTOSConfig.h for this + * function to be available. + * + * A task will enter the Blocked state when it is waiting for an event. The + * event it is waiting for can be a temporal event (waiting for a time), such + * as when vTaskDelay() is called, or an event on an object, such as when + * xQueueReceive() or ulTaskNotifyTake() is called. If the handle of a task + * that is in the Blocked state is used in a call to xTaskAbortDelay() then the + * task will leave the Blocked state, and return from whichever function call + * placed the task into the Blocked state. + * + * There is no 'FromISR' version of this function as an interrupt would need to + * know which object a task was blocked on in order to know which actions to + * take. For example, if the task was blocked on a queue the interrupt handler + * would then need to know if the queue was locked. + * + * @param xTask The handle of the task to remove from the Blocked state. + * + * @return If the task referenced by xTask was not in the Blocked state then + * pdFAIL is returned. Otherwise pdPASS is returned. + * + * \defgroup xTaskAbortDelay xTaskAbortDelay + * \ingroup TaskCtrl + */ +BaseType_t xTaskAbortDelay( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
UBaseType_t uxTaskPriorityGet( const TaskHandle_t xTask );
+ * + * INCLUDE_uxTaskPriorityGet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the priority of any task. + * + * @param xTask Handle of the task to be queried. Passing a NULL + * handle results in the priority of the calling task being returned. + * + * @return The priority of xTask. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet + * \ingroup TaskCtrl + */ +UBaseType_t uxTaskPriorityGet( const TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
UBaseType_t uxTaskPriorityGetFromISR( const TaskHandle_t xTask );
+ * + * A version of uxTaskPriorityGet() that can be used from an ISR. + */ +UBaseType_t uxTaskPriorityGetFromISR( const TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
eTaskState eTaskGetState( TaskHandle_t xTask );
+ * + * INCLUDE_eTaskGetState must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the state of any task. States are encoded by the eTaskState + * enumerated type. + * + * @param xTask Handle of the task to be queried. + * + * @return The state of xTask at the time the function was called. Note the + * state of the task might change between the function being called, and the + * functions return value being tested by the calling task. + */ +eTaskState eTaskGetState( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState );
+ * + * configUSE_TRACE_FACILITY must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * Populates a TaskStatus_t structure with information about a task. + * + * @param xTask Handle of the task being queried. If xTask is NULL then + * information will be returned about the calling task. + * + * @param pxTaskStatus A pointer to the TaskStatus_t structure that will be + * filled with information about the task referenced by the handle passed using + * the xTask parameter. + * + * @xGetFreeStackSpace The TaskStatus_t structure contains a member to report + * the stack high water mark of the task being queried. Calculating the stack + * high water mark takes a relatively long time, and can make the system + * temporarily unresponsive - so the xGetFreeStackSpace parameter is provided to + * allow the high water mark checking to be skipped. The high watermark value + * will only be written to the TaskStatus_t structure if xGetFreeStackSpace is + * not set to pdFALSE; + * + * @param eState The TaskStatus_t structure contains a member to report the + * state of the task being queried. Obtaining the task state is not as fast as + * a simple assignment - so the eState parameter is provided to allow the state + * information to be omitted from the TaskStatus_t structure. To obtain state + * information then set eState to eInvalid - otherwise the value passed in + * eState will be reported as the task state in the TaskStatus_t structure. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+ TaskStatus_t xTaskDetails;
+
+    // Obtain the handle of a task from its name.
+    xHandle = xTaskGetHandle( "Task_Name" );
+
+    // Check the handle is not NULL.
+    configASSERT( xHandle );
+
+    // Use the handle to obtain further information about the task.
+    vTaskGetInfo( xHandle,
+                  &xTaskDetails,
+                  pdTRUE, // Include the high water mark in xTaskDetails.
+                  eInvalid ); // Include the task state in xTaskDetails.
+ }
+   
+ * \defgroup vTaskGetInfo vTaskGetInfo + * \ingroup TaskCtrl + */ +void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority );
+ * + * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Set the priority of any task. + * + * A context switch will occur before the function returns if the priority + * being set is higher than the currently executing task. + * + * @param xTask Handle to the task for which the priority is being set. + * Passing a NULL handle results in the priority of the calling task being set. + * + * @param uxNewPriority The priority to which the task will be set. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   
+ * \defgroup vTaskPrioritySet vTaskPrioritySet + * \ingroup TaskCtrl + */ +void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspend( TaskHandle_t xTaskToSuspend );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Suspend any task. When suspended a task will never get any microcontroller + * processing time, no matter what its priority. + * + * Calls to vTaskSuspend are not accumulative - + * i.e. calling vTaskSuspend () twice on the same task still only requires one + * call to vTaskResume () to ready the suspended task. + * + * @param xTaskToSuspend Handle to the task being suspended. Passing a NULL + * handle will cause the calling task to be suspended. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   
+ * \defgroup vTaskSuspend vTaskSuspend + * \ingroup TaskCtrl + */ +void vTaskSuspend( TaskHandle_t xTaskToSuspend ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskResume( TaskHandle_t xTaskToResume );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Resumes a suspended task. + * + * A task that has been suspended by one or more calls to vTaskSuspend () + * will be made available for running again by a single call to + * vTaskResume (). + * + * @param xTaskToResume Handle to the task being readied. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with its priority within the system.
+ }
+   
+ * \defgroup vTaskResume vTaskResume + * \ingroup TaskCtrl + */ +void vTaskResume( TaskHandle_t xTaskToResume ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void xTaskResumeFromISR( TaskHandle_t xTaskToResume );
+ * + * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * An implementation of vTaskResume() that can be called from within an ISR. + * + * A task that has been suspended by one or more calls to vTaskSuspend () + * will be made available for running again by a single call to + * xTaskResumeFromISR (). + * + * xTaskResumeFromISR() should not be used to synchronise a task with an + * interrupt if there is a chance that the interrupt could arrive prior to the + * task being suspended - as this can lead to interrupts being missed. Use of a + * semaphore as a synchronisation mechanism would avoid this eventuality. + * + * @param xTaskToResume Handle to the task being readied. + * + * @return pdTRUE if resuming the task should result in a context switch, + * otherwise pdFALSE. This is used by the ISR to determine if a context switch + * may be required following the ISR. + * + * \defgroup vTaskResumeFromISR vTaskResumeFromISR + * \ingroup TaskCtrl + */ +BaseType_t xTaskResumeFromISR( TaskHandle_t xTaskToResume ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER CONTROL + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskStartScheduler( void );
+ * + * Starts the real time kernel tick processing. After calling the kernel + * has control over which tasks are executed and when. + * + * See the demo application file main.c for an example of creating + * tasks and starting the kernel. + * + * Example usage: +
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   
+ * + * \defgroup vTaskStartScheduler vTaskStartScheduler + * \ingroup SchedulerControl + */ +void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskEndScheduler( void );
+ * + * NOTE: At the time of writing only the x86 real mode port, which runs on a PC + * in place of DOS, implements this function. + * + * Stops the real time kernel tick. All created tasks will be automatically + * deleted and multitasking (either preemptive or cooperative) will + * stop. Execution then resumes from the point where vTaskStartScheduler () + * was called, as if vTaskStartScheduler () had just returned. + * + * See the demo application file main. c in the demo/PC directory for an + * example that uses vTaskEndScheduler (). + * + * vTaskEndScheduler () requires an exit function to be defined within the + * portable layer (see vPortEndScheduler () in port. c for the PC port). This + * performs hardware specific operations such as stopping the kernel tick. + * + * vTaskEndScheduler () will cause all of the resources allocated by the + * kernel to be freed - but will not free resources allocated by application + * tasks. + * + * Example usage: +
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   
+ * + * \defgroup vTaskEndScheduler vTaskEndScheduler + * \ingroup SchedulerControl + */ +void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspendAll( void );
+ * + * Suspends the scheduler without disabling interrupts. Context switches will + * not occur while the scheduler is suspended. + * + * After calling vTaskSuspendAll () the calling task will continue to execute + * without risk of being swapped out until a call to xTaskResumeAll () has been + * made. + * + * API functions that have the potential to cause a context switch (for example, + * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler + * is suspended. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   
+ * \defgroup vTaskSuspendAll vTaskSuspendAll + * \ingroup SchedulerControl + */ +void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskResumeAll( void );
+ * + * Resumes scheduler activity after it was suspended by a call to + * vTaskSuspendAll(). + * + * xTaskResumeAll() only resumes the scheduler. It does not unsuspend tasks + * that were previously suspended by a call to vTaskSuspend(). + * + * @return If resuming the scheduler caused a context switch then pdTRUE is + * returned, otherwise pdFALSE is returned. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   
+ * \defgroup xTaskResumeAll xTaskResumeAll + * \ingroup SchedulerControl + */ +BaseType_t xTaskResumeAll( void ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK UTILITIES + *----------------------------------------------------------*/ + +/** + * task. h + *
TickType_t xTaskGetTickCount( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * \defgroup xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +TickType_t xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
TickType_t xTaskGetTickCountFromISR( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * This is a version of xTaskGetTickCount() that is safe to be called from an + * ISR - provided that TickType_t is the natural word size of the + * microcontroller being used or interrupt nesting is either not supported or + * not being used. + * + * \defgroup xTaskGetTickCountFromISR xTaskGetTickCountFromISR + * \ingroup TaskUtils + */ +TickType_t xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
uint16_t uxTaskGetNumberOfTasks( void );
+ * + * @return The number of tasks that the real time kernel is currently managing. + * This includes all ready, blocked and suspended tasks. A task that + * has been deleted but not yet freed by the idle task will also be + * included in the count. + * + * \defgroup uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks + * \ingroup TaskUtils + */ +UBaseType_t uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
char *pcTaskGetName( TaskHandle_t xTaskToQuery );
+ * + * @return The text (human readable) name of the task referenced by the handle + * xTaskToQuery. A task can query its own name by either passing in its own + * handle, or by setting xTaskToQuery to NULL. + * + * \defgroup pcTaskGetName pcTaskGetName + * \ingroup TaskUtils + */ +char *pcTaskGetName( TaskHandle_t xTaskToQuery ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** + * task. h + *
TaskHandle_t xTaskGetHandle( const char *pcNameToQuery );
+ * + * NOTE: This function takes a relatively long time to complete and should be + * used sparingly. + * + * @return The handle of the task that has the human readable name pcNameToQuery. + * NULL is returned if no matching name is found. INCLUDE_xTaskGetHandle + * must be set to 1 in FreeRTOSConfig.h for pcTaskGetHandle() to be available. + * + * \defgroup pcTaskGetHandle pcTaskGetHandle + * \ingroup TaskUtils + */ +TaskHandle_t xTaskGetHandle( const char *pcNameToQuery ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** + * task.h + *
UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in words, so on a 32 bit machine + * a value of 1 means 4 bytes) since the task started. The smaller the returned + * number the closer the task has come to overflowing its stack. + * + * uxTaskGetStackHighWaterMark() and uxTaskGetStackHighWaterMark2() are the + * same except for their return type. Using configSTACK_DEPTH_TYPE allows the + * user to determine the return type. It gets around the problem of the value + * overflowing on 8-bit types without breaking backward compatibility for + * applications that expect an 8-bit return type. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in words, so + * actual spaces on the stack rather than bytes) since the task referenced by + * xTask was created. + */ +UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
configSTACK_DEPTH_TYPE uxTaskGetStackHighWaterMark2( TaskHandle_t xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark2 must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in words, so on a 32 bit machine + * a value of 1 means 4 bytes) since the task started. The smaller the returned + * number the closer the task has come to overflowing its stack. + * + * uxTaskGetStackHighWaterMark() and uxTaskGetStackHighWaterMark2() are the + * same except for their return type. Using configSTACK_DEPTH_TYPE allows the + * user to determine the return type. It gets around the problem of the value + * overflowing on 8-bit types without breaking backward compatibility for + * applications that expect an 8-bit return type. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in words, so + * actual spaces on the stack rather than bytes) since the task referenced by + * xTask was created. + */ +configSTACK_DEPTH_TYPE uxTaskGetStackHighWaterMark2( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/* When using trace macros it is sometimes necessary to include task.h before +FreeRTOS.h. When this is done TaskHookFunction_t will not yet have been defined, +so the following two prototypes will cause a compilation error. This can be +fixed by simply guarding against the inclusion of these two prototypes unless +they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration +constant. */ +#ifdef configUSE_APPLICATION_TASK_TAG + #if configUSE_APPLICATION_TASK_TAG == 1 + /** + * task.h + *
void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction );
+ * + * Sets pxHookFunction to be the task hook function used by the task xTask. + * Passing xTask as NULL has the effect of setting the calling tasks hook + * function. + */ + void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction ) PRIVILEGED_FUNCTION; + + /** + * task.h + *
void xTaskGetApplicationTaskTag( TaskHandle_t xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. Do not + * call from an interrupt service routine - call + * xTaskGetApplicationTaskTagFromISR() instead. + */ + TaskHookFunction_t xTaskGetApplicationTaskTag( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + + /** + * task.h + *
void xTaskGetApplicationTaskTagFromISR( TaskHandle_t xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. Can + * be called from an interrupt service routine. + */ + TaskHookFunction_t xTaskGetApplicationTaskTagFromISR( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ +#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ + +#if( configNUM_THREAD_LOCAL_STORAGE_POINTERS > 0 ) + + /* Each task contains an array of pointers that is dimensioned by the + configNUM_THREAD_LOCAL_STORAGE_POINTERS setting in FreeRTOSConfig.h. The + kernel does not use the pointers itself, so the application writer can use + the pointers for any purpose they wish. The following two functions are + used to set and query a pointer respectively. */ + void vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue ) PRIVILEGED_FUNCTION; + void *pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex ) PRIVILEGED_FUNCTION; + +#endif + +/** + * task.h + *
BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter );
+ * + * Calls the hook function associated with xTask. Passing xTask as NULL has + * the effect of calling the Running tasks (the calling task) hook function. + * + * pvParameter is passed to the hook function for the task to interpret as it + * wants. The return value is the value returned by the task hook function + * registered by the user. + */ +BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter ) PRIVILEGED_FUNCTION; + +/** + * xTaskGetIdleTaskHandle() is only available if + * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the idle task. It is not valid to call + * xTaskGetIdleTaskHandle() before the scheduler has been started. + */ +TaskHandle_t xTaskGetIdleTaskHandle( void ) PRIVILEGED_FUNCTION; + +/** + * configUSE_TRACE_FACILITY must be defined as 1 in FreeRTOSConfig.h for + * uxTaskGetSystemState() to be available. + * + * uxTaskGetSystemState() populates an TaskStatus_t structure for each task in + * the system. TaskStatus_t structures contain, among other things, members + * for the task handle, task name, task priority, task state, and total amount + * of run time consumed by the task. See the TaskStatus_t structure + * definition in this file for the full member list. + * + * NOTE: This function is intended for debugging use only as its use results in + * the scheduler remaining suspended for an extended period. + * + * @param pxTaskStatusArray A pointer to an array of TaskStatus_t structures. + * The array must contain at least one TaskStatus_t structure for each task + * that is under the control of the RTOS. The number of tasks under the control + * of the RTOS can be determined using the uxTaskGetNumberOfTasks() API function. + * + * @param uxArraySize The size of the array pointed to by the pxTaskStatusArray + * parameter. The size is specified as the number of indexes in the array, or + * the number of TaskStatus_t structures contained in the array, not by the + * number of bytes in the array. + * + * @param pulTotalRunTime If configGENERATE_RUN_TIME_STATS is set to 1 in + * FreeRTOSConfig.h then *pulTotalRunTime is set by uxTaskGetSystemState() to the + * total run time (as defined by the run time stats clock, see + * http://www.freertos.org/rtos-run-time-stats.html) since the target booted. + * pulTotalRunTime can be set to NULL to omit the total run time information. + * + * @return The number of TaskStatus_t structures that were populated by + * uxTaskGetSystemState(). This should equal the number returned by the + * uxTaskGetNumberOfTasks() API function, but will be zero if the value passed + * in the uxArraySize parameter was too small. + * + * Example usage: +
+    // This example demonstrates how a human readable table of run time stats
+	// information is generated from raw data provided by uxTaskGetSystemState().
+	// The human readable table is written to pcWriteBuffer
+	void vTaskGetRunTimeStats( char *pcWriteBuffer )
+	{
+	TaskStatus_t *pxTaskStatusArray;
+	volatile UBaseType_t uxArraySize, x;
+	uint32_t ulTotalRunTime, ulStatsAsPercentage;
+
+		// Make sure the write buffer does not contain a string.
+		*pcWriteBuffer = 0x00;
+
+		// Take a snapshot of the number of tasks in case it changes while this
+		// function is executing.
+		uxArraySize = uxTaskGetNumberOfTasks();
+
+		// Allocate a TaskStatus_t structure for each task.  An array could be
+		// allocated statically at compile time.
+		pxTaskStatusArray = pvPortMalloc( uxArraySize * sizeof( TaskStatus_t ) );
+
+		if( pxTaskStatusArray != NULL )
+		{
+			// Generate raw status information about each task.
+			uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, &ulTotalRunTime );
+
+			// For percentage calculations.
+			ulTotalRunTime /= 100UL;
+
+			// Avoid divide by zero errors.
+			if( ulTotalRunTime > 0 )
+			{
+				// For each populated position in the pxTaskStatusArray array,
+				// format the raw data as human readable ASCII data
+				for( x = 0; x < uxArraySize; x++ )
+				{
+					// What percentage of the total run time has the task used?
+					// This will always be rounded down to the nearest integer.
+					// ulTotalRunTimeDiv100 has already been divided by 100.
+					ulStatsAsPercentage = pxTaskStatusArray[ x ].ulRunTimeCounter / ulTotalRunTime;
+
+					if( ulStatsAsPercentage > 0UL )
+					{
+						sprintf( pcWriteBuffer, "%s\t\t%lu\t\t%lu%%\r\n", pxTaskStatusArray[ x ].pcTaskName, pxTaskStatusArray[ x ].ulRunTimeCounter, ulStatsAsPercentage );
+					}
+					else
+					{
+						// If the percentage is zero here then the task has
+						// consumed less than 1% of the total run time.
+						sprintf( pcWriteBuffer, "%s\t\t%lu\t\t<1%%\r\n", pxTaskStatusArray[ x ].pcTaskName, pxTaskStatusArray[ x ].ulRunTimeCounter );
+					}
+
+					pcWriteBuffer += strlen( ( char * ) pcWriteBuffer );
+				}
+			}
+
+			// The array is no longer needed, free the memory it consumes.
+			vPortFree( pxTaskStatusArray );
+		}
+	}
+	
+ */ +UBaseType_t uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, const UBaseType_t uxArraySize, uint32_t * const pulTotalRunTime ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskList( char *pcWriteBuffer );
+ * + * configUSE_TRACE_FACILITY and configUSE_STATS_FORMATTING_FUNCTIONS must + * both be defined as 1 for this function to be available. See the + * configuration section of the FreeRTOS.org website for more information. + * + * NOTE 1: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Lists all the current tasks, along with their current state and stack + * usage high water mark. + * + * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or + * suspended ('S'). + * + * PLEASE NOTE: + * + * This function is provided for convenience only, and is used by many of the + * demo applications. Do not consider it to be part of the scheduler. + * + * vTaskList() calls uxTaskGetSystemState(), then formats part of the + * uxTaskGetSystemState() output into a human readable table that displays task + * names, states and stack usage. + * + * vTaskList() has a dependency on the sprintf() C library function that might + * bloat the code size, use a lot of stack, and provide different results on + * different platforms. An alternative, tiny, third party, and limited + * functionality implementation of sprintf() is provided in many of the + * FreeRTOS/Demo sub-directories in a file called printf-stdarg.c (note + * printf-stdarg.c does not provide a full snprintf() implementation!). + * + * It is recommended that production systems call uxTaskGetSystemState() + * directly to get access to raw stats data, rather than indirectly through a + * call to vTaskList(). + * + * @param pcWriteBuffer A buffer into which the above mentioned details + * will be written, in ASCII form. This buffer is assumed to be large + * enough to contain the generated report. Approximately 40 bytes per + * task should be sufficient. + * + * \defgroup vTaskList vTaskList + * \ingroup TaskUtils + */ +void vTaskList( char * pcWriteBuffer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** + * task. h + *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
+ * + * configGENERATE_RUN_TIME_STATS and configUSE_STATS_FORMATTING_FUNCTIONS + * must both be defined as 1 for this function to be available. The application + * must also then provide definitions for + * portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and portGET_RUN_TIME_COUNTER_VALUE() + * to configure a peripheral timer/counter and return the timers current count + * value respectively. The counter should be at least 10 times the frequency of + * the tick count. + * + * NOTE 1: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total + * accumulated execution time being stored for each task. The resolution + * of the accumulated time value depends on the frequency of the timer + * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. + * Calling vTaskGetRunTimeStats() writes the total execution time of each + * task into a buffer, both as an absolute count value and as a percentage + * of the total system execution time. + * + * NOTE 2: + * + * This function is provided for convenience only, and is used by many of the + * demo applications. Do not consider it to be part of the scheduler. + * + * vTaskGetRunTimeStats() calls uxTaskGetSystemState(), then formats part of the + * uxTaskGetSystemState() output into a human readable table that displays the + * amount of time each task has spent in the Running state in both absolute and + * percentage terms. + * + * vTaskGetRunTimeStats() has a dependency on the sprintf() C library function + * that might bloat the code size, use a lot of stack, and provide different + * results on different platforms. An alternative, tiny, third party, and + * limited functionality implementation of sprintf() is provided in many of the + * FreeRTOS/Demo sub-directories in a file called printf-stdarg.c (note + * printf-stdarg.c does not provide a full snprintf() implementation!). + * + * It is recommended that production systems call uxTaskGetSystemState() directly + * to get access to raw stats data, rather than indirectly through a call to + * vTaskGetRunTimeStats(). + * + * @param pcWriteBuffer A buffer into which the execution times will be + * written, in ASCII form. This buffer is assumed to be large enough to + * contain the generated report. Approximately 40 bytes per task should + * be sufficient. + * + * \defgroup vTaskGetRunTimeStats vTaskGetRunTimeStats + * \ingroup TaskUtils + */ +void vTaskGetRunTimeStats( char *pcWriteBuffer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** +* task. h +*
uint32_t ulTaskGetIdleRunTimeCounter( void );
+* +* configGENERATE_RUN_TIME_STATS and configUSE_STATS_FORMATTING_FUNCTIONS +* must both be defined as 1 for this function to be available. The application +* must also then provide definitions for +* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and portGET_RUN_TIME_COUNTER_VALUE() +* to configure a peripheral timer/counter and return the timers current count +* value respectively. The counter should be at least 10 times the frequency of +* the tick count. +* +* Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total +* accumulated execution time being stored for each task. The resolution +* of the accumulated time value depends on the frequency of the timer +* configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. +* While uxTaskGetSystemState() and vTaskGetRunTimeStats() writes the total +* execution time of each task into a buffer, ulTaskGetIdleRunTimeCounter() +* returns the total execution time of just the idle task. +* +* @return The total run time of the idle task. This is the amount of time the +* idle task has actually been executing. The unit of time is dependent on the +* frequency configured using the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and +* portGET_RUN_TIME_COUNTER_VALUE() macros. +* +* \defgroup ulTaskGetIdleRunTimeCounter ulTaskGetIdleRunTimeCounter +* \ingroup TaskUtils +*/ +uint32_t ulTaskGetIdleRunTimeCounter( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this + * function to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * A notification sent to a task will remain pending until it is cleared by the + * task calling xTaskNotifyWait() or ulTaskNotifyTake(). If the task was + * already in the Blocked state to wait for a notification when the notification + * arrives then the task will automatically be removed from the Blocked state + * (unblocked) and the notification cleared. + * + * A task can use xTaskNotifyWait() to [optionally] block to wait for a + * notification to be pending, or ulTaskNotifyTake() to [optionally] block + * to wait for its notification value to have a non-zero value. The task does + * not consume any CPU time while it is in the Blocked state. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details. + * + * @param xTaskToNotify The handle of the task being notified. The handle to a + * task can be returned from the xTaskCreate() API function used to create the + * task, and the handle of the currently running task can be obtained by calling + * xTaskGetCurrentTaskHandle(). + * + * @param ulValue Data that can be sent with the notification. How the data is + * used depends on the value of the eAction parameter. + * + * @param eAction Specifies how the notification updates the task's notification + * value, if at all. Valid values for eAction are as follows: + * + * eSetBits - + * The task's notification value is bitwise ORed with ulValue. xTaskNofify() + * always returns pdPASS in this case. + * + * eIncrement - + * The task's notification value is incremented. ulValue is not used and + * xTaskNotify() always returns pdPASS in this case. + * + * eSetValueWithOverwrite - + * The task's notification value is set to the value of ulValue, even if the + * task being notified had not yet processed the previous notification (the + * task already had a notification pending). xTaskNotify() always returns + * pdPASS in this case. + * + * eSetValueWithoutOverwrite - + * If the task being notified did not already have a notification pending then + * the task's notification value is set to ulValue and xTaskNotify() will + * return pdPASS. If the task being notified already had a notification + * pending then no action is performed and pdFAIL is returned. + * + * eNoAction - + * The task receives a notification without its notification value being + * updated. ulValue is not used and xTaskNotify() always returns pdPASS in + * this case. + * + * pulPreviousNotificationValue - + * Can be used to pass out the subject task's notification value before any + * bits are modified by the notify function. + * + * @return Dependent on the value of eAction. See the description of the + * eAction parameter. + * + * \defgroup xTaskNotify xTaskNotify + * \ingroup TaskNotifications + */ +BaseType_t xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue ) PRIVILEGED_FUNCTION; +#define xTaskNotify( xTaskToNotify, ulValue, eAction ) xTaskGenericNotify( ( xTaskToNotify ), ( ulValue ), ( eAction ), NULL ) +#define xTaskNotifyAndQuery( xTaskToNotify, ulValue, eAction, pulPreviousNotifyValue ) xTaskGenericNotify( ( xTaskToNotify ), ( ulValue ), ( eAction ), ( pulPreviousNotifyValue ) ) + +/** + * task. h + *
BaseType_t xTaskNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, BaseType_t *pxHigherPriorityTaskWoken );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this + * function to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * A version of xTaskNotify() that can be used from an interrupt service routine + * (ISR). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * A notification sent to a task will remain pending until it is cleared by the + * task calling xTaskNotifyWait() or ulTaskNotifyTake(). If the task was + * already in the Blocked state to wait for a notification when the notification + * arrives then the task will automatically be removed from the Blocked state + * (unblocked) and the notification cleared. + * + * A task can use xTaskNotifyWait() to [optionally] block to wait for a + * notification to be pending, or ulTaskNotifyTake() to [optionally] block + * to wait for its notification value to have a non-zero value. The task does + * not consume any CPU time while it is in the Blocked state. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details. + * + * @param xTaskToNotify The handle of the task being notified. The handle to a + * task can be returned from the xTaskCreate() API function used to create the + * task, and the handle of the currently running task can be obtained by calling + * xTaskGetCurrentTaskHandle(). + * + * @param ulValue Data that can be sent with the notification. How the data is + * used depends on the value of the eAction parameter. + * + * @param eAction Specifies how the notification updates the task's notification + * value, if at all. Valid values for eAction are as follows: + * + * eSetBits - + * The task's notification value is bitwise ORed with ulValue. xTaskNofify() + * always returns pdPASS in this case. + * + * eIncrement - + * The task's notification value is incremented. ulValue is not used and + * xTaskNotify() always returns pdPASS in this case. + * + * eSetValueWithOverwrite - + * The task's notification value is set to the value of ulValue, even if the + * task being notified had not yet processed the previous notification (the + * task already had a notification pending). xTaskNotify() always returns + * pdPASS in this case. + * + * eSetValueWithoutOverwrite - + * If the task being notified did not already have a notification pending then + * the task's notification value is set to ulValue and xTaskNotify() will + * return pdPASS. If the task being notified already had a notification + * pending then no action is performed and pdFAIL is returned. + * + * eNoAction - + * The task receives a notification without its notification value being + * updated. ulValue is not used and xTaskNotify() always returns pdPASS in + * this case. + * + * @param pxHigherPriorityTaskWoken xTaskNotifyFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending the notification caused the + * task to which the notification was sent to leave the Blocked state, and the + * unblocked task has a priority higher than the currently running task. If + * xTaskNotifyFromISR() sets this value to pdTRUE then a context switch should + * be requested before the interrupt is exited. How a context switch is + * requested from an ISR is dependent on the port - see the documentation page + * for the port in use. + * + * @return Dependent on the value of eAction. See the description of the + * eAction parameter. + * + * \defgroup xTaskNotify xTaskNotify + * \ingroup TaskNotifications + */ +BaseType_t xTaskGenericNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; +#define xTaskNotifyFromISR( xTaskToNotify, ulValue, eAction, pxHigherPriorityTaskWoken ) xTaskGenericNotifyFromISR( ( xTaskToNotify ), ( ulValue ), ( eAction ), NULL, ( pxHigherPriorityTaskWoken ) ) +#define xTaskNotifyAndQueryFromISR( xTaskToNotify, ulValue, eAction, pulPreviousNotificationValue, pxHigherPriorityTaskWoken ) xTaskGenericNotifyFromISR( ( xTaskToNotify ), ( ulValue ), ( eAction ), ( pulPreviousNotificationValue ), ( pxHigherPriorityTaskWoken ) ) + +/** + * task. h + *
BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this + * function to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * A notification sent to a task will remain pending until it is cleared by the + * task calling xTaskNotifyWait() or ulTaskNotifyTake(). If the task was + * already in the Blocked state to wait for a notification when the notification + * arrives then the task will automatically be removed from the Blocked state + * (unblocked) and the notification cleared. + * + * A task can use xTaskNotifyWait() to [optionally] block to wait for a + * notification to be pending, or ulTaskNotifyTake() to [optionally] block + * to wait for its notification value to have a non-zero value. The task does + * not consume any CPU time while it is in the Blocked state. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details. + * + * @param ulBitsToClearOnEntry Bits that are set in ulBitsToClearOnEntry value + * will be cleared in the calling task's notification value before the task + * checks to see if any notifications are pending, and optionally blocks if no + * notifications are pending. Setting ulBitsToClearOnEntry to ULONG_MAX (if + * limits.h is included) or 0xffffffffUL (if limits.h is not included) will have + * the effect of resetting the task's notification value to 0. Setting + * ulBitsToClearOnEntry to 0 will leave the task's notification value unchanged. + * + * @param ulBitsToClearOnExit If a notification is pending or received before + * the calling task exits the xTaskNotifyWait() function then the task's + * notification value (see the xTaskNotify() API function) is passed out using + * the pulNotificationValue parameter. Then any bits that are set in + * ulBitsToClearOnExit will be cleared in the task's notification value (note + * *pulNotificationValue is set before any bits are cleared). Setting + * ulBitsToClearOnExit to ULONG_MAX (if limits.h is included) or 0xffffffffUL + * (if limits.h is not included) will have the effect of resetting the task's + * notification value to 0 before the function exits. Setting + * ulBitsToClearOnExit to 0 will leave the task's notification value unchanged + * when the function exits (in which case the value passed out in + * pulNotificationValue will match the task's notification value). + * + * @param pulNotificationValue Used to pass the task's notification value out + * of the function. Note the value passed out will not be effected by the + * clearing of any bits caused by ulBitsToClearOnExit being non-zero. + * + * @param xTicksToWait The maximum amount of time that the task should wait in + * the Blocked state for a notification to be received, should a notification + * not already be pending when xTaskNotifyWait() was called. The task + * will not consume any processing time while it is in the Blocked state. This + * is specified in kernel ticks, the macro pdMS_TO_TICSK( value_in_ms ) can be + * used to convert a time specified in milliseconds to a time specified in + * ticks. + * + * @return If a notification was received (including notifications that were + * already pending when xTaskNotifyWait was called) then pdPASS is + * returned. Otherwise pdFAIL is returned. + * + * \defgroup xTaskNotifyWait xTaskNotifyWait + * \ingroup TaskNotifications + */ +BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskNotifyGive( TaskHandle_t xTaskToNotify );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this macro + * to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * xTaskNotifyGive() is a helper macro intended for use when task notifications + * are used as light weight and faster binary or counting semaphore equivalents. + * Actual FreeRTOS semaphores are given using the xSemaphoreGive() API function, + * the equivalent action that instead uses a task notification is + * xTaskNotifyGive(). + * + * When task notifications are being used as a binary or counting semaphore + * equivalent then the task being notified should wait for the notification + * using the ulTaskNotificationTake() API function rather than the + * xTaskNotifyWait() API function. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for more details. + * + * @param xTaskToNotify The handle of the task being notified. The handle to a + * task can be returned from the xTaskCreate() API function used to create the + * task, and the handle of the currently running task can be obtained by calling + * xTaskGetCurrentTaskHandle(). + * + * @return xTaskNotifyGive() is a macro that calls xTaskNotify() with the + * eAction parameter set to eIncrement - so pdPASS is always returned. + * + * \defgroup xTaskNotifyGive xTaskNotifyGive + * \ingroup TaskNotifications + */ +#define xTaskNotifyGive( xTaskToNotify ) xTaskGenericNotify( ( xTaskToNotify ), ( 0 ), eIncrement, NULL ) + +/** + * task. h + *
void vTaskNotifyGiveFromISR( TaskHandle_t xTaskHandle, BaseType_t *pxHigherPriorityTaskWoken );
+ *
+ * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this macro
+ * to be available.
+ *
+ * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private
+ * "notification value", which is a 32-bit unsigned integer (uint32_t).
+ *
+ * A version of xTaskNotifyGive() that can be called from an interrupt service
+ * routine (ISR).
+ *
+ * Events can be sent to a task using an intermediary object.  Examples of such
+ * objects are queues, semaphores, mutexes and event groups.  Task notifications
+ * are a method of sending an event directly to a task without the need for such
+ * an intermediary object.
+ *
+ * A notification sent to a task can optionally perform an action, such as
+ * update, overwrite or increment the task's notification value.  In that way
+ * task notifications can be used to send data to a task, or be used as light
+ * weight and fast binary or counting semaphores.
+ *
+ * vTaskNotifyGiveFromISR() is intended for use when task notifications are
+ * used as light weight and faster binary or counting semaphore equivalents.
+ * Actual FreeRTOS semaphores are given from an ISR using the
+ * xSemaphoreGiveFromISR() API function, the equivalent action that instead uses
+ * a task notification is vTaskNotifyGiveFromISR().
+ *
+ * When task notifications are being used as a binary or counting semaphore
+ * equivalent then the task being notified should wait for the notification
+ * using the ulTaskNotificationTake() API function rather than the
+ * xTaskNotifyWait() API function.
+ *
+ * See http://www.FreeRTOS.org/RTOS-task-notifications.html for more details.
+ *
+ * @param xTaskToNotify The handle of the task being notified.  The handle to a
+ * task can be returned from the xTaskCreate() API function used to create the
+ * task, and the handle of the currently running task can be obtained by calling
+ * xTaskGetCurrentTaskHandle().
+ *
+ * @param pxHigherPriorityTaskWoken  vTaskNotifyGiveFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending the notification caused the
+ * task to which the notification was sent to leave the Blocked state, and the
+ * unblocked task has a priority higher than the currently running task.  If
+ * vTaskNotifyGiveFromISR() sets this value to pdTRUE then a context switch
+ * should be requested before the interrupt is exited.  How a context switch is
+ * requested from an ISR is dependent on the port - see the documentation page
+ * for the port in use.
+ *
+ * \defgroup xTaskNotifyWait xTaskNotifyWait
+ * \ingroup TaskNotifications
+ */
+void vTaskNotifyGiveFromISR( TaskHandle_t xTaskToNotify, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * 
uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this + * function to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * ulTaskNotifyTake() is intended for use when a task notification is used as a + * faster and lighter weight binary or counting semaphore alternative. Actual + * FreeRTOS semaphores are taken using the xSemaphoreTake() API function, the + * equivalent action that instead uses a task notification is + * ulTaskNotifyTake(). + * + * When a task is using its notification value as a binary or counting semaphore + * other tasks should send notifications to it using the xTaskNotifyGive() + * macro, or xTaskNotify() function with the eAction parameter set to + * eIncrement. + * + * ulTaskNotifyTake() can either clear the task's notification value to + * zero on exit, in which case the notification value acts like a binary + * semaphore, or decrement the task's notification value on exit, in which case + * the notification value acts like a counting semaphore. + * + * A task can use ulTaskNotifyTake() to [optionally] block to wait for a + * the task's notification value to be non-zero. The task does not consume any + * CPU time while it is in the Blocked state. + * + * Where as xTaskNotifyWait() will return when a notification is pending, + * ulTaskNotifyTake() will return when the task's notification value is + * not zero. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details. + * + * @param xClearCountOnExit if xClearCountOnExit is pdFALSE then the task's + * notification value is decremented when the function exits. In this way the + * notification value acts like a counting semaphore. If xClearCountOnExit is + * not pdFALSE then the task's notification value is cleared to zero when the + * function exits. In this way the notification value acts like a binary + * semaphore. + * + * @param xTicksToWait The maximum amount of time that the task should wait in + * the Blocked state for the task's notification value to be greater than zero, + * should the count not already be greater than zero when + * ulTaskNotifyTake() was called. The task will not consume any processing + * time while it is in the Blocked state. This is specified in kernel ticks, + * the macro pdMS_TO_TICSK( value_in_ms ) can be used to convert a time + * specified in milliseconds to a time specified in ticks. + * + * @return The task's notification count before it is either cleared to zero or + * decremented (see the xClearCountOnExit parameter). + * + * \defgroup ulTaskNotifyTake ulTaskNotifyTake + * \ingroup TaskNotifications + */ +uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask );
+ * + * If the notification state of the task referenced by the handle xTask is + * eNotified, then set the task's notification state to eNotWaitingNotification. + * The task's notification value is not altered. Set xTask to NULL to clear the + * notification state of the calling task. + * + * @return pdTRUE if the task's notification state was set to + * eNotWaitingNotification, otherwise pdFALSE. + * \defgroup xTaskNotifyStateClear xTaskNotifyStateClear + * \ingroup TaskNotifications + */ +BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask ); + +/** +* task. h +*
uint32_t ulTaskNotifyValueClear( TaskHandle_t xTask, uint32_t ulBitsToClear );
+* +* Clears the bits specified by the ulBitsToClear bit mask in the notification +* value of the task referenced by xTask. +* +* Set ulBitsToClear to 0xffffffff (UINT_MAX on 32-bit architectures) to clear +* the notification value to 0. Set ulBitsToClear to 0 to query the task's +* notification value without clearing any bits. +* +* @return The value of the target task's notification value before the bits +* specified by ulBitsToClear were cleared. +* \defgroup ulTaskNotifyValueClear ulTaskNotifyValueClear +* \ingroup TaskNotifications +*/ +uint32_t ulTaskNotifyValueClear( TaskHandle_t xTask, uint32_t ulBitsToClear ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
void vTaskSetTimeOutState( TimeOut_t * const pxTimeOut )
+ * + * Capture the current time for future use with xTaskCheckForTimeOut(). + * + * @param pxTimeOut Pointer to a timeout object into which the current time + * is to be captured. The captured time includes the tick count and the number + * of times the tick count has overflowed since the system first booted. + * \defgroup vTaskSetTimeOutState vTaskSetTimeOutState + * \ingroup TaskCtrl + */ +void vTaskSetTimeOutState( TimeOut_t * const pxTimeOut ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
BaseType_t xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait );
+ * + * Determines if pxTicksToWait ticks has passed since a time was captured + * using a call to vTaskSetTimeOutState(). The captured time includes the tick + * count and the number of times the tick count has overflowed. + * + * @param pxTimeOut The time status as captured previously using + * vTaskSetTimeOutState. If the timeout has not yet occurred, it is updated + * to reflect the current time status. + * @param pxTicksToWait The number of ticks to check for timeout i.e. if + * pxTicksToWait ticks have passed since pxTimeOut was last updated (either by + * vTaskSetTimeOutState() or xTaskCheckForTimeOut()), the timeout has occurred. + * If the timeout has not occurred, pxTIcksToWait is updated to reflect the + * number of remaining ticks. + * + * @return If timeout has occurred, pdTRUE is returned. Otherwise pdFALSE is + * returned and pxTicksToWait is updated to reflect the number of remaining + * ticks. + * + * @see https://www.freertos.org/xTaskCheckForTimeOut.html + * + * Example Usage: + *
+	// Driver library function used to receive uxWantedBytes from an Rx buffer
+	// that is filled by a UART interrupt. If there are not enough bytes in the
+	// Rx buffer then the task enters the Blocked state until it is notified that
+	// more data has been placed into the buffer. If there is still not enough
+	// data then the task re-enters the Blocked state, and xTaskCheckForTimeOut()
+	// is used to re-calculate the Block time to ensure the total amount of time
+	// spent in the Blocked state does not exceed MAX_TIME_TO_WAIT. This
+	// continues until either the buffer contains at least uxWantedBytes bytes,
+	// or the total amount of time spent in the Blocked state reaches
+	// MAX_TIME_TO_WAIT – at which point the task reads however many bytes are
+	// available up to a maximum of uxWantedBytes.
+
+	size_t xUART_Receive( uint8_t *pucBuffer, size_t uxWantedBytes )
+	{
+	size_t uxReceived = 0;
+	TickType_t xTicksToWait = MAX_TIME_TO_WAIT;
+	TimeOut_t xTimeOut;
+
+		// Initialize xTimeOut.  This records the time at which this function
+		// was entered.
+		vTaskSetTimeOutState( &xTimeOut );
+
+		// Loop until the buffer contains the wanted number of bytes, or a
+		// timeout occurs.
+		while( UART_bytes_in_rx_buffer( pxUARTInstance ) < uxWantedBytes )
+		{
+			// The buffer didn't contain enough data so this task is going to
+			// enter the Blocked state. Adjusting xTicksToWait to account for
+			// any time that has been spent in the Blocked state within this
+			// function so far to ensure the total amount of time spent in the
+			// Blocked state does not exceed MAX_TIME_TO_WAIT.
+			if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) != pdFALSE )
+			{
+				//Timed out before the wanted number of bytes were available,
+				// exit the loop.
+				break;
+			}
+
+			// Wait for a maximum of xTicksToWait ticks to be notified that the
+			// receive interrupt has placed more data into the buffer.
+			ulTaskNotifyTake( pdTRUE, xTicksToWait );
+		}
+
+		// Attempt to read uxWantedBytes from the receive buffer into pucBuffer.
+		// The actual number of bytes read (which might be less than
+		// uxWantedBytes) is returned.
+		uxReceived = UART_read_from_receive_buffer( pxUARTInstance,
+													pucBuffer,
+													uxWantedBytes );
+
+		return uxReceived;
+	}
+ 
+ * \defgroup xTaskCheckForTimeOut xTaskCheckForTimeOut + * \ingroup TaskCtrl + */ +BaseType_t xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + *----------------------------------------------------------*/ + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Called from the real time kernel tick (either preemptive or cooperative), + * this increments the tick count and checks if any tasks that are blocked + * for a finite period required removing from a blocked list and placing on + * a ready list. If a non-zero value is returned then a context switch is + * required because either: + * + A task was removed from a blocked list because its timeout had expired, + * or + * + Time slicing is in use and there is a task of equal priority to the + * currently running task. + */ +BaseType_t xTaskIncrementTick( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes the calling task from the ready list and places it both + * on the list of tasks waiting for a particular event, and the + * list of delayed tasks. The task will be removed from both lists + * and replaced on the ready list should either the event occur (and + * there be no higher priority tasks waiting on the same event) or + * the delay period expires. + * + * The 'unordered' version replaces the event list item value with the + * xItemValue value, and inserts the list item at the end of the list. + * + * The 'ordered' version uses the existing event list item value (which is the + * owning tasks priority) to insert the list item into the event list is task + * priority order. + * + * @param pxEventList The list containing tasks that are blocked waiting + * for the event to occur. + * + * @param xItemValue The item value to use for the event list item when the + * event list is not ordered by task priority. + * + * @param xTicksToWait The maximum amount of time that the task should wait + * for the event to occur. This is specified in kernel ticks,the constant + * portTICK_PERIOD_MS can be used to convert kernel ticks into a real time + * period. + */ +void vTaskPlaceOnEventList( List_t * const pxEventList, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; +void vTaskPlaceOnUnorderedEventList( List_t * pxEventList, const TickType_t xItemValue, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * This function performs nearly the same function as vTaskPlaceOnEventList(). + * The difference being that this function does not permit tasks to block + * indefinitely, whereas vTaskPlaceOnEventList() does. + * + */ +void vTaskPlaceOnEventListRestricted( List_t * const pxEventList, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes a task from both the specified event list and the list of blocked + * tasks, and places it on a ready queue. + * + * xTaskRemoveFromEventList()/vTaskRemoveFromUnorderedEventList() will be called + * if either an event occurs to unblock a task, or the block timeout period + * expires. + * + * xTaskRemoveFromEventList() is used when the event list is in task priority + * order. It removes the list item from the head of the event list as that will + * have the highest priority owning task of all the tasks on the event list. + * vTaskRemoveFromUnorderedEventList() is used when the event list is not + * ordered and the event list items hold something other than the owning tasks + * priority. In this case the event list item value is updated to the value + * passed in the xItemValue parameter. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +BaseType_t xTaskRemoveFromEventList( const List_t * const pxEventList ) PRIVILEGED_FUNCTION; +void vTaskRemoveFromUnorderedEventList( ListItem_t * pxEventListItem, const TickType_t xItemValue ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Sets the pointer to the current TCB to the TCB of the highest priority task + * that is ready to run. + */ +portDONT_DISCARD void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; + +/* + * THESE FUNCTIONS MUST NOT BE USED FROM APPLICATION CODE. THEY ARE USED BY + * THE EVENT BITS MODULE. + */ +TickType_t uxTaskResetEventItemValue( void ) PRIVILEGED_FUNCTION; + +/* + * Return the handle of the calling task. + */ +TaskHandle_t xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; + +/* + * Shortcut used by the queue implementation to prevent unnecessary call to + * taskYIELD(); + */ +void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; + +/* + * Returns the scheduler state as taskSCHEDULER_RUNNING, + * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. + */ +BaseType_t xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; + +/* + * Raises the priority of the mutex holder to that of the calling task should + * the mutex holder have a priority less than the calling task. + */ +BaseType_t xTaskPriorityInherit( TaskHandle_t const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Set the priority of a task back to its proper priority in the case that it + * inherited a higher priority while it was holding a semaphore. + */ +BaseType_t xTaskPriorityDisinherit( TaskHandle_t const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * If a higher priority task attempting to obtain a mutex caused a lower + * priority task to inherit the higher priority task's priority - but the higher + * priority task then timed out without obtaining the mutex, then the lower + * priority task will disinherit the priority again - but only down as far as + * the highest priority task that is still waiting for the mutex (if there were + * more than one task waiting for the mutex). + */ +void vTaskPriorityDisinheritAfterTimeout( TaskHandle_t const pxMutexHolder, UBaseType_t uxHighestPriorityWaitingTask ) PRIVILEGED_FUNCTION; + +/* + * Get the uxTCBNumber assigned to the task referenced by the xTask parameter. + */ +UBaseType_t uxTaskGetTaskNumber( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/* + * Set the uxTaskNumber of the task referenced by the xTask parameter to + * uxHandle. + */ +void vTaskSetTaskNumber( TaskHandle_t xTask, const UBaseType_t uxHandle ) PRIVILEGED_FUNCTION; + +/* + * Only available when configUSE_TICKLESS_IDLE is set to 1. + * If tickless mode is being used, or a low power mode is implemented, then + * the tick interrupt will not execute during idle periods. When this is the + * case, the tick count value maintained by the scheduler needs to be kept up + * to date with the actual execution time by being skipped forward by a time + * equal to the idle period. + */ +void vTaskStepTick( const TickType_t xTicksToJump ) PRIVILEGED_FUNCTION; + +/* Correct the tick count value after the application code has held +interrupts disabled for an extended period. xTicksToCatchUp is the number +of tick interrupts that have been missed due to interrupts being disabled. +Its value is not computed automatically, so must be computed by the +application writer. + +This function is similar to vTaskStepTick(), however, unlike +vTaskStepTick(), xTaskCatchUpTicks() may move the tick count forward past a +time at which a task should be removed from the blocked state. That means +tasks may have to be removed from the blocked state as the tick count is +moved. */ +BaseType_t xTaskCatchUpTicks( TickType_t xTicksToCatchUp ) PRIVILEGED_FUNCTION; + +/* + * Only available when configUSE_TICKLESS_IDLE is set to 1. + * Provided for use within portSUPPRESS_TICKS_AND_SLEEP() to allow the port + * specific sleep function to determine if it is ok to proceed with the sleep, + * and if it is ok to proceed, if it is ok to sleep indefinitely. + * + * This function is necessary because portSUPPRESS_TICKS_AND_SLEEP() is only + * called with the scheduler suspended, not from within a critical section. It + * is therefore possible for an interrupt to request a context switch between + * portSUPPRESS_TICKS_AND_SLEEP() and the low power mode actually being + * entered. eTaskConfirmSleepModeStatus() should be called from a short + * critical section between the timer being stopped and the sleep mode being + * entered to ensure it is ok to proceed into the sleep mode. + */ +eSleepModeStatus eTaskConfirmSleepModeStatus( void ) PRIVILEGED_FUNCTION; + +/* + * For internal use only. Increment the mutex held count when a mutex is + * taken and return the handle of the task that has taken the mutex. + */ +TaskHandle_t pvTaskIncrementMutexHeldCount( void ) PRIVILEGED_FUNCTION; + +/* + * For internal use only. Same as vTaskSetTimeOutState(), but without a critial + * section. + */ +void vTaskInternalSetTimeOutState( TimeOut_t * const pxTimeOut ) PRIVILEGED_FUNCTION; + + +#ifdef __cplusplus +} +#endif +#endif /* INC_TASK_H */ + + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/timers.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/timers.h new file mode 100644 index 0000000..210b011 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/include/timers.h @@ -0,0 +1,1309 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 TIMERS_H +#define TIMERS_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include timers.h" +#endif + +/*lint -save -e537 This headers are only multiply included if the application code +happens to also be including task.h. */ +#include "task.h" +/*lint -restore */ + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +/* IDs for commands that can be sent/received on the timer queue. These are to +be used solely through the macros that make up the public software timer API, +as defined below. The commands that are sent from interrupts must use the +highest numbers as tmrFIRST_FROM_ISR_COMMAND is used to determine if the task +or interrupt version of the queue send function should be used. */ +#define tmrCOMMAND_EXECUTE_CALLBACK_FROM_ISR ( ( BaseType_t ) -2 ) +#define tmrCOMMAND_EXECUTE_CALLBACK ( ( BaseType_t ) -1 ) +#define tmrCOMMAND_START_DONT_TRACE ( ( BaseType_t ) 0 ) +#define tmrCOMMAND_START ( ( BaseType_t ) 1 ) +#define tmrCOMMAND_RESET ( ( BaseType_t ) 2 ) +#define tmrCOMMAND_STOP ( ( BaseType_t ) 3 ) +#define tmrCOMMAND_CHANGE_PERIOD ( ( BaseType_t ) 4 ) +#define tmrCOMMAND_DELETE ( ( BaseType_t ) 5 ) + +#define tmrFIRST_FROM_ISR_COMMAND ( ( BaseType_t ) 6 ) +#define tmrCOMMAND_START_FROM_ISR ( ( BaseType_t ) 6 ) +#define tmrCOMMAND_RESET_FROM_ISR ( ( BaseType_t ) 7 ) +#define tmrCOMMAND_STOP_FROM_ISR ( ( BaseType_t ) 8 ) +#define tmrCOMMAND_CHANGE_PERIOD_FROM_ISR ( ( BaseType_t ) 9 ) + + +/** + * Type by which software timers are referenced. For example, a call to + * xTimerCreate() returns an TimerHandle_t variable that can then be used to + * reference the subject timer in calls to other software timer API functions + * (for example, xTimerStart(), xTimerReset(), etc.). + */ +struct tmrTimerControl; /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +typedef struct tmrTimerControl * TimerHandle_t; + +/* + * Defines the prototype to which timer callback functions must conform. + */ +typedef void (*TimerCallbackFunction_t)( TimerHandle_t xTimer ); + +/* + * Defines the prototype to which functions used with the + * xTimerPendFunctionCallFromISR() function must conform. + */ +typedef void (*PendedFunction_t)( void *, uint32_t ); + +/** + * TimerHandle_t xTimerCreate( const char * const pcTimerName, + * TickType_t xTimerPeriodInTicks, + * UBaseType_t uxAutoReload, + * void * pvTimerID, + * TimerCallbackFunction_t pxCallbackFunction ); + * + * Creates a new software timer instance, and returns a handle by which the + * created software timer can be referenced. + * + * Internally, within the FreeRTOS implementation, software timers use a block + * of memory, in which the timer data structure is stored. If a software timer + * is created using xTimerCreate() then the required memory is automatically + * dynamically allocated inside the xTimerCreate() function. (see + * http://www.freertos.org/a00111.html). If a software timer is created using + * xTimerCreateStatic() then the application writer must provide the memory that + * will get used by the software timer. xTimerCreateStatic() therefore allows a + * software timer to be created without using any dynamic memory allocation. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a + * timer into the active state. + * + * @param pcTimerName A text name that is assigned to the timer. This is done + * purely to assist debugging. The kernel itself only ever references a timer + * by its handle, and never by its name. + * + * @param xTimerPeriodInTicks The timer period. The time is defined in tick + * periods so the constant portTICK_PERIOD_MS can be used to convert a time that + * has been specified in milliseconds. For example, if the timer must expire + * after 100 ticks, then xTimerPeriodInTicks should be set to 100. + * Alternatively, if the timer must expire after 500ms, then xPeriod can be set + * to ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than or + * equal to 1000. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. + * If uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + * + * @param pvTimerID An identifier that is assigned to the timer being created. + * Typically this would be used in the timer callback function to identify which + * timer expired when the same callback function is assigned to more than one + * timer. + * + * @param pxCallbackFunction The function to call when the timer expires. + * Callback functions must have the prototype defined by TimerCallbackFunction_t, + * which is "void vCallbackFunction( TimerHandle_t xTimer );". + * + * @return If the timer is successfully created then a handle to the newly + * created timer is returned. If the timer cannot be created (because either + * there is insufficient FreeRTOS heap remaining to allocate the timer + * structures, or the timer period was set to 0) then NULL is returned. + * + * Example usage: + * @verbatim + * #define NUM_TIMERS 5 + * + * // An array to hold handles to the created timers. + * TimerHandle_t xTimers[ NUM_TIMERS ]; + * + * // An array to hold a count of the number of times each timer expires. + * int32_t lExpireCounters[ NUM_TIMERS ] = { 0 }; + * + * // Define a callback function that will be used by multiple timer instances. + * // The callback function does nothing but count the number of times the + * // associated timer expires, and stop the timer once the timer has expired + * // 10 times. + * void vTimerCallback( TimerHandle_t pxTimer ) + * { + * int32_t lArrayIndex; + * const int32_t xMaxExpiryCountBeforeStopping = 10; + * + * // Optionally do something if the pxTimer parameter is NULL. + * configASSERT( pxTimer ); + * + * // Which timer expired? + * lArrayIndex = ( int32_t ) pvTimerGetTimerID( pxTimer ); + * + * // Increment the number of times that pxTimer has expired. + * lExpireCounters[ lArrayIndex ] += 1; + * + * // If the timer has expired 10 times then stop it from running. + * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) + * { + * // Do not use a block time if calling a timer API function from a + * // timer callback function, as doing so could cause a deadlock! + * xTimerStop( pxTimer, 0 ); + * } + * } + * + * void main( void ) + * { + * int32_t x; + * + * // Create then start some timers. Starting the timers before the scheduler + * // has been started means the timers will start running immediately that + * // the scheduler starts. + * for( x = 0; x < NUM_TIMERS; x++ ) + * { + * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. + * ( 100 * x ), // The timer period in ticks. + * pdTRUE, // The timers will auto-reload themselves when they expire. + * ( void * ) x, // Assign each timer a unique id equal to its array index. + * vTimerCallback // Each timer calls the same callback when it expires. + * ); + * + * if( xTimers[ x ] == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timers running as they have already + * // been set into the active state. + * vTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + * @endverbatim + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + TimerHandle_t xTimerCreate( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction ) PRIVILEGED_FUNCTION; +#endif + +/** + * TimerHandle_t xTimerCreateStatic(const char * const pcTimerName, + * TickType_t xTimerPeriodInTicks, + * UBaseType_t uxAutoReload, + * void * pvTimerID, + * TimerCallbackFunction_t pxCallbackFunction, + * StaticTimer_t *pxTimerBuffer ); + * + * Creates a new software timer instance, and returns a handle by which the + * created software timer can be referenced. + * + * Internally, within the FreeRTOS implementation, software timers use a block + * of memory, in which the timer data structure is stored. If a software timer + * is created using xTimerCreate() then the required memory is automatically + * dynamically allocated inside the xTimerCreate() function. (see + * http://www.freertos.org/a00111.html). If a software timer is created using + * xTimerCreateStatic() then the application writer must provide the memory that + * will get used by the software timer. xTimerCreateStatic() therefore allows a + * software timer to be created without using any dynamic memory allocation. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a + * timer into the active state. + * + * @param pcTimerName A text name that is assigned to the timer. This is done + * purely to assist debugging. The kernel itself only ever references a timer + * by its handle, and never by its name. + * + * @param xTimerPeriodInTicks The timer period. The time is defined in tick + * periods so the constant portTICK_PERIOD_MS can be used to convert a time that + * has been specified in milliseconds. For example, if the timer must expire + * after 100 ticks, then xTimerPeriodInTicks should be set to 100. + * Alternatively, if the timer must expire after 500ms, then xPeriod can be set + * to ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than or + * equal to 1000. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. + * If uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + * + * @param pvTimerID An identifier that is assigned to the timer being created. + * Typically this would be used in the timer callback function to identify which + * timer expired when the same callback function is assigned to more than one + * timer. + * + * @param pxCallbackFunction The function to call when the timer expires. + * Callback functions must have the prototype defined by TimerCallbackFunction_t, + * which is "void vCallbackFunction( TimerHandle_t xTimer );". + * + * @param pxTimerBuffer Must point to a variable of type StaticTimer_t, which + * will be then be used to hold the software timer's data structures, removing + * the need for the memory to be allocated dynamically. + * + * @return If the timer is created then a handle to the created timer is + * returned. If pxTimerBuffer was NULL then NULL is returned. + * + * Example usage: + * @verbatim + * + * // The buffer used to hold the software timer's data structure. + * static StaticTimer_t xTimerBuffer; + * + * // A variable that will be incremented by the software timer's callback + * // function. + * UBaseType_t uxVariableToIncrement = 0; + * + * // A software timer callback function that increments a variable passed to + * // it when the software timer was created. After the 5th increment the + * // callback function stops the software timer. + * static void prvTimerCallback( TimerHandle_t xExpiredTimer ) + * { + * UBaseType_t *puxVariableToIncrement; + * BaseType_t xReturned; + * + * // Obtain the address of the variable to increment from the timer ID. + * puxVariableToIncrement = ( UBaseType_t * ) pvTimerGetTimerID( xExpiredTimer ); + * + * // Increment the variable to show the timer callback has executed. + * ( *puxVariableToIncrement )++; + * + * // If this callback has executed the required number of times, stop the + * // timer. + * if( *puxVariableToIncrement == 5 ) + * { + * // This is called from a timer callback so must not block. + * xTimerStop( xExpiredTimer, staticDONT_BLOCK ); + * } + * } + * + * + * void main( void ) + * { + * // Create the software time. xTimerCreateStatic() has an extra parameter + * // than the normal xTimerCreate() API function. The parameter is a pointer + * // to the StaticTimer_t structure that will hold the software timer + * // structure. If the parameter is passed as NULL then the structure will be + * // allocated dynamically, just as if xTimerCreate() had been called. + * xTimer = xTimerCreateStatic( "T1", // Text name for the task. Helps debugging only. Not used by FreeRTOS. + * xTimerPeriod, // The period of the timer in ticks. + * pdTRUE, // This is an auto-reload timer. + * ( void * ) &uxVariableToIncrement, // A variable incremented by the software timer's callback function + * prvTimerCallback, // The function to execute when the timer expires. + * &xTimerBuffer ); // The buffer that will hold the software timer structure. + * + * // The scheduler has not started yet so a block time is not used. + * xReturned = xTimerStart( xTimer, 0 ); + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timers running as they have already + * // been set into the active state. + * vTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + * @endverbatim + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + TimerHandle_t xTimerCreateStatic( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction, + StaticTimer_t *pxTimerBuffer ) PRIVILEGED_FUNCTION; +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * void *pvTimerGetTimerID( TimerHandle_t xTimer ); + * + * Returns the ID assigned to the timer. + * + * IDs are assigned to timers using the pvTimerID parameter of the call to + * xTimerCreated() that was used to create the timer, and by calling the + * vTimerSetTimerID() API function. + * + * If the same callback function is assigned to multiple timers then the timer + * ID can be used as time specific (timer local) storage. + * + * @param xTimer The timer being queried. + * + * @return The ID assigned to the timer being queried. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + */ +void *pvTimerGetTimerID( const TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/** + * void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ); + * + * Sets the ID assigned to the timer. + * + * IDs are assigned to timers using the pvTimerID parameter of the call to + * xTimerCreated() that was used to create the timer. + * + * If the same callback function is assigned to multiple timers then the timer + * ID can be used as time specific (timer local) storage. + * + * @param xTimer The timer being updated. + * + * @param pvNewID The ID to assign to the timer. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + */ +void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ) PRIVILEGED_FUNCTION; + +/** + * BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer ); + * + * Queries a timer to see if it is active or dormant. + * + * A timer will be dormant if: + * 1) It has been created but not started, or + * 2) It is an expired one-shot timer that has not been restarted. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param xTimer The timer being queried. + * + * @return pdFALSE will be returned if the timer is dormant. A value other than + * pdFALSE will be returned if the timer is active. + * + * Example usage: + * @verbatim + * // This function assumes xTimer has already been created. + * void vAFunction( TimerHandle_t xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is active, do something. + * } + * else + * { + * // xTimer is not active, do something else. + * } + * } + * @endverbatim + */ +BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/** + * TaskHandle_t xTimerGetTimerDaemonTaskHandle( void ); + * + * Simply returns the handle of the timer service/daemon task. It it not valid + * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. + */ +TaskHandle_t xTimerGetTimerDaemonTaskHandle( void ) PRIVILEGED_FUNCTION; + +/** + * BaseType_t xTimerStart( TimerHandle_t xTimer, TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStart() starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerStart() has equivalent functionality + * to the xTimerReset() API function. + * + * Starting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerStart() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerStart() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerStart() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() + * to be available. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the start command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStart() was called. xTicksToWait is ignored if xTimerStart() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue even after xTicksToWait ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStart( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerStop( TimerHandle_t xTimer, TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStop() stops a timer that was previously started using either of the + * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), + * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. + * + * Stopping a timer ensures the timer is not in the active state. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() + * to be available. + * + * @param xTimer The handle of the timer being stopped. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the stop command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStop() was called. xTicksToWait is ignored if xTimerStop() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue even after xTicksToWait ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStop( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerChangePeriod( TimerHandle_t xTimer, + * TickType_t xNewPeriod, + * TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerChangePeriod() changes the period of a timer that was previously + * created using the xTimerCreate() API function. + * + * xTimerChangePeriod() can be called to change the period of an active or + * dormant state timer. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerChangePeriod() to be available. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_PERIOD_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the change period command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerChangePeriod() was called. xTicksToWait is ignored if + * xTimerChangePeriod() is called before the scheduler is started. + * + * @return pdFAIL will be returned if the change period command could not be + * sent to the timer command queue even after xTicksToWait ticks had passed. + * pdPASS will be returned if the command was successfully sent to the timer + * command queue. When the command is actually processed will depend on the + * priority of the timer service/daemon task relative to other tasks in the + * system. The timer service/daemon task priority is set by the + * configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * @verbatim + * // This function assumes xTimer has already been created. If the timer + * // referenced by xTimer is already active when it is called, then the timer + * // is deleted. If the timer referenced by xTimer is not active when it is + * // called, then the period of the timer is set to 500ms and the timer is + * // started. + * void vAFunction( TimerHandle_t xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is already active - delete it. + * xTimerDelete( xTimer ); + * } + * else + * { + * // xTimer is not active, change its period to 500ms. This will also + * // cause the timer to start. Block for a maximum of 100 ticks if the + * // change period command cannot immediately be sent to the timer + * // command queue. + * if( xTimerChangePeriod( xTimer, 500 / portTICK_PERIOD_MS, 100 ) == pdPASS ) + * { + * // The command was successfully sent. + * } + * else + * { + * // The command could not be sent, even after waiting for 100 ticks + * // to pass. Take appropriate action here. + * } + * } + * } + * @endverbatim + */ + #define xTimerChangePeriod( xTimer, xNewPeriod, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerDelete( TimerHandle_t xTimer, TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerDelete() deletes a timer that was previously created using the + * xTimerCreate() API function. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerDelete() to be available. + * + * @param xTimer The handle of the timer being deleted. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the delete command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerDelete() was called. xTicksToWait is ignored if xTimerDelete() + * is called before the scheduler is started. + * + * @return pdFAIL will be returned if the delete command could not be sent to + * the timer command queue even after xTicksToWait ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerChangePeriod() API function example usage scenario. + */ +#define xTimerDelete( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerReset( TimerHandle_t xTimer, TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerReset() re-starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerReset() will cause the timer to + * re-evaluate its expiry time so that it is relative to when xTimerReset() was + * called. If the timer was in the dormant state then xTimerReset() has + * equivalent functionality to the xTimerStart() API function. + * + * Resetting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerReset() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerReset() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerReset() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() + * to be available. + * + * @param xTimer The handle of the timer being reset/started/restarted. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the reset command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerReset() was called. xTicksToWait is ignored if xTimerReset() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue even after xTicksToWait ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * @verbatim + * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer. + * + * TimerHandle_t xBacklightTimer = NULL; + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( TimerHandle_t pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press event handler. + * void vKeyPressEventHandler( char cKey ) + * { + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. Wait 10 ticks for the command to be successfully sent + * // if it cannot be sent immediately. + * vSetBacklightState( BACKLIGHT_ON ); + * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * } + * + * void main( void ) + * { + * int32_t x; + * + * // Create then start the one-shot timer that is responsible for turning + * // the back-light off if no keys are pressed within a 5 second period. + * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. + * ( 5000 / portTICK_PERIOD_MS), // The timer period in ticks. + * pdFALSE, // The timer is a one-shot timer. + * 0, // The id is not used by the callback so can take any value. + * vBacklightTimerCallback // The callback function that switches the LCD back-light off. + * ); + * + * if( xBacklightTimer == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timer running as it has already + * // been set into the active state. + * vTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + * @endverbatim + */ +#define xTimerReset( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_RESET, ( xTaskGetTickCount() ), NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerStartFromISR( TimerHandle_t xTimer, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStart() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStartFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStartFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStartFromISR() function. If + * xTimerStartFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerStartFromISR() is actually called. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * @verbatim + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( TimerHandle_t pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * BaseType_t xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then restart the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The start command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used). + * } + * } + * @endverbatim + */ +#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START_FROM_ISR, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * BaseType_t xTimerStopFromISR( TimerHandle_t xTimer, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStop() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being stopped. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStopFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStopFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStopFromISR() function. If + * xTimerStopFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * @verbatim + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the timer should be simply stopped. + * + * // The interrupt service routine that stops the timer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * BaseType_t xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - simply stop the timer. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The stop command was not executed successfully. Take appropriate + * // action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used). + * } + * } + * @endverbatim + */ +#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP_FROM_ISR, 0, ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * BaseType_t xTimerChangePeriodFromISR( TimerHandle_t xTimer, + * TickType_t xNewPeriod, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * A version of xTimerChangePeriod() that can be called from an interrupt + * service routine. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_PERIOD_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerChangePeriodFromISR() writes a message to the + * timer command queue, so has the potential to transition the timer service/ + * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() + * causes the timer service/daemon task to leave the Blocked state, and the + * timer service/daemon task has a priority equal to or greater than the + * currently executing task (the task that was interrupted), then + * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the + * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets + * this value to pdTRUE then a context switch should be performed before the + * interrupt exits. + * + * @return pdFAIL will be returned if the command to change the timers period + * could not be sent to the timer command queue. pdPASS will be returned if the + * command was successfully sent to the timer command queue. When the command + * is actually processed will depend on the priority of the timer service/daemon + * task relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * @verbatim + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the period of xTimer should be changed to 500ms. + * + * // The interrupt service routine that changes the period of xTimer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * BaseType_t xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - change the period of xTimer to 500ms. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The command to change the timers period was not executed + * // successfully. Take appropriate action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used). + * } + * } + * @endverbatim + */ +#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD_FROM_ISR, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * BaseType_t xTimerResetFromISR( TimerHandle_t xTimer, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * A version of xTimerReset() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer that is to be started, reset, or + * restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerResetFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerResetFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerResetFromISR() function. If + * xTimerResetFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerResetFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * @verbatim + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( TimerHandle_t pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * BaseType_t xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used). + * } + * } + * @endverbatim + */ +#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_RESET_FROM_ISR, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + + +/** + * BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend, + * void *pvParameter1, + * uint32_t ulParameter2, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * + * Used from application interrupt service routines to defer the execution of a + * function to the RTOS daemon task (the timer service task, hence this function + * is implemented in timers.c and is prefixed with 'Timer'). + * + * Ideally an interrupt service routine (ISR) is kept as short as possible, but + * sometimes an ISR either has a lot of processing to do, or needs to perform + * processing that is not deterministic. In these cases + * xTimerPendFunctionCallFromISR() can be used to defer processing of a function + * to the RTOS daemon task. + * + * A mechanism is provided that allows the interrupt to return directly to the + * task that will subsequently execute the pended callback function. This + * allows the callback function to execute contiguously in time with the + * interrupt - just as if the callback had executed in the interrupt itself. + * + * @param xFunctionToPend The function to execute from the timer service/ + * daemon task. The function must conform to the PendedFunction_t + * prototype. + * + * @param pvParameter1 The value of the callback function's first parameter. + * The parameter has a void * type to allow it to be used to pass any type. + * For example, unsigned longs can be cast to a void *, or the void * can be + * used to point to a structure. + * + * @param ulParameter2 The value of the callback function's second parameter. + * + * @param pxHigherPriorityTaskWoken As mentioned above, calling this function + * will result in a message being sent to the timer daemon task. If the + * priority of the timer daemon task (which is set using + * configTIMER_TASK_PRIORITY in FreeRTOSConfig.h) is higher than the priority of + * the currently running task (the task the interrupt interrupted) then + * *pxHigherPriorityTaskWoken will be set to pdTRUE within + * xTimerPendFunctionCallFromISR(), indicating that a context switch should be + * requested before the interrupt exits. For that reason + * *pxHigherPriorityTaskWoken must be initialised to pdFALSE. See the + * example code below. + * + * @return pdPASS is returned if the message was successfully sent to the + * timer daemon task, otherwise pdFALSE is returned. + * + * Example usage: + * @verbatim + * + * // The callback function that will execute in the context of the daemon task. + * // Note callback functions must all use this same prototype. + * void vProcessInterface( void *pvParameter1, uint32_t ulParameter2 ) + * { + * BaseType_t xInterfaceToService; + * + * // The interface that requires servicing is passed in the second + * // parameter. The first parameter is not used in this case. + * xInterfaceToService = ( BaseType_t ) ulParameter2; + * + * // ...Perform the processing here... + * } + * + * // An ISR that receives data packets from multiple interfaces + * void vAnISR( void ) + * { + * BaseType_t xInterfaceToService, xHigherPriorityTaskWoken; + * + * // Query the hardware to determine which interface needs processing. + * xInterfaceToService = prvCheckInterfaces(); + * + * // The actual processing is to be deferred to a task. Request the + * // vProcessInterface() callback function is executed, passing in the + * // number of the interface that needs processing. The interface to + * // service is passed in the second parameter. The first parameter is + * // not used in this case. + * xHigherPriorityTaskWoken = pdFALSE; + * xTimerPendFunctionCallFromISR( vProcessInterface, NULL, ( uint32_t ) xInterfaceToService, &xHigherPriorityTaskWoken ); + * + * // If xHigherPriorityTaskWoken is now set to pdTRUE then a context + * // switch should be requested. The macro used is port specific and will + * // be either portYIELD_FROM_ISR() or portEND_SWITCHING_ISR() - refer to + * // the documentation page for the port being used. + * portYIELD_FROM_ISR( xHigherPriorityTaskWoken ); + * + * } + * @endverbatim + */ +BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + + /** + * BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, + * void *pvParameter1, + * uint32_t ulParameter2, + * TickType_t xTicksToWait ); + * + * + * Used to defer the execution of a function to the RTOS daemon task (the timer + * service task, hence this function is implemented in timers.c and is prefixed + * with 'Timer'). + * + * @param xFunctionToPend The function to execute from the timer service/ + * daemon task. The function must conform to the PendedFunction_t + * prototype. + * + * @param pvParameter1 The value of the callback function's first parameter. + * The parameter has a void * type to allow it to be used to pass any type. + * For example, unsigned longs can be cast to a void *, or the void * can be + * used to point to a structure. + * + * @param ulParameter2 The value of the callback function's second parameter. + * + * @param xTicksToWait Calling this function will result in a message being + * sent to the timer daemon task on a queue. xTicksToWait is the amount of + * time the calling task should remain in the Blocked state (so not using any + * processing time) for space to become available on the timer queue if the + * queue is found to be full. + * + * @return pdPASS is returned if the message was successfully sent to the + * timer daemon task, otherwise pdFALSE is returned. + * + */ +BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * const char * const pcTimerGetName( TimerHandle_t xTimer ); + * + * Returns the name that was assigned to a timer when the timer was created. + * + * @param xTimer The handle of the timer being queried. + * + * @return The name assigned to the timer specified by the xTimer parameter. + */ +const char * pcTimerGetName( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** + * void vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ); + * + * Updates a timer to be either an auto-reload timer, in which case the timer + * automatically resets itself each time it expires, or a one-shot timer, in + * which case the timer will only expire once unless it is manually restarted. + * + * @param xTimer The handle of the timer being updated. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the timer's period (see the + * xTimerPeriodInTicks parameter of the xTimerCreate() API function). If + * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + */ +void vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ) PRIVILEGED_FUNCTION; + +/** +* UBaseType_t uxTimerGetReloadMode( TimerHandle_t xTimer ); +* +* Queries a timer to determine if it is an auto-reload timer, in which case the timer +* automatically resets itself each time it expires, or a one-shot timer, in +* which case the timer will only expire once unless it is manually restarted. +* +* @param xTimer The handle of the timer being queried. +* +* @return If the timer is an auto-reload timer then pdTRUE is returned, otherwise +* pdFALSE is returned. +*/ +UBaseType_t uxTimerGetReloadMode( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/** + * TickType_t xTimerGetPeriod( TimerHandle_t xTimer ); + * + * Returns the period of a timer. + * + * @param xTimer The handle of the timer being queried. + * + * @return The period of the timer in ticks. + */ +TickType_t xTimerGetPeriod( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/** +* TickType_t xTimerGetExpiryTime( TimerHandle_t xTimer ); +* +* Returns the time in ticks at which the timer will expire. If this is less +* than the current tick count then the expiry time has overflowed from the +* current time. +* +* @param xTimer The handle of the timer being queried. +* +* @return If the timer is running then the time in ticks at which the timer +* will next expire is returned. If the timer is not running then the return +* value is undefined. +*/ +TickType_t xTimerGetExpiryTime( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/* + * Functions beyond this part are not part of the public API and are intended + * for use by the kernel only. + */ +BaseType_t xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; +BaseType_t xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +#if( configUSE_TRACE_FACILITY == 1 ) + void vTimerSetTimerNumber( TimerHandle_t xTimer, UBaseType_t uxTimerNumber ) PRIVILEGED_FUNCTION; + UBaseType_t uxTimerGetTimerNumber( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif +#endif /* TIMERS_H */ + + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/list.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/list.c new file mode 100644 index 0000000..a293e31 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/list.c @@ -0,0 +1,198 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + + +#include +#include "FreeRTOS.h" +#include "list.h" + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +void vListInitialise( List_t * const pxList ) +{ + /* The list structure contains a list item which is used to mark the + end of the list. To initialise the list the list end is inserted + as the only list entry. */ + pxList->pxIndex = ( ListItem_t * ) &( pxList->xListEnd ); /*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. */ + + /* The list end value is the highest possible value in the list to + ensure it remains at the end of the list. */ + pxList->xListEnd.xItemValue = portMAX_DELAY; + + /* The list end next and previous pointers point to itself so we know + when the list is empty. */ + pxList->xListEnd.pxNext = ( ListItem_t * ) &( pxList->xListEnd ); /*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. */ + pxList->xListEnd.pxPrevious = ( ListItem_t * ) &( pxList->xListEnd );/*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. */ + + pxList->uxNumberOfItems = ( UBaseType_t ) 0U; + + /* Write known values into the list if + configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList ); + listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList ); +} +/*-----------------------------------------------------------*/ + +void vListInitialiseItem( ListItem_t * const pxItem ) +{ + /* Make sure the list item is not recorded as being on a list. */ + pxItem->pxContainer = NULL; + + /* Write known values into the list item if + configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ); + listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ); +} +/*-----------------------------------------------------------*/ + +void vListInsertEnd( List_t * const pxList, ListItem_t * const pxNewListItem ) +{ +ListItem_t * const pxIndex = pxList->pxIndex; + + /* Only effective when configASSERT() is also defined, these tests may catch + the list data structures being overwritten in memory. They will not catch + data errors caused by incorrect configuration or use of FreeRTOS. */ + listTEST_LIST_INTEGRITY( pxList ); + listTEST_LIST_ITEM_INTEGRITY( pxNewListItem ); + + /* Insert a new list item into pxList, but rather than sort the list, + makes the new list item the last item to be removed by a call to + listGET_OWNER_OF_NEXT_ENTRY(). */ + pxNewListItem->pxNext = pxIndex; + pxNewListItem->pxPrevious = pxIndex->pxPrevious; + + /* Only used during decision coverage testing. */ + mtCOVERAGE_TEST_DELAY(); + + pxIndex->pxPrevious->pxNext = pxNewListItem; + pxIndex->pxPrevious = pxNewListItem; + + /* Remember which list the item is in. */ + pxNewListItem->pxContainer = pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListInsert( List_t * const pxList, ListItem_t * const pxNewListItem ) +{ +ListItem_t *pxIterator; +const TickType_t xValueOfInsertion = pxNewListItem->xItemValue; + + /* Only effective when configASSERT() is also defined, these tests may catch + the list data structures being overwritten in memory. They will not catch + data errors caused by incorrect configuration or use of FreeRTOS. */ + listTEST_LIST_INTEGRITY( pxList ); + listTEST_LIST_ITEM_INTEGRITY( pxNewListItem ); + + /* Insert the new list item into the list, sorted in xItemValue order. + + If the list already contains a list item with the same item value then the + new list item should be placed after it. This ensures that TCBs which are + stored in ready lists (all of which have the same xItemValue value) get a + share of the CPU. However, if the xItemValue is the same as the back marker + the iteration loop below will not end. Therefore the value is checked + first, and the algorithm slightly modified if necessary. */ + if( xValueOfInsertion == portMAX_DELAY ) + { + pxIterator = pxList->xListEnd.pxPrevious; + } + else + { + /* *** NOTE *********************************************************** + If you find your application is crashing here then likely causes are + listed below. In addition see https://www.freertos.org/FAQHelp.html for + more tips, and ensure configASSERT() is defined! + https://www.freertos.org/a00110.html#configASSERT + + 1) Stack overflow - + see https://www.freertos.org/Stacks-and-stack-overflow-checking.html + 2) Incorrect interrupt priority assignment, especially on Cortex-M + parts where numerically high priority values denote low actual + interrupt priorities, which can seem counter intuitive. See + https://www.freertos.org/RTOS-Cortex-M3-M4.html and the definition + of configMAX_SYSCALL_INTERRUPT_PRIORITY on + https://www.freertos.org/a00110.html + 3) Calling an API function from within a critical section or when + the scheduler is suspended, or calling an API function that does + not end in "FromISR" from an interrupt. + 4) Using a queue or semaphore before it has been initialised or + before the scheduler has been started (are interrupts firing + before vTaskStartScheduler() has been called?). + **********************************************************************/ + + for( pxIterator = ( ListItem_t * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) /*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. *//*lint !e440 The iterator moves to a different value, not xValueOfInsertion. */ + { + /* There is nothing to do here, just iterating to the wanted + insertion position. */ + } + } + + pxNewListItem->pxNext = pxIterator->pxNext; + pxNewListItem->pxNext->pxPrevious = pxNewListItem; + pxNewListItem->pxPrevious = pxIterator; + pxIterator->pxNext = pxNewListItem; + + /* Remember which list the item is in. This allows fast removal of the + item later. */ + pxNewListItem->pxContainer = pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +UBaseType_t uxListRemove( ListItem_t * const pxItemToRemove ) +{ +/* The list item knows which list it is in. Obtain the list from the list +item. */ +List_t * const pxList = pxItemToRemove->pxContainer; + + pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; + pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; + + /* Only used during decision coverage testing. */ + mtCOVERAGE_TEST_DELAY(); + + /* Make sure the index is left pointing to a valid item. */ + if( pxList->pxIndex == pxItemToRemove ) + { + pxList->pxIndex = pxItemToRemove->pxPrevious; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + pxItemToRemove->pxContainer = NULL; + ( pxList->uxNumberOfItems )--; + + return pxList->uxNumberOfItems; +} +/*-----------------------------------------------------------*/ + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/Common/mpu_wrappers.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/Common/mpu_wrappers.c new file mode 100644 index 0000000..af11ee9 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/Common/mpu_wrappers.c @@ -0,0 +1,1374 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 the wrapper functions used to raise the processor privilege + * before calling a standard FreeRTOS API function. + */ + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "timers.h" +#include "event_groups.h" +#include "stream_buffer.h" +#include "mpu_prototypes.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/** + * @brief Calls the port specific code to raise the privilege. + * + * @return pdFALSE if privilege was raised, pdTRUE otherwise. + */ +BaseType_t xPortRaisePrivilege( void ) FREERTOS_SYSTEM_CALL; + +/** + * @brief If xRunningPrivileged is not pdTRUE, calls the port specific + * code to reset the privilege, otherwise does nothing. + */ +void vPortResetPrivilege( BaseType_t xRunningPrivileged ); +/*-----------------------------------------------------------*/ + +BaseType_t xPortRaisePrivilege( void ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged; + + /* Check whether the processor is already privileged. */ + xRunningPrivileged = portIS_PRIVILEGED(); + + /* If the processor is not already privileged, raise privilege. */ + if( xRunningPrivileged != pdTRUE ) + { + portRAISE_PRIVILEGE(); + } + + return xRunningPrivileged; +} +/*-----------------------------------------------------------*/ + +void vPortResetPrivilege( BaseType_t xRunningPrivileged ) +{ + if( xRunningPrivileged != pdTRUE ) + { + portRESET_PRIVILEGE(); + } +} +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + BaseType_t MPU_xTaskCreateRestricted( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskCreateRestricted( pxTaskDefinition, pxCreatedTask ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif /* conifgSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + BaseType_t MPU_xTaskCreateRestrictedStatic( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskCreateRestrictedStatic( pxTaskDefinition, pxCreatedTask ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif /* conifgSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + BaseType_t MPU_xTaskCreate( TaskFunction_t pvTaskCode, const char * const pcName, uint16_t usStackDepth, void *pvParameters, UBaseType_t uxPriority, TaskHandle_t *pxCreatedTask ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + TaskHandle_t MPU_xTaskCreateStatic( TaskFunction_t pxTaskCode, const char * const pcName, const uint32_t ulStackDepth, void * const pvParameters, UBaseType_t uxPriority, StackType_t * const puxStackBuffer, StaticTask_t * const pxTaskBuffer ) /* FREERTOS_SYSTEM_CALL */ + { + TaskHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskCreateStatic( pxTaskCode, pcName, ulStackDepth, pvParameters, uxPriority, puxStackBuffer, pxTaskBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +void MPU_vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const xRegions ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskAllocateMPURegions( xTask, xRegions ); + vPortResetPrivilege( xRunningPrivileged ); +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + void MPU_vTaskDelete( TaskHandle_t pxTaskToDelete ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskDelete( pxTaskToDelete ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelayUntil == 1 ) + void MPU_vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, TickType_t xTimeIncrement ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskDelayUntil( pxPreviousWakeTime, xTimeIncrement ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskAbortDelay == 1 ) + BaseType_t MPU_xTaskAbortDelay( TaskHandle_t xTask ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskAbortDelay( xTask ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelay == 1 ) + void MPU_vTaskDelay( TickType_t xTicksToDelay ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskDelay( xTicksToDelay ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + UBaseType_t MPU_uxTaskPriorityGet( const TaskHandle_t pxTask ) /* FREERTOS_SYSTEM_CALL */ + { + UBaseType_t uxReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + uxReturn = uxTaskPriorityGet( pxTask ); + vPortResetPrivilege( xRunningPrivileged ); + return uxReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskPrioritySet == 1 ) + void MPU_vTaskPrioritySet( TaskHandle_t pxTask, UBaseType_t uxNewPriority ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskPrioritySet( pxTask, uxNewPriority ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_eTaskGetState == 1 ) + eTaskState MPU_eTaskGetState( TaskHandle_t pxTask ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + eTaskState eReturn; + + eReturn = eTaskGetState( pxTask ); + vPortResetPrivilege( xRunningPrivileged ); + return eReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TRACE_FACILITY == 1 ) + void MPU_vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskGetInfo( xTask, pxTaskStatus, xGetFreeStackSpace, eState ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + TaskHandle_t MPU_xTaskGetIdleTaskHandle( void ) /* FREERTOS_SYSTEM_CALL */ + { + TaskHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskGetIdleTaskHandle(); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + void MPU_vTaskSuspend( TaskHandle_t pxTaskToSuspend ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskSuspend( pxTaskToSuspend ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + void MPU_vTaskResume( TaskHandle_t pxTaskToResume ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskResume( pxTaskToResume ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +void MPU_vTaskSuspendAll( void ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskSuspendAll(); + vPortResetPrivilege( xRunningPrivileged ); +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xTaskResumeAll( void ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskResumeAll(); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +TickType_t MPU_xTaskGetTickCount( void ) /* FREERTOS_SYSTEM_CALL */ +{ +TickType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskGetTickCount(); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +UBaseType_t MPU_uxTaskGetNumberOfTasks( void ) /* FREERTOS_SYSTEM_CALL */ +{ +UBaseType_t uxReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + uxReturn = uxTaskGetNumberOfTasks(); + vPortResetPrivilege( xRunningPrivileged ); + return uxReturn; +} +/*-----------------------------------------------------------*/ + +char * MPU_pcTaskGetName( TaskHandle_t xTaskToQuery ) /* FREERTOS_SYSTEM_CALL */ +{ +char *pcReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + pcReturn = pcTaskGetName( xTaskToQuery ); + vPortResetPrivilege( xRunningPrivileged ); + return pcReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetHandle == 1 ) + TaskHandle_t MPU_xTaskGetHandle( const char *pcNameToQuery ) /* FREERTOS_SYSTEM_CALL */ + { + TaskHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskGetHandle( pcNameToQuery ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + void MPU_vTaskList( char *pcWriteBuffer ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskList( pcWriteBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + void MPU_vTaskGetRunTimeStats( char *pcWriteBuffer ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskGetRunTimeStats( pcWriteBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) ) + uint32_t MPU_ulTaskGetIdleRunTimeCounter( void ) /* FREERTOS_SYSTEM_CALL */ + { + uint32_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = ulTaskGetIdleRunTimeCounter(); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + void MPU_vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxTagValue ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskSetApplicationTaskTag( xTask, pxTagValue ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + TaskHookFunction_t MPU_xTaskGetApplicationTaskTag( TaskHandle_t xTask ) /* FREERTOS_SYSTEM_CALL */ + { + TaskHookFunction_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskGetApplicationTaskTag( xTask ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 ) + void MPU_vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskSetThreadLocalStoragePointer( xTaskToSet, xIndex, pvValue ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 ) + void *MPU_pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex ) /* FREERTOS_SYSTEM_CALL */ + { + void *pvReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + pvReturn = pvTaskGetThreadLocalStoragePointer( xTaskToQuery, xIndex ); + vPortResetPrivilege( xRunningPrivileged ); + return pvReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + BaseType_t MPU_xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskCallApplicationTaskHook( xTask, pvParameter ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t MPU_uxTaskGetSystemState( TaskStatus_t *pxTaskStatusArray, UBaseType_t uxArraySize, uint32_t *pulTotalRunTime ) /* FREERTOS_SYSTEM_CALL */ + { + UBaseType_t uxReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + uxReturn = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, pulTotalRunTime ); + vPortResetPrivilege( xRunningPrivileged ); + return uxReturn; + } +#endif +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xTaskCatchUpTicks( TickType_t xTicksToCatchUp ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskCatchUpTicks( xTicksToCatchUp ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) + UBaseType_t MPU_uxTaskGetStackHighWaterMark( TaskHandle_t xTask ) /* FREERTOS_SYSTEM_CALL */ + { + UBaseType_t uxReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + uxReturn = uxTaskGetStackHighWaterMark( xTask ); + vPortResetPrivilege( xRunningPrivileged ); + return uxReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) + configSTACK_DEPTH_TYPE MPU_uxTaskGetStackHighWaterMark2( TaskHandle_t xTask ) /* FREERTOS_SYSTEM_CALL */ + { + configSTACK_DEPTH_TYPE uxReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + uxReturn = uxTaskGetStackHighWaterMark2( xTask ); + vPortResetPrivilege( xRunningPrivileged ); + return uxReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) + TaskHandle_t MPU_xTaskGetCurrentTaskHandle( void ) /* FREERTOS_SYSTEM_CALL */ + { + TaskHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskGetCurrentTaskHandle(); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetSchedulerState == 1 ) + BaseType_t MPU_xTaskGetSchedulerState( void ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskGetSchedulerState(); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +void MPU_vTaskSetTimeOutState( TimeOut_t * const pxTimeOut ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTaskSetTimeOutState( pxTimeOut ); + vPortResetPrivilege( xRunningPrivileged ); +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskCheckForTimeOut( pxTimeOut, pxTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + BaseType_t MPU_xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskGenericNotify( xTaskToNotify, ulValue, eAction, pulPreviousNotificationValue ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + BaseType_t MPU_xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskNotifyWait( ulBitsToClearOnEntry, ulBitsToClearOnExit, pulNotificationValue, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + uint32_t MPU_ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ + { + uint32_t ulReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + ulReturn = ulTaskNotifyTake( xClearCountOnExit, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + return ulReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + BaseType_t MPU_xTaskNotifyStateClear( TaskHandle_t xTask ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTaskNotifyStateClear( xTask ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + uint32_t MPU_ulTaskNotifyValueClear( TaskHandle_t xTask, uint32_t ulBitsToClear ) /* FREERTOS_SYSTEM_CALL */ + { + uint32_t ulReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + ulReturn = ulTaskNotifyValueClear( xTask, ulBitsToClear ); + vPortResetPrivilege( xRunningPrivileged ); + return ulReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + QueueHandle_t MPU_xQueueGenericCreate( UBaseType_t uxQueueLength, UBaseType_t uxItemSize, uint8_t ucQueueType ) /* FREERTOS_SYSTEM_CALL */ + { + QueueHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueGenericCreate( uxQueueLength, uxItemSize, ucQueueType ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + QueueHandle_t MPU_xQueueGenericCreateStatic( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, StaticQueue_t *pxStaticQueue, const uint8_t ucQueueType ) /* FREERTOS_SYSTEM_CALL */ + { + QueueHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueGenericCreateStatic( uxQueueLength, uxItemSize, pucQueueStorage, pxStaticQueue, ucQueueType ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xQueueGenericReset( QueueHandle_t pxQueue, BaseType_t xNewQueue ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueGenericReset( pxQueue, xNewQueue ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, BaseType_t xCopyPosition ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, xCopyPosition ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +UBaseType_t MPU_uxQueueMessagesWaiting( const QueueHandle_t pxQueue ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); +UBaseType_t uxReturn; + + uxReturn = uxQueueMessagesWaiting( pxQueue ); + vPortResetPrivilege( xRunningPrivileged ); + return uxReturn; +} +/*-----------------------------------------------------------*/ + +UBaseType_t MPU_uxQueueSpacesAvailable( const QueueHandle_t xQueue ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); +UBaseType_t uxReturn; + + uxReturn = uxQueueSpacesAvailable( xQueue ); + vPortResetPrivilege( xRunningPrivileged ); + return uxReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xQueueReceive( QueueHandle_t pxQueue, void * const pvBuffer, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); +BaseType_t xReturn; + + xReturn = xQueueReceive( pxQueue, pvBuffer, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xQueuePeek( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); +BaseType_t xReturn; + + xReturn = xQueuePeek( xQueue, pvBuffer, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xQueueSemaphoreTake( QueueHandle_t xQueue, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); +BaseType_t xReturn; + + xReturn = xQueueSemaphoreTake( xQueue, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xSemaphoreGetMutexHolder == 1 ) ) + TaskHandle_t MPU_xQueueGetMutexHolder( QueueHandle_t xSemaphore ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + void * xReturn; + + xReturn = xQueueGetMutexHolder( xSemaphore ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( ( configUSE_MUTEXES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + QueueHandle_t MPU_xQueueCreateMutex( const uint8_t ucQueueType ) /* FREERTOS_SYSTEM_CALL */ + { + QueueHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueCreateMutex( ucQueueType ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( ( configUSE_MUTEXES == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + QueueHandle_t MPU_xQueueCreateMutexStatic( const uint8_t ucQueueType, StaticQueue_t *pxStaticQueue ) /* FREERTOS_SYSTEM_CALL */ + { + QueueHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueCreateMutexStatic( ucQueueType, pxStaticQueue ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + QueueHandle_t MPU_xQueueCreateCountingSemaphore( UBaseType_t uxCountValue, UBaseType_t uxInitialCount ) /* FREERTOS_SYSTEM_CALL */ + { + QueueHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueCreateCountingSemaphore( uxCountValue, uxInitialCount ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + + QueueHandle_t MPU_xQueueCreateCountingSemaphoreStatic( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount, StaticQueue_t *pxStaticQueue ) /* FREERTOS_SYSTEM_CALL */ + { + QueueHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueCreateCountingSemaphoreStatic( uxMaxCount, uxInitialCount, pxStaticQueue ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) + BaseType_t MPU_xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xBlockTime ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueTakeMutexRecursive( xMutex, xBlockTime ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) + BaseType_t MPU_xQueueGiveMutexRecursive( QueueHandle_t xMutex ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueGiveMutexRecursive( xMutex ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( ( configUSE_QUEUE_SETS == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + QueueSetHandle_t MPU_xQueueCreateSet( UBaseType_t uxEventQueueLength ) /* FREERTOS_SYSTEM_CALL */ + { + QueueSetHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueCreateSet( uxEventQueueLength ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + QueueSetMemberHandle_t MPU_xQueueSelectFromSet( QueueSetHandle_t xQueueSet, TickType_t xBlockTimeTicks ) /* FREERTOS_SYSTEM_CALL */ + { + QueueSetMemberHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueSelectFromSet( xQueueSet, xBlockTimeTicks ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + BaseType_t MPU_xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueAddToSet( xQueueOrSemaphore, xQueueSet ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + BaseType_t MPU_xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xQueueRemoveFromSet( xQueueOrSemaphore, xQueueSet ); + vPortResetPrivilege( xRunningPrivileged ); + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + void MPU_vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcName ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vQueueAddToRegistry( xQueue, pcName ); + + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + void MPU_vQueueUnregisterQueue( QueueHandle_t xQueue ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vQueueUnregisterQueue( xQueue ); + + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + const char *MPU_pcQueueGetName( QueueHandle_t xQueue ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + const char *pcReturn; + + pcReturn = pcQueueGetName( xQueue ); + + vPortResetPrivilege( xRunningPrivileged ); + return pcReturn; + } +#endif +/*-----------------------------------------------------------*/ + +void MPU_vQueueDelete( QueueHandle_t xQueue ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vQueueDelete( xQueue ); + + vPortResetPrivilege( xRunningPrivileged ); +} +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + void *MPU_pvPortMalloc( size_t xSize ) /* FREERTOS_SYSTEM_CALL */ + { + void *pvReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + pvReturn = pvPortMalloc( xSize ); + + vPortResetPrivilege( xRunningPrivileged ); + + return pvReturn; + } +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + void MPU_vPortFree( void *pv ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vPortFree( pv ); + + vPortResetPrivilege( xRunningPrivileged ); + } +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + void MPU_vPortInitialiseBlocks( void ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vPortInitialiseBlocks(); + + vPortResetPrivilege( xRunningPrivileged ); + } +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + size_t MPU_xPortGetFreeHeapSize( void ) /* FREERTOS_SYSTEM_CALL */ + { + size_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xPortGetFreeHeapSize(); + + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configUSE_TIMERS == 1 ) ) + TimerHandle_t MPU_xTimerCreate( const char * const pcTimerName, const TickType_t xTimerPeriodInTicks, const UBaseType_t uxAutoReload, void * const pvTimerID, TimerCallbackFunction_t pxCallbackFunction ) /* FREERTOS_SYSTEM_CALL */ + { + TimerHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTimerCreate( pcTimerName, xTimerPeriodInTicks, uxAutoReload, pvTimerID, pxCallbackFunction ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configUSE_TIMERS == 1 ) ) + TimerHandle_t MPU_xTimerCreateStatic( const char * const pcTimerName, const TickType_t xTimerPeriodInTicks, const UBaseType_t uxAutoReload, void * const pvTimerID, TimerCallbackFunction_t pxCallbackFunction, StaticTimer_t *pxTimerBuffer ) /* FREERTOS_SYSTEM_CALL */ + { + TimerHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTimerCreateStatic( pcTimerName, xTimerPeriodInTicks, uxAutoReload, pvTimerID, pxCallbackFunction, pxTimerBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + void *MPU_pvTimerGetTimerID( const TimerHandle_t xTimer ) /* FREERTOS_SYSTEM_CALL */ + { + void * pvReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + pvReturn = pvTimerGetTimerID( xTimer ); + vPortResetPrivilege( xRunningPrivileged ); + + return pvReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + void MPU_vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTimerSetTimerID( xTimer, pvNewID ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + BaseType_t MPU_xTimerIsTimerActive( TimerHandle_t xTimer ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTimerIsTimerActive( xTimer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + TaskHandle_t MPU_xTimerGetTimerDaemonTaskHandle( void ) /* FREERTOS_SYSTEM_CALL */ + { + TaskHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTimerGetTimerDaemonTaskHandle(); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 1 ) ) + BaseType_t MPU_xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTimerPendFunctionCall( xFunctionToPend, pvParameter1, ulParameter2, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + void MPU_vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vTimerSetReloadMode( xTimer, uxAutoReload ); + vPortResetPrivilege( xRunningPrivileged ); + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + UBaseType_t MPU_uxTimerGetReloadMode( TimerHandle_t xTimer ) + { + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + UBaseType_t uxReturn; + + uxReturn = uxTimerGetReloadMode( xTimer ); + vPortResetPrivilege( xRunningPrivileged ); + return uxReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + const char * MPU_pcTimerGetName( TimerHandle_t xTimer ) /* FREERTOS_SYSTEM_CALL */ + { + const char * pcReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + pcReturn = pcTimerGetName( xTimer ); + vPortResetPrivilege( xRunningPrivileged ); + + return pcReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + TickType_t MPU_xTimerGetPeriod( TimerHandle_t xTimer ) /* FREERTOS_SYSTEM_CALL */ + { + TickType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTimerGetPeriod( xTimer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + TickType_t MPU_xTimerGetExpiryTime( TimerHandle_t xTimer ) /* FREERTOS_SYSTEM_CALL */ + { + TickType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTimerGetExpiryTime( xTimer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + BaseType_t MPU_xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ + { + BaseType_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xTimerGenericCommand( xTimer, xCommandID, xOptionalValue, pxHigherPriorityTaskWoken, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + EventGroupHandle_t MPU_xEventGroupCreate( void ) /* FREERTOS_SYSTEM_CALL */ + { + EventGroupHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xEventGroupCreate(); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + EventGroupHandle_t MPU_xEventGroupCreateStatic( StaticEventGroup_t *pxEventGroupBuffer ) /* FREERTOS_SYSTEM_CALL */ + { + EventGroupHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xEventGroupCreateStatic( pxEventGroupBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif +/*-----------------------------------------------------------*/ + +EventBits_t MPU_xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ +{ +EventBits_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xEventGroupWaitBits( xEventGroup, uxBitsToWaitFor, xClearOnExit, xWaitForAllBits, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +EventBits_t MPU_xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) /* FREERTOS_SYSTEM_CALL */ +{ +EventBits_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xEventGroupClearBits( xEventGroup, uxBitsToClear ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +EventBits_t MPU_xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) /* FREERTOS_SYSTEM_CALL */ +{ +EventBits_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xEventGroupSetBits( xEventGroup, uxBitsToSet ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +EventBits_t MPU_xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ +{ +EventBits_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xEventGroupSync( xEventGroup, uxBitsToSet, uxBitsToWaitFor, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void MPU_vEventGroupDelete( EventGroupHandle_t xEventGroup ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vEventGroupDelete( xEventGroup ); + vPortResetPrivilege( xRunningPrivileged ); +} +/*-----------------------------------------------------------*/ + +size_t MPU_xStreamBufferSend( StreamBufferHandle_t xStreamBuffer, const void *pvTxData, size_t xDataLengthBytes, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ +{ +size_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferSend( xStreamBuffer, pvTxData, xDataLengthBytes, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t MPU_xStreamBufferNextMessageLengthBytes( StreamBufferHandle_t xStreamBuffer ) /* FREERTOS_SYSTEM_CALL */ +{ +size_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferNextMessageLengthBytes( xStreamBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t MPU_xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer, void *pvRxData, size_t xBufferLengthBytes, TickType_t xTicksToWait ) /* FREERTOS_SYSTEM_CALL */ +{ +size_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferReceive( xStreamBuffer, pvRxData, xBufferLengthBytes, xTicksToWait ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void MPU_vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + vStreamBufferDelete( xStreamBuffer ); + vPortResetPrivilege( xRunningPrivileged ); +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferIsFull( xStreamBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferIsEmpty( xStreamBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xStreamBufferReset( StreamBufferHandle_t xStreamBuffer ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferReset( xStreamBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t MPU_xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer ) /* FREERTOS_SYSTEM_CALL */ +{ +size_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferSpacesAvailable( xStreamBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t MPU_xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer ) /* FREERTOS_SYSTEM_CALL */ +{ +size_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferBytesAvailable( xStreamBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t MPU_xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel ) /* FREERTOS_SYSTEM_CALL */ +{ +BaseType_t xReturn; +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferSetTriggerLevel( xStreamBuffer, xTriggerLevel ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + StreamBufferHandle_t MPU_xStreamBufferGenericCreate( size_t xBufferSizeBytes, size_t xTriggerLevelBytes, BaseType_t xIsMessageBuffer ) /* FREERTOS_SYSTEM_CALL */ + { + StreamBufferHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferGenericCreate( xBufferSizeBytes, xTriggerLevelBytes, xIsMessageBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + StreamBufferHandle_t MPU_xStreamBufferGenericCreateStatic( size_t xBufferSizeBytes, size_t xTriggerLevelBytes, BaseType_t xIsMessageBuffer, uint8_t * const pucStreamBufferStorageArea, StaticStreamBuffer_t * const pxStaticStreamBuffer ) /* FREERTOS_SYSTEM_CALL */ + { + StreamBufferHandle_t xReturn; + BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + xReturn = xStreamBufferGenericCreateStatic( xBufferSizeBytes, xTriggerLevelBytes, xIsMessageBuffer, pucStreamBufferStorageArea, pxStaticStreamBuffer ); + vPortResetPrivilege( xRunningPrivileged ); + + return xReturn; + } +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + + +/* Functions that the application writer wants to execute in privileged mode +can be defined in application_defined_privileged_functions.h. The functions +must take the same format as those above whereby the privilege state on exit +equals the privilege state on entry. For example: + +void MPU_FunctionName( [parameters ] ) +{ +BaseType_t xRunningPrivileged = xPortRaisePrivilege(); + + FunctionName( [parameters ] ); + + vPortResetPrivilege( xRunningPrivileged ); +} +*/ + +#if configINCLUDE_APPLICATION_DEFINED_PRIVILEGED_FUNCTIONS == 1 + #include "application_defined_privileged_functions.h" +#endif diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/port.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/port.c new file mode 100644 index 0000000..49f0943 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/port.c @@ -0,0 +1,933 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining + * all the API functions to use the MPU wrappers. That should only be done when + * task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" + +/* MPU wrappers includes. */ +#include "mpu_wrappers.h" + +/* Portasm includes. */ +#include "portasm.h" + +#if( configENABLE_TRUSTZONE == 1 ) + /* Secure components includes. */ + #include "secure_context.h" + #include "secure_init.h" +#endif /* configENABLE_TRUSTZONE */ + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/** + * The FreeRTOS Cortex M33 port can be configured to run on the Secure Side only + * i.e. the processor boots as secure and never jumps to the non-secure side. + * The Trust Zone support in the port must be disabled in order to run FreeRTOS + * on the secure side. The following are the valid configuration seetings: + * + * 1. Run FreeRTOS on the Secure Side: + * configRUN_FREERTOS_SECURE_ONLY = 1 and configENABLE_TRUSTZONE = 0 + * + * 2. Run FreeRTOS on the Non-Secure Side with Secure Side function call support: + * configRUN_FREERTOS_SECURE_ONLY = 0 and configENABLE_TRUSTZONE = 1 + * + * 3. Run FreeRTOS on the Non-Secure Side only i.e. no Secure Side function call support: + * configRUN_FREERTOS_SECURE_ONLY = 0 and configENABLE_TRUSTZONE = 0 + */ +#if( ( configRUN_FREERTOS_SECURE_ONLY == 1 ) && ( configENABLE_TRUSTZONE == 1 ) ) + #error TrustZone needs to be disabled in order to run FreeRTOS on the Secure Side. +#endif +/*-----------------------------------------------------------*/ + +/** + * @brief Constants required to manipulate the NVIC. + */ +#define portNVIC_SYSTICK_CTRL ( ( volatile uint32_t * ) 0xe000e010 ) +#define portNVIC_SYSTICK_LOAD ( ( volatile uint32_t * ) 0xe000e014 ) +#define portNVIC_SYSTICK_CURRENT_VALUE ( ( volatile uint32_t * ) 0xe000e018 ) +#define portNVIC_INT_CTRL ( ( volatile uint32_t * ) 0xe000ed04 ) +#define portNVIC_SYSPRI2 ( ( volatile uint32_t * ) 0xe000ed20 ) +#define portNVIC_SYSTICK_CLK ( 0x00000004 ) +#define portNVIC_SYSTICK_INT ( 0x00000002 ) +#define portNVIC_SYSTICK_ENABLE ( 0x00000001 ) +#define portNVIC_PENDSVSET ( 0x10000000 ) +#define portMIN_INTERRUPT_PRIORITY ( 255UL ) +#define portNVIC_PENDSV_PRI ( portMIN_INTERRUPT_PRIORITY << 16UL ) +#define portNVIC_SYSTICK_PRI ( portMIN_INTERRUPT_PRIORITY << 24UL ) +/*-----------------------------------------------------------*/ + +/** + * @brief Constants required to manipulate the SCB. + */ +#define portSCB_SYS_HANDLER_CTRL_STATE_REG ( * ( volatile uint32_t * ) 0xe000ed24 ) +#define portSCB_MEM_FAULT_ENABLE ( 1UL << 16UL ) +/*-----------------------------------------------------------*/ + +/** + * @brief Constants required to manipulate the FPU. + */ +#define portCPACR ( ( volatile uint32_t * ) 0xe000ed88 ) /* Coprocessor Access Control Register. */ +#define portCPACR_CP10_VALUE ( 3UL ) +#define portCPACR_CP11_VALUE portCPACR_CP10_VALUE +#define portCPACR_CP10_POS ( 20UL ) +#define portCPACR_CP11_POS ( 22UL ) + +#define portFPCCR ( ( volatile uint32_t * ) 0xe000ef34 ) /* Floating Point Context Control Register. */ +#define portFPCCR_ASPEN_POS ( 31UL ) +#define portFPCCR_ASPEN_MASK ( 1UL << portFPCCR_ASPEN_POS ) +#define portFPCCR_LSPEN_POS ( 30UL ) +#define portFPCCR_LSPEN_MASK ( 1UL << portFPCCR_LSPEN_POS ) +/*-----------------------------------------------------------*/ + +/** + * @brief Constants required to manipulate the MPU. + */ +#define portMPU_TYPE_REG ( * ( ( volatile uint32_t * ) 0xe000ed90 ) ) +#define portMPU_CTRL_REG ( * ( ( volatile uint32_t * ) 0xe000ed94 ) ) +#define portMPU_RNR_REG ( * ( ( volatile uint32_t * ) 0xe000ed98 ) ) + +#define portMPU_RBAR_REG ( * ( ( volatile uint32_t * ) 0xe000ed9c ) ) +#define portMPU_RLAR_REG ( * ( ( volatile uint32_t * ) 0xe000eda0 ) ) + +#define portMPU_RBAR_A1_REG ( * ( ( volatile uint32_t * ) 0xe000eda4 ) ) +#define portMPU_RLAR_A1_REG ( * ( ( volatile uint32_t * ) 0xe000eda8 ) ) + +#define portMPU_RBAR_A2_REG ( * ( ( volatile uint32_t * ) 0xe000edac ) ) +#define portMPU_RLAR_A2_REG ( * ( ( volatile uint32_t * ) 0xe000edb0 ) ) + +#define portMPU_RBAR_A3_REG ( * ( ( volatile uint32_t * ) 0xe000edb4 ) ) +#define portMPU_RLAR_A3_REG ( * ( ( volatile uint32_t * ) 0xe000edb8 ) ) + +#define portMPU_MAIR0_REG ( * ( ( volatile uint32_t * ) 0xe000edc0 ) ) +#define portMPU_MAIR1_REG ( * ( ( volatile uint32_t * ) 0xe000edc4 ) ) + +#define portMPU_RBAR_ADDRESS_MASK ( 0xffffffe0 ) /* Must be 32-byte aligned. */ +#define portMPU_RLAR_ADDRESS_MASK ( 0xffffffe0 ) /* Must be 32-byte aligned. */ + +#define portMPU_MAIR_ATTR0_POS ( 0UL ) +#define portMPU_MAIR_ATTR0_MASK ( 0x000000ff ) + +#define portMPU_MAIR_ATTR1_POS ( 8UL ) +#define portMPU_MAIR_ATTR1_MASK ( 0x0000ff00 ) + +#define portMPU_MAIR_ATTR2_POS ( 16UL ) +#define portMPU_MAIR_ATTR2_MASK ( 0x00ff0000 ) + +#define portMPU_MAIR_ATTR3_POS ( 24UL ) +#define portMPU_MAIR_ATTR3_MASK ( 0xff000000 ) + +#define portMPU_MAIR_ATTR4_POS ( 0UL ) +#define portMPU_MAIR_ATTR4_MASK ( 0x000000ff ) + +#define portMPU_MAIR_ATTR5_POS ( 8UL ) +#define portMPU_MAIR_ATTR5_MASK ( 0x0000ff00 ) + +#define portMPU_MAIR_ATTR6_POS ( 16UL ) +#define portMPU_MAIR_ATTR6_MASK ( 0x00ff0000 ) + +#define portMPU_MAIR_ATTR7_POS ( 24UL ) +#define portMPU_MAIR_ATTR7_MASK ( 0xff000000 ) + +#define portMPU_RLAR_ATTR_INDEX0 ( 0UL << 1UL ) +#define portMPU_RLAR_ATTR_INDEX1 ( 1UL << 1UL ) +#define portMPU_RLAR_ATTR_INDEX2 ( 2UL << 1UL ) +#define portMPU_RLAR_ATTR_INDEX3 ( 3UL << 1UL ) +#define portMPU_RLAR_ATTR_INDEX4 ( 4UL << 1UL ) +#define portMPU_RLAR_ATTR_INDEX5 ( 5UL << 1UL ) +#define portMPU_RLAR_ATTR_INDEX6 ( 6UL << 1UL ) +#define portMPU_RLAR_ATTR_INDEX7 ( 7UL << 1UL ) + +#define portMPU_RLAR_REGION_ENABLE ( 1UL ) + +/* Enable privileged access to unmapped region. */ +#define portMPU_PRIV_BACKGROUND_ENABLE ( 1UL << 2UL ) + +/* Enable MPU. */ +#define portMPU_ENABLE ( 1UL << 0UL ) + +/* Expected value of the portMPU_TYPE register. */ +#define portEXPECTED_MPU_TYPE_VALUE ( 8UL << 8UL ) /* 8 regions, unified. */ +/*-----------------------------------------------------------*/ + +/** + * @brief Constants required to set up the initial stack. + */ +#define portINITIAL_XPSR ( 0x01000000 ) + +#if( configRUN_FREERTOS_SECURE_ONLY == 1 ) + /** + * @brief Initial EXC_RETURN value. + * + * FF FF FF FD + * 1111 1111 1111 1111 1111 1111 1111 1101 + * + * Bit[6] - 1 --> The exception was taken from the Secure state. + * Bit[5] - 1 --> Do not skip stacking of additional state context. + * Bit[4] - 1 --> The PE did not allocate space on the stack for FP context. + * Bit[3] - 1 --> Return to the Thread mode. + * Bit[2] - 1 --> Restore registers from the process stack. + * Bit[1] - 0 --> Reserved, 0. + * Bit[0] - 1 --> The exception was taken to the Secure state. + */ + #define portINITIAL_EXC_RETURN ( 0xfffffffd ) +#else + /** + * @brief Initial EXC_RETURN value. + * + * FF FF FF BC + * 1111 1111 1111 1111 1111 1111 1011 1100 + * + * Bit[6] - 0 --> The exception was taken from the Non-Secure state. + * Bit[5] - 1 --> Do not skip stacking of additional state context. + * Bit[4] - 1 --> The PE did not allocate space on the stack for FP context. + * Bit[3] - 1 --> Return to the Thread mode. + * Bit[2] - 1 --> Restore registers from the process stack. + * Bit[1] - 0 --> Reserved, 0. + * Bit[0] - 0 --> The exception was taken to the Non-Secure state. + */ + #define portINITIAL_EXC_RETURN ( 0xffffffbc ) +#endif /* configRUN_FREERTOS_SECURE_ONLY */ + +/** + * @brief CONTROL register privileged bit mask. + * + * Bit[0] in CONTROL register tells the privilege: + * Bit[0] = 0 ==> The task is privileged. + * Bit[0] = 1 ==> The task is not privileged. + */ +#define portCONTROL_PRIVILEGED_MASK ( 1UL << 0UL ) + +/** + * @brief Initial CONTROL register values. + */ +#define portINITIAL_CONTROL_UNPRIVILEGED ( 0x3 ) +#define portINITIAL_CONTROL_PRIVILEGED ( 0x2 ) + +/** + * @brief 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 + +/** + * @brief If portPRELOAD_REGISTERS then registers will be given an initial value + * when a task is created. This helps in debugging at the cost of code size. + */ +#define portPRELOAD_REGISTERS 1 + +/** + * @brief A task is created without a secure context, and must call + * portALLOCATE_SECURE_CONTEXT() to give itself a secure context before it makes + * any secure calls. + */ +#define portNO_SECURE_CONTEXT 0 +/*-----------------------------------------------------------*/ + +/** + * @brief Used to catch tasks that attempt to return from their implementing + * function. + */ +static void prvTaskExitError( void ); + +#if( configENABLE_MPU == 1 ) + /** + * @brief Setup the Memory Protection Unit (MPU). + */ + static void prvSetupMPU( void ) PRIVILEGED_FUNCTION; +#endif /* configENABLE_MPU */ + +#if( configENABLE_FPU == 1 ) + /** + * @brief Setup the Floating Point Unit (FPU). + */ + static void prvSetupFPU( void ) PRIVILEGED_FUNCTION; +#endif /* configENABLE_FPU */ + +/** + * @brief 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 ) PRIVILEGED_FUNCTION; + +/** + * @brief Checks whether the current execution context is interrupt. + * + * @return pdTRUE if the current execution context is interrupt, pdFALSE + * otherwise. + */ +BaseType_t xPortIsInsideInterrupt( void ); + +/** + * @brief Yield the processor. + */ +void vPortYield( void ) PRIVILEGED_FUNCTION; + +/** + * @brief Enter critical section. + */ +void vPortEnterCritical( void ) PRIVILEGED_FUNCTION; + +/** + * @brief Exit from critical section. + */ +void vPortExitCritical( void ) PRIVILEGED_FUNCTION; + +/** + * @brief SysTick handler. + */ +void SysTick_Handler( void ) PRIVILEGED_FUNCTION; + +/** + * @brief C part of SVC handler. + */ +portDONT_DISCARD void vPortSVCHandler_C( uint32_t *pulCallerStackAddress ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +/** + * @brief Each task maintains its own interrupt status in the critical nesting + * variable. + */ +static volatile uint32_t ulCriticalNesting = 0xaaaaaaaaUL; + +#if( configENABLE_TRUSTZONE == 1 ) + /** + * @brief Saved as part of the task context to indicate which context the + * task is using on the secure side. + */ + portDONT_DISCARD volatile SecureContextHandle_t xSecureContext = portNO_SECURE_CONTEXT; +#endif /* configENABLE_TRUSTZONE */ +/*-----------------------------------------------------------*/ + +__attribute__(( weak )) void vPortSetupTimerInterrupt( void ) /* PRIVILEGED_FUNCTION */ +{ + /* Stop and reset the SysTick. */ + *( portNVIC_SYSTICK_CTRL ) = 0UL; + *( portNVIC_SYSTICK_CURRENT_VALUE ) = 0UL; + + /* Configure SysTick to interrupt at the requested rate. */ + *( portNVIC_SYSTICK_LOAD ) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; + *( portNVIC_SYSTICK_CTRL ) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE; +} +/*-----------------------------------------------------------*/ + +static void prvTaskExitError( void ) +{ +volatile uint32_t ulDummy = 0UL; + + /* A function that implements a task must not exit or attempt to return to + * its caller as there is nothing to return to. If a task wants to exit it + * should instead call vTaskDelete( NULL ). Artificially force an assert() + * to be triggered if configASSERT() is defined, then stop here so + * application writers can catch the error. */ + configASSERT( ulCriticalNesting == ~0UL ); + portDISABLE_INTERRUPTS(); + + while( ulDummy == 0 ) + { + /* This file calls prvTaskExitError() after the scheduler has been + * started to remove a compiler warning about the function being + * defined but never called. ulDummy is used purely to quieten other + * warnings about code appearing after this function is called - making + * ulDummy volatile makes the compiler think the function could return + * and therefore not output an 'unreachable code' warning for code that + * appears after it. */ + } +} +/*-----------------------------------------------------------*/ + +#if( configENABLE_MPU == 1 ) + static void prvSetupMPU( void ) /* PRIVILEGED_FUNCTION */ + { + #if defined( __ARMCC_VERSION ) + /* Declaration when these variable are defined in code instead of being + * exported from linker scripts. */ + extern uint32_t * __privileged_functions_start__; + extern uint32_t * __privileged_functions_end__; + extern uint32_t * __syscalls_flash_start__; + extern uint32_t * __syscalls_flash_end__; + extern uint32_t * __unprivileged_flash_start__; + extern uint32_t * __unprivileged_flash_end__; + extern uint32_t * __privileged_sram_start__; + extern uint32_t * __privileged_sram_end__; + #else + /* Declaration when these variable are exported from linker scripts. */ + extern uint32_t __privileged_functions_start__[]; + extern uint32_t __privileged_functions_end__[]; + extern uint32_t __syscalls_flash_start__[]; + extern uint32_t __syscalls_flash_end__[]; + extern uint32_t __unprivileged_flash_start__[]; + extern uint32_t __unprivileged_flash_end__[]; + extern uint32_t __privileged_sram_start__[]; + extern uint32_t __privileged_sram_end__[]; + #endif /* defined( __ARMCC_VERSION ) */ + + /* Check that the MPU is present. */ + if( portMPU_TYPE_REG == portEXPECTED_MPU_TYPE_VALUE ) + { + /* MAIR0 - Index 0. */ + portMPU_MAIR0_REG |= ( ( portMPU_NORMAL_MEMORY_BUFFERABLE_CACHEABLE << portMPU_MAIR_ATTR0_POS ) & portMPU_MAIR_ATTR0_MASK ); + /* MAIR0 - Index 1. */ + portMPU_MAIR0_REG |= ( ( portMPU_DEVICE_MEMORY_nGnRE << portMPU_MAIR_ATTR1_POS ) & portMPU_MAIR_ATTR1_MASK ); + + /* Setup privileged flash as Read Only so that privileged tasks can + * read it but not modify. */ + portMPU_RNR_REG = portPRIVILEGED_FLASH_REGION; + portMPU_RBAR_REG = ( ( ( uint32_t ) __privileged_functions_start__ ) & portMPU_RBAR_ADDRESS_MASK ) | + ( portMPU_REGION_NON_SHAREABLE ) | + ( portMPU_REGION_PRIVILEGED_READ_ONLY ); + portMPU_RLAR_REG = ( ( ( uint32_t ) __privileged_functions_end__ ) & portMPU_RLAR_ADDRESS_MASK ) | + ( portMPU_RLAR_ATTR_INDEX0 ) | + ( portMPU_RLAR_REGION_ENABLE ); + + /* Setup unprivileged flash as Read Only by both privileged and + * unprivileged tasks. All tasks can read it but no-one can modify. */ + portMPU_RNR_REG = portUNPRIVILEGED_FLASH_REGION; + portMPU_RBAR_REG = ( ( ( uint32_t ) __unprivileged_flash_start__ ) & portMPU_RBAR_ADDRESS_MASK ) | + ( portMPU_REGION_NON_SHAREABLE ) | + ( portMPU_REGION_READ_ONLY ); + portMPU_RLAR_REG = ( ( ( uint32_t ) __unprivileged_flash_end__ ) & portMPU_RLAR_ADDRESS_MASK ) | + ( portMPU_RLAR_ATTR_INDEX0 ) | + ( portMPU_RLAR_REGION_ENABLE ); + + /* Setup unprivileged syscalls flash as Read Only by both privileged + * and unprivileged tasks. All tasks can read it but no-one can modify. */ + portMPU_RNR_REG = portUNPRIVILEGED_SYSCALLS_REGION; + portMPU_RBAR_REG = ( ( ( uint32_t ) __syscalls_flash_start__ ) & portMPU_RBAR_ADDRESS_MASK ) | + ( portMPU_REGION_NON_SHAREABLE ) | + ( portMPU_REGION_READ_ONLY ); + portMPU_RLAR_REG = ( ( ( uint32_t ) __syscalls_flash_end__ ) & portMPU_RLAR_ADDRESS_MASK ) | + ( portMPU_RLAR_ATTR_INDEX0 ) | + ( portMPU_RLAR_REGION_ENABLE ); + + /* Setup RAM containing kernel data for privileged access only. */ + portMPU_RNR_REG = portPRIVILEGED_RAM_REGION; + portMPU_RBAR_REG = ( ( ( uint32_t ) __privileged_sram_start__ ) & portMPU_RBAR_ADDRESS_MASK ) | + ( portMPU_REGION_NON_SHAREABLE ) | + ( portMPU_REGION_PRIVILEGED_READ_WRITE ) | + ( portMPU_REGION_EXECUTE_NEVER ); + portMPU_RLAR_REG = ( ( ( uint32_t ) __privileged_sram_end__ ) & portMPU_RLAR_ADDRESS_MASK ) | + ( portMPU_RLAR_ATTR_INDEX0 ) | + ( portMPU_RLAR_REGION_ENABLE ); + + /* Enable mem fault. */ + portSCB_SYS_HANDLER_CTRL_STATE_REG |= portSCB_MEM_FAULT_ENABLE; + + /* Enable MPU with privileged background access i.e. unmapped + * regions have privileged access. */ + portMPU_CTRL_REG |= ( portMPU_PRIV_BACKGROUND_ENABLE | portMPU_ENABLE ); + } + } +#endif /* configENABLE_MPU */ +/*-----------------------------------------------------------*/ + +#if( configENABLE_FPU == 1 ) + static void prvSetupFPU( void ) /* PRIVILEGED_FUNCTION */ + { + #if( configENABLE_TRUSTZONE == 1 ) + { + /* Enable non-secure access to the FPU. */ + SecureInit_EnableNSFPUAccess(); + } + #endif /* configENABLE_TRUSTZONE */ + + /* CP10 = 11 ==> Full access to FPU i.e. both privileged and + * unprivileged code should be able to access FPU. CP11 should be + * programmed to the same value as CP10. */ + *( portCPACR ) |= ( ( portCPACR_CP10_VALUE << portCPACR_CP10_POS ) | + ( portCPACR_CP11_VALUE << portCPACR_CP11_POS ) + ); + + /* ASPEN = 1 ==> Hardware should automatically preserve floating point + * context on exception entry and restore on exception return. + * LSPEN = 1 ==> Enable lazy context save of FP state. */ + *( portFPCCR ) |= ( portFPCCR_ASPEN_MASK | portFPCCR_LSPEN_MASK ); + } +#endif /* configENABLE_FPU */ +/*-----------------------------------------------------------*/ + +void vPortYield( void ) /* PRIVILEGED_FUNCTION */ +{ + /* Set a PendSV to request a context switch. */ + *( portNVIC_INT_CTRL ) = portNVIC_PENDSVSET; + + /* Barriers are normally not required but do ensure the code is + * completely within the specified behaviour for the architecture. */ + __asm volatile( "dsb" ::: "memory" ); + __asm volatile( "isb" ); +} +/*-----------------------------------------------------------*/ + +void vPortEnterCritical( void ) /* PRIVILEGED_FUNCTION */ +{ + portDISABLE_INTERRUPTS(); + ulCriticalNesting++; + + /* Barriers are normally not required but do ensure the code is + * completely within the specified behaviour for the architecture. */ + __asm volatile( "dsb" ::: "memory" ); + __asm volatile( "isb" ); +} +/*-----------------------------------------------------------*/ + +void vPortExitCritical( void ) /* PRIVILEGED_FUNCTION */ +{ + configASSERT( ulCriticalNesting ); + ulCriticalNesting--; + + if( ulCriticalNesting == 0 ) + { + portENABLE_INTERRUPTS(); + } +} +/*-----------------------------------------------------------*/ + +void SysTick_Handler( void ) /* PRIVILEGED_FUNCTION */ +{ +uint32_t ulPreviousMask; + + ulPreviousMask = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* Increment the RTOS tick. */ + if( xTaskIncrementTick() != pdFALSE ) + { + /* Pend a context switch. */ + *( portNVIC_INT_CTRL ) = portNVIC_PENDSVSET; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( ulPreviousMask ); +} +/*-----------------------------------------------------------*/ + +void vPortSVCHandler_C( uint32_t *pulCallerStackAddress ) /* PRIVILEGED_FUNCTION portDONT_DISCARD */ +{ +#if( configENABLE_MPU == 1 ) + #if defined( __ARMCC_VERSION ) + /* Declaration when these variable are defined in code instead of being + * exported from linker scripts. */ + extern uint32_t * __syscalls_flash_start__; + extern uint32_t * __syscalls_flash_end__; + #else + /* Declaration when these variable are exported from linker scripts. */ + extern uint32_t __syscalls_flash_start__[]; + extern uint32_t __syscalls_flash_end__[]; + #endif /* defined( __ARMCC_VERSION ) */ +#endif /* configENABLE_MPU */ + +uint32_t ulPC; + +#if( configENABLE_TRUSTZONE == 1 ) + uint32_t ulR0; + #if( configENABLE_MPU == 1 ) + uint32_t ulControl, ulIsTaskPrivileged; + #endif /* configENABLE_MPU */ +#endif /* configENABLE_TRUSTZONE */ +uint8_t ucSVCNumber; + + /* Register are stored on the stack in the following order - R0, R1, R2, R3, + * R12, LR, PC, xPSR. */ + ulPC = pulCallerStackAddress[ 6 ]; + ucSVCNumber = ( ( uint8_t *) ulPC )[ -2 ]; + + switch( ucSVCNumber ) + { + #if( configENABLE_TRUSTZONE == 1 ) + case portSVC_ALLOCATE_SECURE_CONTEXT: + { + /* R0 contains the stack size passed as parameter to the + * vPortAllocateSecureContext function. */ + ulR0 = pulCallerStackAddress[ 0 ]; + + #if( configENABLE_MPU == 1 ) + { + /* Read the CONTROL register value. */ + __asm volatile ( "mrs %0, control" : "=r" ( ulControl ) ); + + /* The task that raised the SVC is privileged if Bit[0] + * in the CONTROL register is 0. */ + ulIsTaskPrivileged = ( ( ulControl & portCONTROL_PRIVILEGED_MASK ) == 0 ); + + /* Allocate and load a context for the secure task. */ + xSecureContext = SecureContext_AllocateContext( ulR0, ulIsTaskPrivileged ); + } + #else + { + /* Allocate and load a context for the secure task. */ + xSecureContext = SecureContext_AllocateContext( ulR0 ); + } + #endif /* configENABLE_MPU */ + + configASSERT( xSecureContext != NULL ); + SecureContext_LoadContext( xSecureContext ); + } + break; + + case portSVC_FREE_SECURE_CONTEXT: + { + /* R0 contains the secure context handle to be freed. */ + ulR0 = pulCallerStackAddress[ 0 ]; + + /* Free the secure context. */ + SecureContext_FreeContext( ( SecureContextHandle_t ) ulR0 ); + } + break; + #endif /* configENABLE_TRUSTZONE */ + + case portSVC_START_SCHEDULER: + { + #if( configENABLE_TRUSTZONE == 1 ) + { + /* De-prioritize the non-secure exceptions so that the + * non-secure pendSV runs at the lowest priority. */ + SecureInit_DePrioritizeNSExceptions(); + + /* Initialize the secure context management system. */ + SecureContext_Init(); + } + #endif /* configENABLE_TRUSTZONE */ + + #if( configENABLE_FPU == 1 ) + { + /* Setup the Floating Point Unit (FPU). */ + prvSetupFPU(); + } + #endif /* configENABLE_FPU */ + + /* Setup the context of the first task so that the first task starts + * executing. */ + vRestoreContextOfFirstTask(); + } + break; + + #if( configENABLE_MPU == 1 ) + case portSVC_RAISE_PRIVILEGE: + { + /* Only raise the privilege, if the svc was raised from any of + * the system calls. */ + if( ulPC >= ( uint32_t ) __syscalls_flash_start__ && + ulPC <= ( uint32_t ) __syscalls_flash_end__ ) + { + vRaisePrivilege(); + } + } + break; + #endif /* configENABLE_MPU */ + + default: + { + /* Incorrect SVC call. */ + configASSERT( pdFALSE ); + } + } +} +/*-----------------------------------------------------------*/ + +#if( configENABLE_MPU == 1 ) + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, StackType_t *pxEndOfStack, TaskFunction_t pxCode, void *pvParameters, BaseType_t xRunPrivileged ) /* PRIVILEGED_FUNCTION */ +#else + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, StackType_t *pxEndOfStack, TaskFunction_t pxCode, void *pvParameters ) /* PRIVILEGED_FUNCTION */ +#endif /* configENABLE_MPU */ +{ + /* Simulate the stack frame as it would be created by a context switch + * interrupt. */ + #if( portPRELOAD_REGISTERS == 0 ) + { + pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */ + *pxTopOfStack = portINITIAL_XPSR; /* xPSR */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) pxCode; /* PC */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */ + pxTopOfStack -= 5; /* R12, R3, R2 and R1. */ + *pxTopOfStack = ( StackType_t ) pvParameters; /* R0 */ + pxTopOfStack -= 9; /* R11..R4, EXC_RETURN. */ + *pxTopOfStack = portINITIAL_EXC_RETURN; + + #if( configENABLE_MPU == 1 ) + { + pxTopOfStack--; + if( xRunPrivileged == pdTRUE ) + { + *pxTopOfStack = portINITIAL_CONTROL_PRIVILEGED; /* Slot used to hold this task's CONTROL value. */ + } + else + { + *pxTopOfStack = portINITIAL_CONTROL_UNPRIVILEGED; /* Slot used to hold this task's CONTROL value. */ + } + } + #endif /* configENABLE_MPU */ + + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) pxEndOfStack; /* Slot used to hold this task's PSPLIM value. */ + + #if( configENABLE_TRUSTZONE == 1 ) + { + pxTopOfStack--; + *pxTopOfStack = portNO_SECURE_CONTEXT; /* Slot used to hold this task's xSecureContext value. */ + } + #endif /* configENABLE_TRUSTZONE */ + } + #else /* portPRELOAD_REGISTERS */ + { + pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */ + *pxTopOfStack = portINITIAL_XPSR; /* xPSR */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) pxCode; /* PC */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x12121212UL; /* R12 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x03030303UL; /* R3 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x02020202UL; /* R2 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x01010101UL; /* R1 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) pvParameters; /* R0 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x11111111UL; /* R11 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x10101010UL; /* R10 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x09090909UL; /* R09 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x08080808UL; /* R08 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x07070707UL; /* R07 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x06060606UL; /* R06 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x05050505UL; /* R05 */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) 0x04040404UL; /* R04 */ + pxTopOfStack--; + *pxTopOfStack = portINITIAL_EXC_RETURN; /* EXC_RETURN */ + + #if( configENABLE_MPU == 1 ) + { + pxTopOfStack--; + if( xRunPrivileged == pdTRUE ) + { + *pxTopOfStack = portINITIAL_CONTROL_PRIVILEGED; /* Slot used to hold this task's CONTROL value. */ + } + else + { + *pxTopOfStack = portINITIAL_CONTROL_UNPRIVILEGED; /* Slot used to hold this task's CONTROL value. */ + } + } + #endif /* configENABLE_MPU */ + + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) pxEndOfStack; /* Slot used to hold this task's PSPLIM value. */ + + #if( configENABLE_TRUSTZONE == 1 ) + { + pxTopOfStack--; + *pxTopOfStack = portNO_SECURE_CONTEXT; /* Slot used to hold this task's xSecureContext value. */ + } + #endif /* configENABLE_TRUSTZONE */ + } + #endif /* portPRELOAD_REGISTERS */ + + return pxTopOfStack; +} +/*-----------------------------------------------------------*/ + +BaseType_t xPortStartScheduler( void ) /* PRIVILEGED_FUNCTION */ +{ + /* Make PendSV, CallSV and SysTick the same priority as the kernel. */ + *( portNVIC_SYSPRI2 ) |= portNVIC_PENDSV_PRI; + *( portNVIC_SYSPRI2 ) |= portNVIC_SYSTICK_PRI; + + #if( configENABLE_MPU == 1 ) + { + /* Setup the Memory Protection Unit (MPU). */ + prvSetupMPU(); + } + #endif /* configENABLE_MPU */ + + /* Start the timer that generates the tick ISR. Interrupts are disabled + * here already. */ + vPortSetupTimerInterrupt(); + + /* Initialize the critical nesting count ready for the first task. */ + ulCriticalNesting = 0; + + /* Start the first task. */ + vStartFirstTask(); + + /* Should never get here as the tasks will now be executing. Call the task + * exit error function to prevent compiler warnings about a static function + * not being called in the case that the application writer overrides this + * functionality by defining configTASK_RETURN_ADDRESS. Call + * vTaskSwitchContext() so link time optimization does not remove the + * symbol. */ + vTaskSwitchContext(); + prvTaskExitError(); + + /* Should not get here. */ + return 0; +} +/*-----------------------------------------------------------*/ + +void vPortEndScheduler( void ) /* PRIVILEGED_FUNCTION */ +{ + /* Not implemented in ports where there is nothing to return to. + * Artificially force an assert. */ + configASSERT( ulCriticalNesting == 1000UL ); +} +/*-----------------------------------------------------------*/ + +#if( configENABLE_MPU == 1 ) + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, StackType_t *pxBottomOfStack, uint32_t ulStackDepth ) + { + uint32_t ulRegionStartAddress, ulRegionEndAddress, ulRegionNumber; + int32_t lIndex = 0; + + /* Setup MAIR0. */ + xMPUSettings->ulMAIR0 = ( ( portMPU_NORMAL_MEMORY_BUFFERABLE_CACHEABLE << portMPU_MAIR_ATTR0_POS ) & portMPU_MAIR_ATTR0_MASK ); + xMPUSettings->ulMAIR0 |= ( ( portMPU_DEVICE_MEMORY_nGnRE << portMPU_MAIR_ATTR1_POS ) & portMPU_MAIR_ATTR1_MASK ); + + /* This function is called automatically when the task is created - in + * which case the stack region parameters will be valid. At all other + * times the stack parameters will not be valid and it is assumed that + * the stack region has already been configured. */ + if( ulStackDepth > 0 ) + { + /* Define the region that allows access to the stack. */ + ulRegionStartAddress = ( ( uint32_t ) pxBottomOfStack ) & portMPU_RBAR_ADDRESS_MASK; + ulRegionEndAddress = ( uint32_t ) pxBottomOfStack + ( ulStackDepth * ( uint32_t ) sizeof( StackType_t ) ) - 1; + ulRegionEndAddress &= portMPU_RLAR_ADDRESS_MASK; + + xMPUSettings->xRegionsSettings[ 0 ].ulRBAR = ( ulRegionStartAddress ) | + ( portMPU_REGION_NON_SHAREABLE ) | + ( portMPU_REGION_READ_WRITE ) | + ( portMPU_REGION_EXECUTE_NEVER ); + + xMPUSettings->xRegionsSettings[ 0 ].ulRLAR = ( ulRegionEndAddress ) | + ( portMPU_RLAR_ATTR_INDEX0 ) | + ( portMPU_RLAR_REGION_ENABLE ); + } + + /* User supplied configurable regions. */ + for( ulRegionNumber = 1; ulRegionNumber <= portNUM_CONFIGURABLE_REGIONS; ulRegionNumber++ ) + { + /* If xRegions is NULL i.e. the task has not specified any MPU + * region, the else part ensures that all the configurable MPU + * regions are invalidated. */ + if( ( xRegions != NULL ) && ( xRegions[ lIndex ].ulLengthInBytes > 0UL ) ) + { + /* Translate the generic region definition contained in xRegions + * into the ARMv8 specific MPU settings that are then stored in + * xMPUSettings. */ + ulRegionStartAddress = ( ( uint32_t ) xRegions[ lIndex ].pvBaseAddress ) & portMPU_RBAR_ADDRESS_MASK; + ulRegionEndAddress = ( uint32_t ) xRegions[ lIndex ].pvBaseAddress + xRegions[ lIndex ].ulLengthInBytes - 1; + ulRegionEndAddress &= portMPU_RLAR_ADDRESS_MASK; + + /* Start address. */ + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRBAR = ( ulRegionStartAddress ) | + ( portMPU_REGION_NON_SHAREABLE ); + + /* RO/RW. */ + if( ( xRegions[ lIndex ].ulParameters & tskMPU_REGION_READ_ONLY ) != 0 ) + { + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRBAR |= ( portMPU_REGION_READ_ONLY ); + } + else + { + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRBAR |= ( portMPU_REGION_READ_WRITE ); + } + + /* XN. */ + if( ( xRegions[ lIndex ].ulParameters & tskMPU_REGION_EXECUTE_NEVER ) != 0 ) + { + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRBAR |= ( portMPU_REGION_EXECUTE_NEVER ); + } + + /* End Address. */ + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRLAR = ( ulRegionEndAddress ) | + ( portMPU_RLAR_REGION_ENABLE ); + + /* Normal memory/ Device memory. */ + if( ( xRegions[ lIndex ].ulParameters & tskMPU_REGION_DEVICE_MEMORY ) != 0 ) + { + /* Attr1 in MAIR0 is configured as device memory. */ + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRLAR |= portMPU_RLAR_ATTR_INDEX1; + } + else + { + /* Attr1 in MAIR0 is configured as normal memory. */ + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRLAR |= portMPU_RLAR_ATTR_INDEX0; + } + } + else + { + /* Invalidate the region. */ + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRBAR = 0UL; + xMPUSettings->xRegionsSettings[ ulRegionNumber ].ulRLAR = 0UL; + } + + lIndex++; + } + } +#endif /* configENABLE_MPU */ +/*-----------------------------------------------------------*/ + +BaseType_t xPortIsInsideInterrupt( void ) +{ +uint32_t ulCurrentInterrupt; +BaseType_t xReturn; + + /* Obtain the number of the currently executing interrupt. Interrupt Program + * Status Register (IPSR) holds the exception number of the currently-executing + * exception or zero for Thread mode.*/ + __asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) :: "memory" ); + + if( ulCurrentInterrupt == 0 ) + { + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ \ No newline at end of file diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portasm.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portasm.c new file mode 100644 index 0000000..14b6038 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portasm.c @@ -0,0 +1,316 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* Standard includes. */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE ensures that PRIVILEGED_FUNCTION + * is defined correctly and privileged functions are placed in correct sections. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* Portasm includes. */ +#include "portasm.h" + +/* MPU_WRAPPERS_INCLUDED_FROM_API_FILE is needed to be defined only for the + * header files. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +void vRestoreContextOfFirstTask( void ) /* __attribute__ (( naked )) PRIVILEGED_FUNCTION */ +{ + __asm volatile + ( + " .syntax unified \n" + " \n" + " ldr r2, pxCurrentTCBConst2 \n" /* Read the location of pxCurrentTCB i.e. &( pxCurrentTCB ). */ + " ldr r1, [r2] \n" /* Read pxCurrentTCB. */ + " ldr r0, [r1] \n" /* Read top of stack from TCB - The first item in pxCurrentTCB is the task top of stack. */ + " \n" + #if( configENABLE_MPU == 1 ) + " dmb \n" /* Complete outstanding transfers before disabling MPU. */ + " ldr r2, xMPUCTRLConst2 \n" /* r2 = 0xe000ed94 [Location of MPU_CTRL]. */ + " ldr r4, [r2] \n" /* Read the value of MPU_CTRL. */ + " bic r4, #1 \n" /* r4 = r4 & ~1 i.e. Clear the bit 0 in r4. */ + " str r4, [r2] \n" /* Disable MPU. */ + " \n" + " adds r1, #4 \n" /* r1 = r1 + 4. r1 now points to MAIR0 in TCB. */ + " ldr r3, [r1] \n" /* r3 = *r1 i.e. r3 = MAIR0. */ + " ldr r2, xMAIR0Const2 \n" /* r2 = 0xe000edc0 [Location of MAIR0]. */ + " str r3, [r2] \n" /* Program MAIR0. */ + " ldr r2, xRNRConst2 \n" /* r2 = 0xe000ed98 [Location of RNR]. */ + " movs r3, #4 \n" /* r3 = 4. */ + " str r3, [r2] \n" /* Program RNR = 4. */ + " adds r1, #4 \n" /* r1 = r1 + 4. r1 now points to first RBAR in TCB. */ + " ldr r2, xRBARConst2 \n" /* r2 = 0xe000ed9c [Location of RBAR]. */ + " ldmia r1!, {r4-r11} \n" /* Read 4 set of RBAR/RLAR registers from TCB. */ + " stmia r2!, {r4-r11} \n" /* Write 4 set of RBAR/RLAR registers using alias registers. */ + " \n" + " ldr r2, xMPUCTRLConst2 \n" /* r2 = 0xe000ed94 [Location of MPU_CTRL]. */ + " ldr r4, [r2] \n" /* Read the value of MPU_CTRL. */ + " orr r4, #1 \n" /* r4 = r4 | 1 i.e. Set the bit 0 in r4. */ + " str r4, [r2] \n" /* Enable MPU. */ + " dsb \n" /* Force memory writes before continuing. */ + #endif /* configENABLE_MPU */ + " \n" + #if( configENABLE_MPU == 1 ) + " ldm r0!, {r1-r3} \n" /* Read from stack - r1 = PSPLIM, r2 = CONTROL and r3 = EXC_RETURN. */ + " msr psplim, r1 \n" /* Set this task's PSPLIM value. */ + " msr control, r2 \n" /* Set this task's CONTROL value. */ + " adds r0, #32 \n" /* Discard everything up to r0. */ + " msr psp, r0 \n" /* This is now the new top of stack to use in the task. */ + " isb \n" + " bx r3 \n" /* Finally, branch to EXC_RETURN. */ + #else /* configENABLE_MPU */ + " ldm r0!, {r1-r2} \n" /* Read from stack - r1 = PSPLIM and r2 = EXC_RETURN. */ + " msr psplim, r1 \n" /* Set this task's PSPLIM value. */ + " movs r1, #2 \n" /* r1 = 2. */ + " msr CONTROL, r1 \n" /* Switch to use PSP in the thread mode. */ + " adds r0, #32 \n" /* Discard everything up to r0. */ + " msr psp, r0 \n" /* This is now the new top of stack to use in the task. */ + " isb \n" + " bx r2 \n" /* Finally, branch to EXC_RETURN. */ + #endif /* configENABLE_MPU */ + " \n" + " .align 4 \n" + "pxCurrentTCBConst2: .word pxCurrentTCB \n" + #if( configENABLE_MPU == 1 ) + "xMPUCTRLConst2: .word 0xe000ed94 \n" + "xMAIR0Const2: .word 0xe000edc0 \n" + "xRNRConst2: .word 0xe000ed98 \n" + "xRBARConst2: .word 0xe000ed9c \n" + #endif /* configENABLE_MPU */ + ); +} +/*-----------------------------------------------------------*/ + +BaseType_t xIsPrivileged( void ) /* __attribute__ (( naked )) */ +{ + __asm volatile + ( + " mrs r0, control \n" /* r0 = CONTROL. */ + " tst r0, #1 \n" /* Perform r0 & 1 (bitwise AND) and update the conditions flag. */ + " ite ne \n" + " movne r0, #0 \n" /* CONTROL[0]!=0. Return false to indicate that the processor is not privileged. */ + " moveq r0, #1 \n" /* CONTROL[0]==0. Return true to indicate that the processor is privileged. */ + " bx lr \n" /* Return. */ + " \n" + " .align 4 \n" + ::: "r0", "memory" + ); +} +/*-----------------------------------------------------------*/ + +void vRaisePrivilege( void ) /* __attribute__ (( naked )) PRIVILEGED_FUNCTION */ +{ + __asm volatile + ( + " mrs r0, control \n" /* Read the CONTROL register. */ + " bic r0, #1 \n" /* Clear the bit 0. */ + " msr control, r0 \n" /* Write back the new CONTROL value. */ + " bx lr \n" /* Return to the caller. */ + ::: "r0", "memory" + ); +} +/*-----------------------------------------------------------*/ + +void vResetPrivilege( void ) /* __attribute__ (( naked )) */ +{ + __asm volatile + ( + " mrs r0, control \n" /* r0 = CONTROL. */ + " orr r0, #1 \n" /* r0 = r0 | 1. */ + " msr control, r0 \n" /* CONTROL = r0. */ + " bx lr \n" /* Return to the caller. */ + :::"r0", "memory" + ); +} +/*-----------------------------------------------------------*/ + +void vStartFirstTask( void ) /* __attribute__ (( naked )) PRIVILEGED_FUNCTION */ +{ + __asm volatile + ( + " ldr r0, xVTORConst \n" /* Use the NVIC offset register to locate the stack. */ + " ldr r0, [r0] \n" /* Read the VTOR register which gives the address of vector table. */ + " ldr r0, [r0] \n" /* The first entry in vector table is stack pointer. */ + " msr msp, r0 \n" /* Set the MSP back to the start of the stack. */ + " cpsie i \n" /* Globally enable interrupts. */ + " cpsie f \n" + " dsb \n" + " isb \n" + " svc %0 \n" /* System call to start the first task. */ + " nop \n" + " \n" + " .align 4 \n" + "xVTORConst: .word 0xe000ed08 \n" + :: "i" ( portSVC_START_SCHEDULER ) : "memory" + ); +} +/*-----------------------------------------------------------*/ + +uint32_t ulSetInterruptMask( void ) /* __attribute__(( naked )) PRIVILEGED_FUNCTION */ +{ + __asm volatile + ( + " mrs r0, basepri \n" /* r0 = basepri. Return original basepri value. */ + " mov r1, %0 \n" /* r1 = configMAX_SYSCALL_INTERRUPT_PRIORITY. */ + " msr basepri, r1 \n" /* Disable interrupts upto configMAX_SYSCALL_INTERRUPT_PRIORITY. */ + " dsb \n" + " isb \n" + " bx lr \n" /* Return. */ + :: "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY ) : "memory" + ); +} +/*-----------------------------------------------------------*/ + +void vClearInterruptMask( __attribute__( ( unused ) ) uint32_t ulMask ) /* __attribute__(( naked )) PRIVILEGED_FUNCTION */ +{ + __asm volatile + ( + " msr basepri, r0 \n" /* basepri = ulMask. */ + " dsb \n" + " isb \n" + " bx lr \n" /* Return. */ + ::: "memory" + ); +} +/*-----------------------------------------------------------*/ + +void PendSV_Handler( void ) /* __attribute__ (( naked )) PRIVILEGED_FUNCTION */ +{ + __asm volatile + ( + " .syntax unified \n" + " \n" + " mrs r0, psp \n" /* Read PSP in r0. */ + #if( configENABLE_FPU == 1 ) + " tst lr, #0x10 \n" /* Test Bit[4] in LR. Bit[4] of EXC_RETURN is 0 if the FPU is in use. */ + " it eq \n" + " vstmdbeq r0!, {s16-s31} \n" /* Store the FPU registers which are not saved automatically. */ + #endif /* configENABLE_FPU */ + #if( configENABLE_MPU == 1 ) + " mrs r1, psplim \n" /* r1 = PSPLIM. */ + " mrs r2, control \n" /* r2 = CONTROL. */ + " mov r3, lr \n" /* r3 = LR/EXC_RETURN. */ + " stmdb r0!, {r1-r11} \n" /* Store on the stack - PSPLIM, CONTROL, LR and registers that are not automatically saved. */ + #else /* configENABLE_MPU */ + " mrs r2, psplim \n" /* r2 = PSPLIM. */ + " mov r3, lr \n" /* r3 = LR/EXC_RETURN. */ + " stmdb r0!, {r2-r11} \n" /* Store on the stack - PSPLIM, LR and registers that are not automatically saved. */ + #endif /* configENABLE_MPU */ + " \n" + " ldr r2, pxCurrentTCBConst \n" /* Read the location of pxCurrentTCB i.e. &( pxCurrentTCB ). */ + " ldr r1, [r2] \n" /* Read pxCurrentTCB. */ + " str r0, [r1] \n" /* Save the new top of stack in TCB. */ + " \n" + " mov r0, %0 \n" /* r0 = configMAX_SYSCALL_INTERRUPT_PRIORITY */ + " msr basepri, r0 \n" /* Disable interrupts upto configMAX_SYSCALL_INTERRUPT_PRIORITY. */ + " dsb \n" + " isb \n" + " bl vTaskSwitchContext \n" + " mov r0, #0 \n" /* r0 = 0. */ + " msr basepri, r0 \n" /* Enable interrupts. */ + " \n" + " ldr r2, pxCurrentTCBConst \n" /* Read the location of pxCurrentTCB i.e. &( pxCurrentTCB ). */ + " ldr r1, [r2] \n" /* Read pxCurrentTCB. */ + " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. r0 now points to the top of stack. */ + " \n" + #if( configENABLE_MPU == 1 ) + " dmb \n" /* Complete outstanding transfers before disabling MPU. */ + " ldr r2, xMPUCTRLConst \n" /* r2 = 0xe000ed94 [Location of MPU_CTRL]. */ + " ldr r4, [r2] \n" /* Read the value of MPU_CTRL. */ + " bic r4, #1 \n" /* r4 = r4 & ~1 i.e. Clear the bit 0 in r4. */ + " str r4, [r2] \n" /* Disable MPU. */ + " \n" + " adds r1, #4 \n" /* r1 = r1 + 4. r1 now points to MAIR0 in TCB. */ + " ldr r3, [r1] \n" /* r3 = *r1 i.e. r3 = MAIR0. */ + " ldr r2, xMAIR0Const \n" /* r2 = 0xe000edc0 [Location of MAIR0]. */ + " str r3, [r2] \n" /* Program MAIR0. */ + " ldr r2, xRNRConst \n" /* r2 = 0xe000ed98 [Location of RNR]. */ + " movs r3, #4 \n" /* r3 = 4. */ + " str r3, [r2] \n" /* Program RNR = 4. */ + " adds r1, #4 \n" /* r1 = r1 + 4. r1 now points to first RBAR in TCB. */ + " ldr r2, xRBARConst \n" /* r2 = 0xe000ed9c [Location of RBAR]. */ + " ldmia r1!, {r4-r11} \n" /* Read 4 sets of RBAR/RLAR registers from TCB. */ + " stmia r2!, {r4-r11} \n" /* Write 4 set of RBAR/RLAR registers using alias registers. */ + " \n" + " ldr r2, xMPUCTRLConst \n" /* r2 = 0xe000ed94 [Location of MPU_CTRL]. */ + " ldr r4, [r2] \n" /* Read the value of MPU_CTRL. */ + " orr r4, #1 \n" /* r4 = r4 | 1 i.e. Set the bit 0 in r4. */ + " str r4, [r2] \n" /* Enable MPU. */ + " dsb \n" /* Force memory writes before continuing. */ + #endif /* configENABLE_MPU */ + " \n" + #if( configENABLE_MPU == 1 ) + " ldmia r0!, {r1-r11} \n" /* Read from stack - r1 = PSPLIM, r2 = CONTROL, r3 = LR and r4-r11 restored. */ + #else /* configENABLE_MPU */ + " ldmia r0!, {r2-r11} \n" /* Read from stack - r2 = PSPLIM, r3 = LR and r4-r11 restored. */ + #endif /* configENABLE_MPU */ + " \n" + #if( configENABLE_FPU == 1 ) + " tst r3, #0x10 \n" /* Test Bit[4] in LR. Bit[4] of EXC_RETURN is 0 if the FPU is in use. */ + " it eq \n" + " vldmiaeq r0!, {s16-s31} \n" /* Restore the FPU registers which are not restored automatically. */ + #endif /* configENABLE_FPU */ + " \n" + #if( configENABLE_MPU == 1 ) + " msr psplim, r1 \n" /* Restore the PSPLIM register value for the task. */ + " msr control, r2 \n" /* Restore the CONTROL register value for the task. */ + #else /* configENABLE_MPU */ + " msr psplim, r2 \n" /* Restore the PSPLIM register value for the task. */ + #endif /* configENABLE_MPU */ + " msr psp, r0 \n" /* Remember the new top of stack for the task. */ + " bx r3 \n" + " \n" + " .align 4 \n" + "pxCurrentTCBConst: .word pxCurrentTCB \n" + #if( configENABLE_MPU == 1 ) + "xMPUCTRLConst: .word 0xe000ed94 \n" + "xMAIR0Const: .word 0xe000edc0 \n" + "xRNRConst: .word 0xe000ed98 \n" + "xRBARConst: .word 0xe000ed9c \n" + #endif /* configENABLE_MPU */ + :: "i"( configMAX_SYSCALL_INTERRUPT_PRIORITY ) + ); +} +/*-----------------------------------------------------------*/ + +void SVC_Handler( void ) /* __attribute__ (( naked )) PRIVILEGED_FUNCTION */ +{ + __asm volatile + ( + " tst lr, #4 \n" + " ite eq \n" + " mrseq r0, msp \n" + " mrsne r0, psp \n" + " ldr r1, svchandler_address_const \n" + " bx r1 \n" + " \n" + " .align 4 \n" + "svchandler_address_const: .word vPortSVCHandler_C \n" + ); +} +/*-----------------------------------------------------------*/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portasm.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portasm.h new file mode 100644 index 0000000..f6220c9 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portasm.h @@ -0,0 +1,113 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 __PORT_ASM_H__ +#define __PORT_ASM_H__ + +/* Scheduler includes. */ +#include "FreeRTOS.h" + +/* MPU wrappers includes. */ +#include "mpu_wrappers.h" + +/** + * @brief Restore the context of the first task so that the first task starts + * executing. + */ +void vRestoreContextOfFirstTask( void ) __attribute__ (( naked )) PRIVILEGED_FUNCTION; + +/** + * @brief Checks whether or not the processor is privileged. + * + * @return 1 if the processor is already privileged, 0 otherwise. + */ +BaseType_t xIsPrivileged( void ) __attribute__ (( naked )); + +/** + * @brief Raises the privilege level by clearing the bit 0 of the CONTROL + * register. + * + * @note This is a privileged function and should only be called from the kenrel + * code. + * + * Bit 0 of the CONTROL register defines the privilege level of Thread Mode. + * Bit[0] = 0 --> The processor is running privileged + * Bit[0] = 1 --> The processor is running unprivileged. + */ +void vRaisePrivilege( void ) __attribute__ (( naked )) PRIVILEGED_FUNCTION; + +/** + * @brief Lowers the privilege level by setting the bit 0 of the CONTROL + * register. + * + * Bit 0 of the CONTROL register defines the privilege level of Thread Mode. + * Bit[0] = 0 --> The processor is running privileged + * Bit[0] = 1 --> The processor is running unprivileged. + */ +void vResetPrivilege( void ) __attribute__ (( naked )); + +/** + * @brief Starts the first task. + */ +void vStartFirstTask( void ) __attribute__ (( naked )) PRIVILEGED_FUNCTION; + +/** + * @brief Disables interrupts. + */ +uint32_t ulSetInterruptMask( void ) __attribute__(( naked )) PRIVILEGED_FUNCTION; + +/** + * @brief Enables interrupts. + */ +void vClearInterruptMask( uint32_t ulMask ) __attribute__(( naked )) PRIVILEGED_FUNCTION; + +/** + * @brief PendSV Exception handler. + */ +void PendSV_Handler( void ) __attribute__ (( naked )) PRIVILEGED_FUNCTION; + +/** + * @brief SVC Handler. + */ +void SVC_Handler( void ) __attribute__ (( naked )) PRIVILEGED_FUNCTION; + +/** + * @brief Allocate a Secure context for the calling task. + * + * @param[in] ulSecureStackSize The size of the stack to be allocated on the + * secure side for the calling task. + */ +void vPortAllocateSecureContext( uint32_t ulSecureStackSize ) __attribute__ (( naked )); + +/** + * @brief Free the task's secure context. + * + * @param[in] pulTCB Pointer to the Task Control Block (TCB) of the task. + */ +void vPortFreeSecureContext( uint32_t *pulTCB ) __attribute__ (( naked )) PRIVILEGED_FUNCTION; + +#endif /* __PORT_ASM_H__ */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portmacro.h b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portmacro.h new file mode 100644 index 0000000..4155edc --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/GCC/ARM_CM33_NTZ/non_secure/portmacro.h @@ -0,0 +1,301 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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. + *------------------------------------------------------------------------------ + */ + +#ifndef configENABLE_FPU + #error configENABLE_FPU must be defined in FreeRTOSConfig.h. Set configENABLE_FPU to 1 to enable the FPU or 0 to disable the FPU. +#endif /* configENABLE_FPU */ + +#ifndef configENABLE_MPU + #error configENABLE_MPU must be defined in FreeRTOSConfig.h. Set configENABLE_MPU to 1 to enable the MPU or 0 to disable the MPU. +#endif /* configENABLE_MPU */ + +#ifndef configENABLE_TRUSTZONE + #error configENABLE_TRUSTZONE must be defined in FreeRTOSConfig.h. Set configENABLE_TRUSTZONE to 1 to enable TrustZone or 0 to disable TrustZone. +#endif /* configENABLE_TRUSTZONE */ + +/*-----------------------------------------------------------*/ + +/** + * @brief Type definitions. + */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG long +#define portSHORT short +#define portSTACK_TYPE uint32_t +#define portBASE_TYPE long + +typedef portSTACK_TYPE StackType_t; +typedef long BaseType_t; +typedef unsigned long UBaseType_t; + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef uint16_t TickType_t; + #define portMAX_DELAY ( TickType_t ) 0xffff +#else + typedef uint32_t TickType_t; + #define portMAX_DELAY ( TickType_t ) 0xffffffffUL + + /* 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 +#endif +/*-----------------------------------------------------------*/ + +/** + * Architecture specifics. + */ +#define portARCH_NAME "Cortex-M33" +#define portSTACK_GROWTH ( -1 ) +#define portTICK_PERIOD_MS ( ( TickType_t ) 1000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 8 +#define portNOP() +#define portINLINE __inline +#ifndef portFORCE_INLINE + #define portFORCE_INLINE inline __attribute__(( always_inline )) +#endif +#define portHAS_STACK_OVERFLOW_CHECKING 1 +#define portDONT_DISCARD __attribute__(( used )) +/*-----------------------------------------------------------*/ + +/** + * @brief Extern declarations. + */ +extern BaseType_t xPortIsInsideInterrupt( void ); + +extern void vPortYield( void ) /* PRIVILEGED_FUNCTION */; + +extern void vPortEnterCritical( void ) /* PRIVILEGED_FUNCTION */; +extern void vPortExitCritical( void ) /* PRIVILEGED_FUNCTION */; + +extern uint32_t ulSetInterruptMask( void ) /* __attribute__(( naked )) PRIVILEGED_FUNCTION */; +extern void vClearInterruptMask( uint32_t ulMask ) /* __attribute__(( naked )) PRIVILEGED_FUNCTION */; + +#if( configENABLE_TRUSTZONE == 1 ) + extern void vPortAllocateSecureContext( uint32_t ulSecureStackSize ); /* __attribute__ (( naked )) */ + extern void vPortFreeSecureContext( uint32_t *pulTCB ) /* __attribute__ (( naked )) PRIVILEGED_FUNCTION */; +#endif /* configENABLE_TRUSTZONE */ + +#if( configENABLE_MPU == 1 ) + extern BaseType_t xIsPrivileged( void ) /* __attribute__ (( naked )) */; + extern void vResetPrivilege( void ) /* __attribute__ (( naked )) */; +#endif /* configENABLE_MPU */ +/*-----------------------------------------------------------*/ + +/** + * @brief MPU specific constants. + */ +#if( configENABLE_MPU == 1 ) + #define portUSING_MPU_WRAPPERS 1 + #define portPRIVILEGE_BIT ( 0x80000000UL ) +#else + #define portPRIVILEGE_BIT ( 0x0UL ) +#endif /* configENABLE_MPU */ + + +/* MPU regions. */ +#define portPRIVILEGED_FLASH_REGION ( 0UL ) +#define portUNPRIVILEGED_FLASH_REGION ( 1UL ) +#define portUNPRIVILEGED_SYSCALLS_REGION ( 2UL ) +#define portPRIVILEGED_RAM_REGION ( 3UL ) +#define portSTACK_REGION ( 4UL ) +#define portFIRST_CONFIGURABLE_REGION ( 5UL ) +#define portLAST_CONFIGURABLE_REGION ( 7UL ) +#define portNUM_CONFIGURABLE_REGIONS ( ( portLAST_CONFIGURABLE_REGION - portFIRST_CONFIGURABLE_REGION ) + 1 ) +#define portTOTAL_NUM_REGIONS ( portNUM_CONFIGURABLE_REGIONS + 1 ) /* Plus one to make space for the stack region. */ + +/* Device memory attributes used in MPU_MAIR registers. + * + * 8-bit values encoded as follows: + * Bit[7:4] - 0000 - Device Memory + * Bit[3:2] - 00 --> Device-nGnRnE + * 01 --> Device-nGnRE + * 10 --> Device-nGRE + * 11 --> Device-GRE + * Bit[1:0] - 00, Reserved. + */ +#define portMPU_DEVICE_MEMORY_nGnRnE ( 0x00 ) /* 0000 0000 */ +#define portMPU_DEVICE_MEMORY_nGnRE ( 0x04 ) /* 0000 0100 */ +#define portMPU_DEVICE_MEMORY_nGRE ( 0x08 ) /* 0000 1000 */ +#define portMPU_DEVICE_MEMORY_GRE ( 0x0C ) /* 0000 1100 */ + +/* Normal memory attributes used in MPU_MAIR registers. */ +#define portMPU_NORMAL_MEMORY_NON_CACHEABLE ( 0x44 ) /* Non-cacheable. */ +#define portMPU_NORMAL_MEMORY_BUFFERABLE_CACHEABLE ( 0xFF ) /* Non-Transient, Write-back, Read-Allocate and Write-Allocate. */ + +/* Attributes used in MPU_RBAR registers. */ +#define portMPU_REGION_NON_SHAREABLE ( 0UL << 3UL ) +#define portMPU_REGION_INNER_SHAREABLE ( 1UL << 3UL ) +#define portMPU_REGION_OUTER_SHAREABLE ( 2UL << 3UL ) + +#define portMPU_REGION_PRIVILEGED_READ_WRITE ( 0UL << 1UL ) +#define portMPU_REGION_READ_WRITE ( 1UL << 1UL ) +#define portMPU_REGION_PRIVILEGED_READ_ONLY ( 2UL << 1UL ) +#define portMPU_REGION_READ_ONLY ( 3UL << 1UL ) + +#define portMPU_REGION_EXECUTE_NEVER ( 1UL ) +/*-----------------------------------------------------------*/ + +/** + * @brief Settings to define an MPU region. + */ +typedef struct MPURegionSettings +{ + uint32_t ulRBAR; /**< RBAR for the region. */ + uint32_t ulRLAR; /**< RLAR for the region. */ +} MPURegionSettings_t; + +/** + * @brief MPU settings as stored in the TCB. + */ +typedef struct MPU_SETTINGS +{ + uint32_t ulMAIR0; /**< MAIR0 for the task containing attributes for all the 4 per task regions. */ + MPURegionSettings_t xRegionsSettings[ portTOTAL_NUM_REGIONS ]; /**< Settings for 4 per task regions. */ +} xMPU_SETTINGS; +/*-----------------------------------------------------------*/ + +/** + * @brief SVC numbers. + */ +#define portSVC_ALLOCATE_SECURE_CONTEXT 0 +#define portSVC_FREE_SECURE_CONTEXT 1 +#define portSVC_START_SCHEDULER 2 +#define portSVC_RAISE_PRIVILEGE 3 +/*-----------------------------------------------------------*/ + +/** + * @brief Scheduler utilities. + */ +#define portYIELD() vPortYield() +#define portNVIC_INT_CTRL_REG ( * ( ( volatile uint32_t * ) 0xe000ed04 ) ) +#define portNVIC_PENDSVSET_BIT ( 1UL << 28UL ) +#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT +#define portYIELD_FROM_ISR( x ) portEND_SWITCHING_ISR( x ) +/*-----------------------------------------------------------*/ + +/** + * @brief Critical section management. + */ +#define portSET_INTERRUPT_MASK_FROM_ISR() ulSetInterruptMask() +#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vClearInterruptMask( x ) +#define portDISABLE_INTERRUPTS() ulSetInterruptMask() +#define portENABLE_INTERRUPTS() vClearInterruptMask( 0 ) +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() +/*-----------------------------------------------------------*/ + +/** + * @brief Task function macros as described on the FreeRTOS.org WEB site. + */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) +/*-----------------------------------------------------------*/ + +#if( configENABLE_TRUSTZONE == 1 ) + /** + * @brief Allocate a secure context for the task. + * + * Tasks are not created with a secure context. Any task that is going to call + * secure functions must call portALLOCATE_SECURE_CONTEXT() to allocate itself a + * secure context before it calls any secure function. + * + * @param[in] ulSecureStackSize The size of the secure stack to be allocated. + */ + #define portALLOCATE_SECURE_CONTEXT( ulSecureStackSize ) vPortAllocateSecureContext( ulSecureStackSize ) + + /** + * @brief Called when a task is deleted to delete the task's secure context, + * if it has one. + * + * @param[in] pxTCB The TCB of the task being deleted. + */ + #define portCLEAN_UP_TCB( pxTCB ) vPortFreeSecureContext( ( uint32_t * ) pxTCB ) +#else + #define portALLOCATE_SECURE_CONTEXT( ulSecureStackSize ) + #define portCLEAN_UP_TCB( pxTCB ) +#endif /* configENABLE_TRUSTZONE */ +/*-----------------------------------------------------------*/ + +#if( configENABLE_MPU == 1 ) + /** + * @brief Checks whether or not the processor is privileged. + * + * @return 1 if the processor is already privileged, 0 otherwise. + */ + #define portIS_PRIVILEGED() xIsPrivileged() + + /** + * @brief Raise an SVC request to raise privilege. + * + * The SVC handler checks that the SVC was raised from a system call and only + * then it raises the privilege. If this is called from any other place, + * the privilege is not raised. + */ + #define portRAISE_PRIVILEGE() __asm volatile ( "svc %0 \n" :: "i" ( portSVC_RAISE_PRIVILEGE ) : "memory" ); + + /** + * @brief Lowers the privilege level by setting the bit 0 of the CONTROL + * register. + */ + #define portRESET_PRIVILEGE() vResetPrivilege() +#else + #define portIS_PRIVILEGED() + #define portRAISE_PRIVILEGE() + #define portRESET_PRIVILEGE() +#endif /* configENABLE_MPU */ +/*-----------------------------------------------------------*/ + +/** + * @brief Barriers. + */ +#define portMEMORY_BARRIER() __asm volatile( "" ::: "memory" ) +/*-----------------------------------------------------------*/ + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/ReadMe.url b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/ReadMe.url new file mode 100644 index 0000000..6c23737 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/ReadMe.url @@ -0,0 +1,5 @@ +[{000214A0-0000-0000-C000-000000000046}] +Prop3=19,2 +[InternetShortcut] +URL=http://www.freertos.org/a00111.html +IDList= diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_1.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_1.c new file mode 100644 index 0000000..ef1de57 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_1.c @@ -0,0 +1,146 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 simplest possible implementation of pvPortMalloc(). Note that this + * implementation does NOT allow allocated memory to be freed again. + * + * See heap_2.c, heap_3.c and heap_4.c for alternative implementations, and the + * memory management pages of http://www.FreeRTOS.org for more information. + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) + #error This file must not be used if configSUPPORT_DYNAMIC_ALLOCATION is 0 +#endif + +/* A few bytes might be lost to byte aligning the heap start address. */ +#define configADJUSTED_HEAP_SIZE ( configTOTAL_HEAP_SIZE - portBYTE_ALIGNMENT ) + +/* Allocate the memory for the heap. */ +#if( configAPPLICATION_ALLOCATED_HEAP == 1 ) + /* The application writer has already defined the array used for the RTOS + heap - probably so it can be placed in a special segment or address. */ + extern uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; +#else + static uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; +#endif /* configAPPLICATION_ALLOCATED_HEAP */ + +/* Index into the ucHeap array. */ +static size_t xNextFreeByte = ( size_t ) 0; + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn = NULL; +static uint8_t *pucAlignedHeap = NULL; + + /* Ensure that blocks are always aligned to the required number of bytes. */ + #if( portBYTE_ALIGNMENT != 1 ) + { + if( xWantedSize & portBYTE_ALIGNMENT_MASK ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + } + } + #endif + + vTaskSuspendAll(); + { + if( pucAlignedHeap == NULL ) + { + /* Ensure the heap starts on a correctly aligned boundary. */ + pucAlignedHeap = ( uint8_t * ) ( ( ( portPOINTER_SIZE_TYPE ) &ucHeap[ portBYTE_ALIGNMENT ] ) & ( ~( ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) ) ); + } + + /* Check there is enough room left for the allocation. */ + if( ( ( xNextFreeByte + xWantedSize ) < configADJUSTED_HEAP_SIZE ) && + ( ( xNextFreeByte + xWantedSize ) > xNextFreeByte ) )/* Check for overflow. */ + { + /* Return the next free byte then increment the index past this + block. */ + pvReturn = pucAlignedHeap + xNextFreeByte; + xNextFreeByte += xWantedSize; + } + + traceMALLOC( pvReturn, xWantedSize ); + } + ( void ) xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + /* Memory cannot be freed using this scheme. See heap_2.c, heap_3.c and + heap_4.c for alternative implementations, and the memory management pages of + http://www.FreeRTOS.org for more information. */ + ( void ) pv; + + /* Force an assert as it is invalid to call this function. */ + configASSERT( pv == NULL ); +} +/*-----------------------------------------------------------*/ + +void vPortInitialiseBlocks( void ) +{ + /* Only required when static memory is not cleared. */ + xNextFreeByte = ( size_t ) 0; +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return ( configADJUSTED_HEAP_SIZE - xNextFreeByte ); +} + + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_2.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_2.c new file mode 100644 index 0000000..903e330 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_2.c @@ -0,0 +1,272 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* + * A sample implementation of pvPortMalloc() and vPortFree() that permits + * allocated blocks to be freed, but does not combine adjacent free blocks + * into a single larger block (and so will fragment memory). See heap_4.c for + * an equivalent that does combine adjacent blocks into single larger blocks. + * + * See heap_1.c, heap_3.c and heap_4.c for alternative implementations, and the + * memory management pages of http://www.FreeRTOS.org for more information. + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) + #error This file must not be used if configSUPPORT_DYNAMIC_ALLOCATION is 0 +#endif + +/* A few bytes might be lost to byte aligning the heap start address. */ +#define configADJUSTED_HEAP_SIZE ( configTOTAL_HEAP_SIZE - portBYTE_ALIGNMENT ) + +/* + * Initialises the heap structures before their first use. + */ +static void prvHeapInit( void ); + +/* Allocate the memory for the heap. */ +#if( configAPPLICATION_ALLOCATED_HEAP == 1 ) + /* The application writer has already defined the array used for the RTOS + heap - probably so it can be placed in a special segment or address. */ + extern uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; +#else + static uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; +#endif /* configAPPLICATION_ALLOCATED_HEAP */ + + +/* Define the linked list structure. This is used to link free blocks in order +of their size. */ +typedef struct A_BLOCK_LINK +{ + struct A_BLOCK_LINK *pxNextFreeBlock; /*<< The next free block in the list. */ + size_t xBlockSize; /*<< The size of the free block. */ +} BlockLink_t; + + +static const uint16_t heapSTRUCT_SIZE = ( ( sizeof ( BlockLink_t ) + ( portBYTE_ALIGNMENT - 1 ) ) & ~portBYTE_ALIGNMENT_MASK ); +#define heapMINIMUM_BLOCK_SIZE ( ( size_t ) ( heapSTRUCT_SIZE * 2 ) ) + +/* Create a couple of list links to mark the start and end of the list. */ +static BlockLink_t xStart, xEnd; + +/* Keeps track of the number of free bytes remaining, but says nothing about +fragmentation. */ +static size_t xFreeBytesRemaining = configADJUSTED_HEAP_SIZE; + +/* STATIC FUNCTIONS ARE DEFINED AS MACROS TO MINIMIZE THE FUNCTION CALL DEPTH. */ + +/* + * Insert a block into the list of free blocks - which is ordered by size of + * the block. Small blocks at the start of the list and large blocks at the end + * of the list. + */ +#define prvInsertBlockIntoFreeList( pxBlockToInsert ) \ +{ \ +BlockLink_t *pxIterator; \ +size_t xBlockSize; \ + \ + xBlockSize = pxBlockToInsert->xBlockSize; \ + \ + /* Iterate through the list until a block is found that has a larger size */ \ + /* than the block we are inserting. */ \ + for( pxIterator = &xStart; pxIterator->pxNextFreeBlock->xBlockSize < xBlockSize; pxIterator = pxIterator->pxNextFreeBlock ) \ + { \ + /* There is nothing to do here - just iterate to the correct position. */ \ + } \ + \ + /* Update the list to include the block being inserted in the correct */ \ + /* position. */ \ + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock; \ + pxIterator->pxNextFreeBlock = pxBlockToInsert; \ +} +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +BlockLink_t *pxBlock, *pxPreviousBlock, *pxNewBlockLink; +static BaseType_t xHeapHasBeenInitialised = pdFALSE; +void *pvReturn = NULL; + + vTaskSuspendAll(); + { + /* If this is the first call to malloc then the heap will require + initialisation to setup the list of free blocks. */ + if( xHeapHasBeenInitialised == pdFALSE ) + { + prvHeapInit(); + xHeapHasBeenInitialised = pdTRUE; + } + + /* The wanted size is increased so it can contain a BlockLink_t + structure in addition to the requested amount of bytes. */ + if( xWantedSize > 0 ) + { + xWantedSize += heapSTRUCT_SIZE; + + /* Ensure that blocks are always aligned to the required number of bytes. */ + if( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) != 0 ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + } + } + + if( ( xWantedSize > 0 ) && ( xWantedSize < configADJUSTED_HEAP_SIZE ) ) + { + /* Blocks are stored in byte order - traverse the list from the start + (smallest) block until one of adequate size is found. */ + pxPreviousBlock = &xStart; + pxBlock = xStart.pxNextFreeBlock; + while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock != NULL ) ) + { + pxPreviousBlock = pxBlock; + pxBlock = pxBlock->pxNextFreeBlock; + } + + /* If we found the end marker then a block of adequate size was not found. */ + if( pxBlock != &xEnd ) + { + /* Return the memory space - jumping over the BlockLink_t structure + at its start. */ + pvReturn = ( void * ) ( ( ( uint8_t * ) pxPreviousBlock->pxNextFreeBlock ) + heapSTRUCT_SIZE ); + + /* This block is being returned for use so must be taken out of the + list of free blocks. */ + pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock; + + /* If the block is larger than required it can be split into two. */ + if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE ) + { + /* This block is to be split into two. Create a new block + following the number of bytes requested. The void cast is + used to prevent byte alignment warnings from the compiler. */ + pxNewBlockLink = ( void * ) ( ( ( uint8_t * ) pxBlock ) + xWantedSize ); + + /* Calculate the sizes of two blocks split from the single + block. */ + pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize; + pxBlock->xBlockSize = xWantedSize; + + /* Insert the new block into the list of free blocks. */ + prvInsertBlockIntoFreeList( ( pxNewBlockLink ) ); + } + + xFreeBytesRemaining -= pxBlock->xBlockSize; + } + } + + traceMALLOC( pvReturn, xWantedSize ); + } + ( void ) xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ +uint8_t *puc = ( uint8_t * ) pv; +BlockLink_t *pxLink; + + if( pv != NULL ) + { + /* The memory being freed will have an BlockLink_t structure immediately + before it. */ + puc -= heapSTRUCT_SIZE; + + /* This unexpected casting is to keep some compilers from issuing + byte alignment warnings. */ + pxLink = ( void * ) puc; + + vTaskSuspendAll(); + { + /* Add this block to the list of free blocks. */ + prvInsertBlockIntoFreeList( ( ( BlockLink_t * ) pxLink ) ); + xFreeBytesRemaining += pxLink->xBlockSize; + traceFREE( pv, pxLink->xBlockSize ); + } + ( void ) xTaskResumeAll(); + } +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return xFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +void vPortInitialiseBlocks( void ) +{ + /* This just exists to keep the linker quiet. */ +} +/*-----------------------------------------------------------*/ + +static void prvHeapInit( void ) +{ +BlockLink_t *pxFirstFreeBlock; +uint8_t *pucAlignedHeap; + + /* Ensure the heap starts on a correctly aligned boundary. */ + pucAlignedHeap = ( uint8_t * ) ( ( ( portPOINTER_SIZE_TYPE ) &ucHeap[ portBYTE_ALIGNMENT ] ) & ( ~( ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) ) ); + + /* xStart is used to hold a pointer to the first item in the list of free + blocks. The void cast is used to prevent compiler warnings. */ + xStart.pxNextFreeBlock = ( void * ) pucAlignedHeap; + xStart.xBlockSize = ( size_t ) 0; + + /* xEnd is used to mark the end of the list of free blocks. */ + xEnd.xBlockSize = configADJUSTED_HEAP_SIZE; + xEnd.pxNextFreeBlock = NULL; + + /* To start with there is a single free block that is sized to take up the + entire heap space. */ + pxFirstFreeBlock = ( void * ) pucAlignedHeap; + pxFirstFreeBlock->xBlockSize = configADJUSTED_HEAP_SIZE; + pxFirstFreeBlock->pxNextFreeBlock = &xEnd; +} +/*-----------------------------------------------------------*/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_3.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_3.c new file mode 100644 index 0000000..2a101a1 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_3.c @@ -0,0 +1,97 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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 pvPortMalloc() and vPortFree() that relies on the + * compilers own malloc() and free() implementations. + * + * This file can only be used if the linker is configured to to generate + * a heap memory area. + * + * See heap_1.c, heap_2.c and heap_4.c for alternative implementations, and the + * memory management pages of http://www.FreeRTOS.org for more information. + */ + +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) + #error This file must not be used if configSUPPORT_DYNAMIC_ALLOCATION is 0 +#endif + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn; + + vTaskSuspendAll(); + { + pvReturn = malloc( xWantedSize ); + traceMALLOC( pvReturn, xWantedSize ); + } + ( void ) xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + if( pv ) + { + vTaskSuspendAll(); + { + free( pv ); + traceFREE( pv, 0 ); + } + ( void ) xTaskResumeAll(); + } +} + + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_4.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_4.c new file mode 100644 index 0000000..4a95b5b --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_4.c @@ -0,0 +1,492 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* + * A sample implementation of pvPortMalloc() and vPortFree() that combines + * (coalescences) adjacent memory blocks as they are freed, and in so doing + * limits memory fragmentation. + * + * See heap_1.c, heap_2.c and heap_3.c for alternative implementations, and the + * memory management pages of http://www.FreeRTOS.org for more information. + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) + #error This file must not be used if configSUPPORT_DYNAMIC_ALLOCATION is 0 +#endif + +/* Block sizes must not get too small. */ +#define heapMINIMUM_BLOCK_SIZE ( ( size_t ) ( xHeapStructSize << 1 ) ) + +/* Assumes 8bit bytes! */ +#define heapBITS_PER_BYTE ( ( size_t ) 8 ) + +/* Allocate the memory for the heap. */ +#if( configAPPLICATION_ALLOCATED_HEAP == 1 ) + /* The application writer has already defined the array used for the RTOS + heap - probably so it can be placed in a special segment or address. */ + extern uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; +#else + static uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; +#endif /* configAPPLICATION_ALLOCATED_HEAP */ + +/* Define the linked list structure. This is used to link free blocks in order +of their memory address. */ +typedef struct A_BLOCK_LINK +{ + struct A_BLOCK_LINK *pxNextFreeBlock; /*<< The next free block in the list. */ + size_t xBlockSize; /*<< The size of the free block. */ +} BlockLink_t; + +/*-----------------------------------------------------------*/ + +/* + * Inserts a block of memory that is being freed into the correct position in + * the list of free memory blocks. The block being freed will be merged with + * the block in front it and/or the block behind it if the memory blocks are + * adjacent to each other. + */ +static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert ); + +/* + * Called automatically to setup the required heap structures the first time + * pvPortMalloc() is called. + */ +static void prvHeapInit( void ); + +/*-----------------------------------------------------------*/ + +/* The size of the structure placed at the beginning of each allocated memory +block must by correctly byte aligned. */ +static const size_t xHeapStructSize = ( sizeof( BlockLink_t ) + ( ( size_t ) ( portBYTE_ALIGNMENT - 1 ) ) ) & ~( ( size_t ) portBYTE_ALIGNMENT_MASK ); + +/* Create a couple of list links to mark the start and end of the list. */ +static BlockLink_t xStart, *pxEnd = NULL; + +/* Keeps track of the number of calls to allocate and free memory as well as the +number of free bytes remaining, but says nothing about fragmentation. */ +static size_t xFreeBytesRemaining = 0U; +static size_t xMinimumEverFreeBytesRemaining = 0U; +static size_t xNumberOfSuccessfulAllocations = 0; +static size_t xNumberOfSuccessfulFrees = 0; + +/* Gets set to the top bit of an size_t type. When this bit in the xBlockSize +member of an BlockLink_t structure is set then the block belongs to the +application. When the bit is free the block is still part of the free heap +space. */ +static size_t xBlockAllocatedBit = 0; + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +BlockLink_t *pxBlock, *pxPreviousBlock, *pxNewBlockLink; +void *pvReturn = NULL; + + vTaskSuspendAll(); + { + /* If this is the first call to malloc then the heap will require + initialisation to setup the list of free blocks. */ + if( pxEnd == NULL ) + { + prvHeapInit(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Check the requested block size is not so large that the top bit is + set. The top bit of the block size member of the BlockLink_t structure + is used to determine who owns the block - the application or the + kernel, so it must be free. */ + if( ( xWantedSize & xBlockAllocatedBit ) == 0 ) + { + /* The wanted size is increased so it can contain a BlockLink_t + structure in addition to the requested amount of bytes. */ + if( xWantedSize > 0 ) + { + xWantedSize += xHeapStructSize; + + /* Ensure that blocks are always aligned to the required number + of bytes. */ + if( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) != 0x00 ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + configASSERT( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) == 0 ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( ( xWantedSize > 0 ) && ( xWantedSize <= xFreeBytesRemaining ) ) + { + /* Traverse the list from the start (lowest address) block until + one of adequate size is found. */ + pxPreviousBlock = &xStart; + pxBlock = xStart.pxNextFreeBlock; + while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock != NULL ) ) + { + pxPreviousBlock = pxBlock; + pxBlock = pxBlock->pxNextFreeBlock; + } + + /* If the end marker was reached then a block of adequate size + was not found. */ + if( pxBlock != pxEnd ) + { + /* Return the memory space pointed to - jumping over the + BlockLink_t structure at its start. */ + pvReturn = ( void * ) ( ( ( uint8_t * ) pxPreviousBlock->pxNextFreeBlock ) + xHeapStructSize ); + + /* This block is being returned for use so must be taken out + of the list of free blocks. */ + pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock; + + /* If the block is larger than required it can be split into + two. */ + if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE ) + { + /* This block is to be split into two. Create a new + block following the number of bytes requested. The void + cast is used to prevent byte alignment warnings from the + compiler. */ + pxNewBlockLink = ( void * ) ( ( ( uint8_t * ) pxBlock ) + xWantedSize ); + configASSERT( ( ( ( size_t ) pxNewBlockLink ) & portBYTE_ALIGNMENT_MASK ) == 0 ); + + /* Calculate the sizes of two blocks split from the + single block. */ + pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize; + pxBlock->xBlockSize = xWantedSize; + + /* Insert the new block into the list of free blocks. */ + prvInsertBlockIntoFreeList( pxNewBlockLink ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xFreeBytesRemaining -= pxBlock->xBlockSize; + + if( xFreeBytesRemaining < xMinimumEverFreeBytesRemaining ) + { + xMinimumEverFreeBytesRemaining = xFreeBytesRemaining; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The block is being returned - it is allocated and owned + by the application and has no "next" block. */ + pxBlock->xBlockSize |= xBlockAllocatedBit; + pxBlock->pxNextFreeBlock = NULL; + xNumberOfSuccessfulAllocations++; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceMALLOC( pvReturn, xWantedSize ); + } + ( void ) xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif + + configASSERT( ( ( ( size_t ) pvReturn ) & ( size_t ) portBYTE_ALIGNMENT_MASK ) == 0 ); + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ +uint8_t *puc = ( uint8_t * ) pv; +BlockLink_t *pxLink; + + if( pv != NULL ) + { + /* The memory being freed will have an BlockLink_t structure immediately + before it. */ + puc -= xHeapStructSize; + + /* This casting is to keep the compiler from issuing warnings. */ + pxLink = ( void * ) puc; + + /* Check the block is actually allocated. */ + configASSERT( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 ); + configASSERT( pxLink->pxNextFreeBlock == NULL ); + + if( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 ) + { + if( pxLink->pxNextFreeBlock == NULL ) + { + /* The block is being returned to the heap - it is no longer + allocated. */ + pxLink->xBlockSize &= ~xBlockAllocatedBit; + + vTaskSuspendAll(); + { + /* Add this block to the list of free blocks. */ + xFreeBytesRemaining += pxLink->xBlockSize; + traceFREE( pv, pxLink->xBlockSize ); + prvInsertBlockIntoFreeList( ( ( BlockLink_t * ) pxLink ) ); + xNumberOfSuccessfulFrees++; + } + ( void ) xTaskResumeAll(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return xFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +size_t xPortGetMinimumEverFreeHeapSize( void ) +{ + return xMinimumEverFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +void vPortInitialiseBlocks( void ) +{ + /* This just exists to keep the linker quiet. */ +} +/*-----------------------------------------------------------*/ + +static void prvHeapInit( void ) +{ +BlockLink_t *pxFirstFreeBlock; +uint8_t *pucAlignedHeap; +size_t uxAddress; +size_t xTotalHeapSize = configTOTAL_HEAP_SIZE; + + /* Ensure the heap starts on a correctly aligned boundary. */ + uxAddress = ( size_t ) ucHeap; + + if( ( uxAddress & portBYTE_ALIGNMENT_MASK ) != 0 ) + { + uxAddress += ( portBYTE_ALIGNMENT - 1 ); + uxAddress &= ~( ( size_t ) portBYTE_ALIGNMENT_MASK ); + xTotalHeapSize -= uxAddress - ( size_t ) ucHeap; + } + + pucAlignedHeap = ( uint8_t * ) uxAddress; + + /* xStart is used to hold a pointer to the first item in the list of free + blocks. The void cast is used to prevent compiler warnings. */ + xStart.pxNextFreeBlock = ( void * ) pucAlignedHeap; + xStart.xBlockSize = ( size_t ) 0; + + /* pxEnd is used to mark the end of the list of free blocks and is inserted + at the end of the heap space. */ + uxAddress = ( ( size_t ) pucAlignedHeap ) + xTotalHeapSize; + uxAddress -= xHeapStructSize; + uxAddress &= ~( ( size_t ) portBYTE_ALIGNMENT_MASK ); + pxEnd = ( void * ) uxAddress; + pxEnd->xBlockSize = 0; + pxEnd->pxNextFreeBlock = NULL; + + /* To start with there is a single free block that is sized to take up the + entire heap space, minus the space taken by pxEnd. */ + pxFirstFreeBlock = ( void * ) pucAlignedHeap; + pxFirstFreeBlock->xBlockSize = uxAddress - ( size_t ) pxFirstFreeBlock; + pxFirstFreeBlock->pxNextFreeBlock = pxEnd; + + /* Only one block exists - and it covers the entire usable heap space. */ + xMinimumEverFreeBytesRemaining = pxFirstFreeBlock->xBlockSize; + xFreeBytesRemaining = pxFirstFreeBlock->xBlockSize; + + /* Work out the position of the top bit in a size_t variable. */ + xBlockAllocatedBit = ( ( size_t ) 1 ) << ( ( sizeof( size_t ) * heapBITS_PER_BYTE ) - 1 ); +} +/*-----------------------------------------------------------*/ + +static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert ) +{ +BlockLink_t *pxIterator; +uint8_t *puc; + + /* Iterate through the list until a block is found that has a higher address + than the block being inserted. */ + for( pxIterator = &xStart; pxIterator->pxNextFreeBlock < pxBlockToInsert; pxIterator = pxIterator->pxNextFreeBlock ) + { + /* Nothing to do here, just iterate to the right position. */ + } + + /* Do the block being inserted, and the block it is being inserted after + make a contiguous block of memory? */ + puc = ( uint8_t * ) pxIterator; + if( ( puc + pxIterator->xBlockSize ) == ( uint8_t * ) pxBlockToInsert ) + { + pxIterator->xBlockSize += pxBlockToInsert->xBlockSize; + pxBlockToInsert = pxIterator; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Do the block being inserted, and the block it is being inserted before + make a contiguous block of memory? */ + puc = ( uint8_t * ) pxBlockToInsert; + if( ( puc + pxBlockToInsert->xBlockSize ) == ( uint8_t * ) pxIterator->pxNextFreeBlock ) + { + if( pxIterator->pxNextFreeBlock != pxEnd ) + { + /* Form one big block from the two blocks. */ + pxBlockToInsert->xBlockSize += pxIterator->pxNextFreeBlock->xBlockSize; + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock->pxNextFreeBlock; + } + else + { + pxBlockToInsert->pxNextFreeBlock = pxEnd; + } + } + else + { + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock; + } + + /* If the block being inserted plugged a gab, so was merged with the block + before and the block after, then it's pxNextFreeBlock pointer will have + already been set, and should not be set here as that would make it point + to itself. */ + if( pxIterator != pxBlockToInsert ) + { + pxIterator->pxNextFreeBlock = pxBlockToInsert; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } +} +/*-----------------------------------------------------------*/ + +void vPortGetHeapStats( HeapStats_t *pxHeapStats ) +{ +BlockLink_t *pxBlock; +size_t xBlocks = 0, xMaxSize = 0, xMinSize = portMAX_DELAY; /* portMAX_DELAY used as a portable way of getting the maximum value. */ + + vTaskSuspendAll(); + { + pxBlock = xStart.pxNextFreeBlock; + + /* pxBlock will be NULL if the heap has not been initialised. The heap + is initialised automatically when the first allocation is made. */ + if( pxBlock != NULL ) + { + do + { + /* Increment the number of blocks and record the largest block seen + so far. */ + xBlocks++; + + if( pxBlock->xBlockSize > xMaxSize ) + { + xMaxSize = pxBlock->xBlockSize; + } + + if( pxBlock->xBlockSize < xMinSize ) + { + xMinSize = pxBlock->xBlockSize; + } + + /* Move to the next block in the chain until the last block is + reached. */ + pxBlock = pxBlock->pxNextFreeBlock; + } while( pxBlock != pxEnd ); + } + } + xTaskResumeAll(); + + pxHeapStats->xSizeOfLargestFreeBlockInBytes = xMaxSize; + pxHeapStats->xSizeOfSmallestFreeBlockInBytes = xMinSize; + pxHeapStats->xNumberOfFreeBlocks = xBlocks; + + taskENTER_CRITICAL(); + { + pxHeapStats->xAvailableHeapSpaceInBytes = xFreeBytesRemaining; + pxHeapStats->xNumberOfSuccessfulAllocations = xNumberOfSuccessfulAllocations; + pxHeapStats->xNumberOfSuccessfulFrees = xNumberOfSuccessfulFrees; + pxHeapStats->xMinimumEverFreeBytesRemaining = xMinimumEverFreeBytesRemaining; + } + taskEXIT_CRITICAL(); +} + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_5.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_5.c new file mode 100644 index 0000000..009258c --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/MemMang/heap_5.c @@ -0,0 +1,547 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* + * A sample implementation of pvPortMalloc() that allows the heap to be defined + * across multiple non-contigous blocks and combines (coalescences) adjacent + * memory blocks as they are freed. + * + * See heap_1.c, heap_2.c, heap_3.c and heap_4.c for alternative + * implementations, and the memory management pages of http://www.FreeRTOS.org + * for more information. + * + * Usage notes: + * + * vPortDefineHeapRegions() ***must*** be called before pvPortMalloc(). + * pvPortMalloc() will be called if any task objects (tasks, queues, event + * groups, etc.) are created, therefore vPortDefineHeapRegions() ***must*** be + * called before any other objects are defined. + * + * vPortDefineHeapRegions() takes a single parameter. The parameter is an array + * of HeapRegion_t structures. HeapRegion_t is defined in portable.h as + * + * typedef struct HeapRegion + * { + * uint8_t *pucStartAddress; << Start address of a block of memory that will be part of the heap. + * size_t xSizeInBytes; << Size of the block of memory. + * } HeapRegion_t; + * + * The array is terminated using a NULL zero sized region definition, and the + * memory regions defined in the array ***must*** appear in address order from + * low address to high address. So the following is a valid example of how + * to use the function. + * + * HeapRegion_t xHeapRegions[] = + * { + * { ( uint8_t * ) 0x80000000UL, 0x10000 }, << Defines a block of 0x10000 bytes starting at address 0x80000000 + * { ( uint8_t * ) 0x90000000UL, 0xa0000 }, << Defines a block of 0xa0000 bytes starting at address of 0x90000000 + * { NULL, 0 } << Terminates the array. + * }; + * + * vPortDefineHeapRegions( xHeapRegions ); << Pass the array into vPortDefineHeapRegions(). + * + * Note 0x80000000 is the lower address so appears in the array first. + * + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) + #error This file must not be used if configSUPPORT_DYNAMIC_ALLOCATION is 0 +#endif + +/* Block sizes must not get too small. */ +#define heapMINIMUM_BLOCK_SIZE ( ( size_t ) ( xHeapStructSize << 1 ) ) + +/* Assumes 8bit bytes! */ +#define heapBITS_PER_BYTE ( ( size_t ) 8 ) + +/* Define the linked list structure. This is used to link free blocks in order +of their memory address. */ +typedef struct A_BLOCK_LINK +{ + struct A_BLOCK_LINK *pxNextFreeBlock; /*<< The next free block in the list. */ + size_t xBlockSize; /*<< The size of the free block. */ +} BlockLink_t; + +/*-----------------------------------------------------------*/ + +/* + * Inserts a block of memory that is being freed into the correct position in + * the list of free memory blocks. The block being freed will be merged with + * the block in front it and/or the block behind it if the memory blocks are + * adjacent to each other. + */ +static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert ); + +/*-----------------------------------------------------------*/ + +/* The size of the structure placed at the beginning of each allocated memory +block must by correctly byte aligned. */ +static const size_t xHeapStructSize = ( sizeof( BlockLink_t ) + ( ( size_t ) ( portBYTE_ALIGNMENT - 1 ) ) ) & ~( ( size_t ) portBYTE_ALIGNMENT_MASK ); + +/* Create a couple of list links to mark the start and end of the list. */ +static BlockLink_t xStart, *pxEnd = NULL; + +/* Keeps track of the number of calls to allocate and free memory as well as the +number of free bytes remaining, but says nothing about fragmentation. */ +static size_t xFreeBytesRemaining = 0U; +static size_t xMinimumEverFreeBytesRemaining = 0U; +static size_t xNumberOfSuccessfulAllocations = 0; +static size_t xNumberOfSuccessfulFrees = 0; + +/* Gets set to the top bit of an size_t type. When this bit in the xBlockSize +member of an BlockLink_t structure is set then the block belongs to the +application. When the bit is free the block is still part of the free heap +space. */ +static size_t xBlockAllocatedBit = 0; + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +BlockLink_t *pxBlock, *pxPreviousBlock, *pxNewBlockLink; +void *pvReturn = NULL; + + /* The heap must be initialised before the first call to + prvPortMalloc(). */ + configASSERT( pxEnd ); + + vTaskSuspendAll(); + { + /* Check the requested block size is not so large that the top bit is + set. The top bit of the block size member of the BlockLink_t structure + is used to determine who owns the block - the application or the + kernel, so it must be free. */ + if( ( xWantedSize & xBlockAllocatedBit ) == 0 ) + { + /* The wanted size is increased so it can contain a BlockLink_t + structure in addition to the requested amount of bytes. */ + if( xWantedSize > 0 ) + { + xWantedSize += xHeapStructSize; + + /* Ensure that blocks are always aligned to the required number + of bytes. */ + if( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) != 0x00 ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( ( xWantedSize > 0 ) && ( xWantedSize <= xFreeBytesRemaining ) ) + { + /* Traverse the list from the start (lowest address) block until + one of adequate size is found. */ + pxPreviousBlock = &xStart; + pxBlock = xStart.pxNextFreeBlock; + while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock != NULL ) ) + { + pxPreviousBlock = pxBlock; + pxBlock = pxBlock->pxNextFreeBlock; + } + + /* If the end marker was reached then a block of adequate size + was not found. */ + if( pxBlock != pxEnd ) + { + /* Return the memory space pointed to - jumping over the + BlockLink_t structure at its start. */ + pvReturn = ( void * ) ( ( ( uint8_t * ) pxPreviousBlock->pxNextFreeBlock ) + xHeapStructSize ); + + /* This block is being returned for use so must be taken out + of the list of free blocks. */ + pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock; + + /* If the block is larger than required it can be split into + two. */ + if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE ) + { + /* This block is to be split into two. Create a new + block following the number of bytes requested. The void + cast is used to prevent byte alignment warnings from the + compiler. */ + pxNewBlockLink = ( void * ) ( ( ( uint8_t * ) pxBlock ) + xWantedSize ); + + /* Calculate the sizes of two blocks split from the + single block. */ + pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize; + pxBlock->xBlockSize = xWantedSize; + + /* Insert the new block into the list of free blocks. */ + prvInsertBlockIntoFreeList( ( pxNewBlockLink ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xFreeBytesRemaining -= pxBlock->xBlockSize; + + if( xFreeBytesRemaining < xMinimumEverFreeBytesRemaining ) + { + xMinimumEverFreeBytesRemaining = xFreeBytesRemaining; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The block is being returned - it is allocated and owned + by the application and has no "next" block. */ + pxBlock->xBlockSize |= xBlockAllocatedBit; + pxBlock->pxNextFreeBlock = NULL; + xNumberOfSuccessfulAllocations++; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceMALLOC( pvReturn, xWantedSize ); + } + ( void ) xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ +uint8_t *puc = ( uint8_t * ) pv; +BlockLink_t *pxLink; + + if( pv != NULL ) + { + /* The memory being freed will have an BlockLink_t structure immediately + before it. */ + puc -= xHeapStructSize; + + /* This casting is to keep the compiler from issuing warnings. */ + pxLink = ( void * ) puc; + + /* Check the block is actually allocated. */ + configASSERT( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 ); + configASSERT( pxLink->pxNextFreeBlock == NULL ); + + if( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 ) + { + if( pxLink->pxNextFreeBlock == NULL ) + { + /* The block is being returned to the heap - it is no longer + allocated. */ + pxLink->xBlockSize &= ~xBlockAllocatedBit; + + vTaskSuspendAll(); + { + /* Add this block to the list of free blocks. */ + xFreeBytesRemaining += pxLink->xBlockSize; + traceFREE( pv, pxLink->xBlockSize ); + prvInsertBlockIntoFreeList( ( ( BlockLink_t * ) pxLink ) ); + xNumberOfSuccessfulFrees++; + } + ( void ) xTaskResumeAll(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return xFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +size_t xPortGetMinimumEverFreeHeapSize( void ) +{ + return xMinimumEverFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert ) +{ +BlockLink_t *pxIterator; +uint8_t *puc; + + /* Iterate through the list until a block is found that has a higher address + than the block being inserted. */ + for( pxIterator = &xStart; pxIterator->pxNextFreeBlock < pxBlockToInsert; pxIterator = pxIterator->pxNextFreeBlock ) + { + /* Nothing to do here, just iterate to the right position. */ + } + + /* Do the block being inserted, and the block it is being inserted after + make a contiguous block of memory? */ + puc = ( uint8_t * ) pxIterator; + if( ( puc + pxIterator->xBlockSize ) == ( uint8_t * ) pxBlockToInsert ) + { + pxIterator->xBlockSize += pxBlockToInsert->xBlockSize; + pxBlockToInsert = pxIterator; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Do the block being inserted, and the block it is being inserted before + make a contiguous block of memory? */ + puc = ( uint8_t * ) pxBlockToInsert; + if( ( puc + pxBlockToInsert->xBlockSize ) == ( uint8_t * ) pxIterator->pxNextFreeBlock ) + { + if( pxIterator->pxNextFreeBlock != pxEnd ) + { + /* Form one big block from the two blocks. */ + pxBlockToInsert->xBlockSize += pxIterator->pxNextFreeBlock->xBlockSize; + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock->pxNextFreeBlock; + } + else + { + pxBlockToInsert->pxNextFreeBlock = pxEnd; + } + } + else + { + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock; + } + + /* If the block being inserted plugged a gab, so was merged with the block + before and the block after, then it's pxNextFreeBlock pointer will have + already been set, and should not be set here as that would make it point + to itself. */ + if( pxIterator != pxBlockToInsert ) + { + pxIterator->pxNextFreeBlock = pxBlockToInsert; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } +} +/*-----------------------------------------------------------*/ + +void vPortDefineHeapRegions( const HeapRegion_t * const pxHeapRegions ) +{ +BlockLink_t *pxFirstFreeBlockInRegion = NULL, *pxPreviousFreeBlock; +size_t xAlignedHeap; +size_t xTotalRegionSize, xTotalHeapSize = 0; +BaseType_t xDefinedRegions = 0; +size_t xAddress; +const HeapRegion_t *pxHeapRegion; + + /* Can only call once! */ + configASSERT( pxEnd == NULL ); + + pxHeapRegion = &( pxHeapRegions[ xDefinedRegions ] ); + + while( pxHeapRegion->xSizeInBytes > 0 ) + { + xTotalRegionSize = pxHeapRegion->xSizeInBytes; + + /* Ensure the heap region starts on a correctly aligned boundary. */ + xAddress = ( size_t ) pxHeapRegion->pucStartAddress; + if( ( xAddress & portBYTE_ALIGNMENT_MASK ) != 0 ) + { + xAddress += ( portBYTE_ALIGNMENT - 1 ); + xAddress &= ~portBYTE_ALIGNMENT_MASK; + + /* Adjust the size for the bytes lost to alignment. */ + xTotalRegionSize -= xAddress - ( size_t ) pxHeapRegion->pucStartAddress; + } + + xAlignedHeap = xAddress; + + /* Set xStart if it has not already been set. */ + if( xDefinedRegions == 0 ) + { + /* xStart is used to hold a pointer to the first item in the list of + free blocks. The void cast is used to prevent compiler warnings. */ + xStart.pxNextFreeBlock = ( BlockLink_t * ) xAlignedHeap; + xStart.xBlockSize = ( size_t ) 0; + } + else + { + /* Should only get here if one region has already been added to the + heap. */ + configASSERT( pxEnd != NULL ); + + /* Check blocks are passed in with increasing start addresses. */ + configASSERT( xAddress > ( size_t ) pxEnd ); + } + + /* Remember the location of the end marker in the previous region, if + any. */ + pxPreviousFreeBlock = pxEnd; + + /* pxEnd is used to mark the end of the list of free blocks and is + inserted at the end of the region space. */ + xAddress = xAlignedHeap + xTotalRegionSize; + xAddress -= xHeapStructSize; + xAddress &= ~portBYTE_ALIGNMENT_MASK; + pxEnd = ( BlockLink_t * ) xAddress; + pxEnd->xBlockSize = 0; + pxEnd->pxNextFreeBlock = NULL; + + /* To start with there is a single free block in this region that is + sized to take up the entire heap region minus the space taken by the + free block structure. */ + pxFirstFreeBlockInRegion = ( BlockLink_t * ) xAlignedHeap; + pxFirstFreeBlockInRegion->xBlockSize = xAddress - ( size_t ) pxFirstFreeBlockInRegion; + pxFirstFreeBlockInRegion->pxNextFreeBlock = pxEnd; + + /* If this is not the first region that makes up the entire heap space + then link the previous region to this region. */ + if( pxPreviousFreeBlock != NULL ) + { + pxPreviousFreeBlock->pxNextFreeBlock = pxFirstFreeBlockInRegion; + } + + xTotalHeapSize += pxFirstFreeBlockInRegion->xBlockSize; + + /* Move onto the next HeapRegion_t structure. */ + xDefinedRegions++; + pxHeapRegion = &( pxHeapRegions[ xDefinedRegions ] ); + } + + xMinimumEverFreeBytesRemaining = xTotalHeapSize; + xFreeBytesRemaining = xTotalHeapSize; + + /* Check something was actually defined before it is accessed. */ + configASSERT( xTotalHeapSize ); + + /* Work out the position of the top bit in a size_t variable. */ + xBlockAllocatedBit = ( ( size_t ) 1 ) << ( ( sizeof( size_t ) * heapBITS_PER_BYTE ) - 1 ); +} +/*-----------------------------------------------------------*/ + +void vPortGetHeapStats( HeapStats_t *pxHeapStats ) +{ +BlockLink_t *pxBlock; +size_t xBlocks = 0, xMaxSize = 0, xMinSize = portMAX_DELAY; /* portMAX_DELAY used as a portable way of getting the maximum value. */ + + vTaskSuspendAll(); + { + pxBlock = xStart.pxNextFreeBlock; + + /* pxBlock will be NULL if the heap has not been initialised. The heap + is initialised automatically when the first allocation is made. */ + if( pxBlock != NULL ) + { + do + { + /* Increment the number of blocks and record the largest block seen + so far. */ + xBlocks++; + + if( pxBlock->xBlockSize > xMaxSize ) + { + xMaxSize = pxBlock->xBlockSize; + } + + /* Heap five will have a zero sized block at the end of each + each region - the block is only used to link to the next + heap region so it not a real block. */ + if( pxBlock->xBlockSize != 0 ) + { + if( pxBlock->xBlockSize < xMinSize ) + { + xMinSize = pxBlock->xBlockSize; + } + } + + /* Move to the next block in the chain until the last block is + reached. */ + pxBlock = pxBlock->pxNextFreeBlock; + } while( pxBlock != pxEnd ); + } + } + xTaskResumeAll(); + + pxHeapStats->xSizeOfLargestFreeBlockInBytes = xMaxSize; + pxHeapStats->xSizeOfSmallestFreeBlockInBytes = xMinSize; + pxHeapStats->xNumberOfFreeBlocks = xBlocks; + + taskENTER_CRITICAL(); + { + pxHeapStats->xAvailableHeapSpaceInBytes = xFreeBytesRemaining; + pxHeapStats->xNumberOfSuccessfulAllocations = xNumberOfSuccessfulAllocations; + pxHeapStats->xNumberOfSuccessfulFrees = xNumberOfSuccessfulFrees; + pxHeapStats->xMinimumEverFreeBytesRemaining = xMinimumEverFreeBytesRemaining; + } + taskEXIT_CRITICAL(); +} + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/readme.txt b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/readme.txt new file mode 100644 index 0000000..b68d2d5 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/portable/readme.txt @@ -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. + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/queue.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/queue.c new file mode 100644 index 0000000..59f78f7 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/queue.c @@ -0,0 +1,2945 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" + +#if ( configUSE_CO_ROUTINES == 1 ) + #include "croutine.h" +#endif + +/* Lint e9021, e961 and e750 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750 !e9021. */ + + +/* Constants used with the cRxLock and cTxLock structure members. */ +#define queueUNLOCKED ( ( int8_t ) -1 ) +#define queueLOCKED_UNMODIFIED ( ( int8_t ) 0 ) + +/* When the Queue_t structure is used to represent a base queue its pcHead and +pcTail members are used as pointers into the queue storage area. When the +Queue_t structure is used to represent a mutex pcHead and pcTail pointers are +not necessary, and the pcHead pointer is set to NULL to indicate that the +structure instead holds a pointer to the mutex holder (if any). Map alternative +names to the pcHead and structure member to ensure the readability of the code +is maintained. The QueuePointers_t and SemaphoreData_t types are used to form +a union as their usage is mutually exclusive dependent on what the queue is +being used for. */ +#define uxQueueType pcHead +#define queueQUEUE_IS_MUTEX NULL + +typedef struct QueuePointers +{ + int8_t *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ + int8_t *pcReadFrom; /*< Points to the last place that a queued item was read from when the structure is used as a queue. */ +} QueuePointers_t; + +typedef struct SemaphoreData +{ + TaskHandle_t xMutexHolder; /*< The handle of the task that holds the mutex. */ + UBaseType_t uxRecursiveCallCount;/*< Maintains a count of the number of times a recursive mutex has been recursively 'taken' when the structure is used as a mutex. */ +} SemaphoreData_t; + +/* Semaphores do not actually store or copy data, so have an item size of +zero. */ +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( UBaseType_t ) 0 ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( TickType_t ) 0U ) + +#if( configUSE_PREEMPTION == 0 ) + /* If the cooperative scheduler is being used then a yield should not be + performed just because a higher priority task has been woken. */ + #define queueYIELD_IF_USING_PREEMPTION() +#else + #define queueYIELD_IF_USING_PREEMPTION() portYIELD_WITHIN_API() +#endif + +/* + * Definition of the queue used by the scheduler. + * Items are queued by copy, not reference. See the following link for the + * rationale: https://www.freertos.org/Embedded-RTOS-Queues.html + */ +typedef struct QueueDefinition /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +{ + int8_t *pcHead; /*< Points to the beginning of the queue storage area. */ + int8_t *pcWriteTo; /*< Points to the free next place in the storage area. */ + + union + { + QueuePointers_t xQueue; /*< Data required exclusively when this structure is used as a queue. */ + SemaphoreData_t xSemaphore; /*< Data required exclusively when this structure is used as a semaphore. */ + } u; + + List_t xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ + List_t xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ + + volatile UBaseType_t uxMessagesWaiting;/*< The number of items currently in the queue. */ + UBaseType_t uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ + UBaseType_t uxItemSize; /*< The size of each items that the queue will hold. */ + + volatile int8_t cRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + volatile int8_t cTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + + #if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + uint8_t ucStaticallyAllocated; /*< Set to pdTRUE if the memory used by the queue was statically allocated to ensure no attempt is made to free the memory. */ + #endif + + #if ( configUSE_QUEUE_SETS == 1 ) + struct QueueDefinition *pxQueueSetContainer; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxQueueNumber; + uint8_t ucQueueType; + #endif + +} xQUEUE; + +/* The old xQUEUE name is maintained above then typedefed to the new Queue_t +name below to enable the use of older kernel aware debuggers. */ +typedef xQUEUE Queue_t; + +/*-----------------------------------------------------------*/ + +/* + * The queue registry is just a means for kernel aware debuggers to locate + * queue structures. It has no other purpose so is an optional component. + */ +#if ( configQUEUE_REGISTRY_SIZE > 0 ) + + /* The type stored within the queue registry array. This allows a name + to be assigned to each queue making kernel aware debugging a little + more user friendly. */ + typedef struct QUEUE_REGISTRY_ITEM + { + const char *pcQueueName; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + QueueHandle_t xHandle; + } xQueueRegistryItem; + + /* The old xQueueRegistryItem name is maintained above then typedefed to the + new xQueueRegistryItem name below to enable the use of older kernel aware + debuggers. */ + typedef xQueueRegistryItem QueueRegistryItem_t; + + /* The queue registry is simply an array of QueueRegistryItem_t structures. + The pcQueueName member of a structure being NULL is indicative of the + array position being vacant. */ + PRIVILEGED_DATA QueueRegistryItem_t xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; + +#endif /* configQUEUE_REGISTRY_SIZE */ + +/* + * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not + * prevent an ISR from adding or removing items to the queue, but does prevent + * an ISR from removing tasks from the queue event lists. If an ISR finds a + * queue is locked it will instead increment the appropriate queue lock count + * to indicate that a task may require unblocking. When the queue in unlocked + * these lock counts are inspected, and the appropriate action taken. + */ +static void prvUnlockQueue( Queue_t * const pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any data in a queue. + * + * @return pdTRUE if the queue contains no items, otherwise pdFALSE. + */ +static BaseType_t prvIsQueueEmpty( const Queue_t *pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any space in a queue. + * + * @return pdTRUE if there is no space, otherwise pdFALSE; + */ +static BaseType_t prvIsQueueFull( const Queue_t *pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Copies an item into the queue, either at the front of the queue or the + * back of the queue. + */ +static BaseType_t prvCopyDataToQueue( Queue_t * const pxQueue, const void *pvItemToQueue, const BaseType_t xPosition ) PRIVILEGED_FUNCTION; + +/* + * Copies an item out of a queue. + */ +static void prvCopyDataFromQueue( Queue_t * const pxQueue, void * const pvBuffer ) PRIVILEGED_FUNCTION; + +#if ( configUSE_QUEUE_SETS == 1 ) + /* + * Checks to see if a queue is a member of a queue set, and if so, notifies + * the queue set that the queue contains data. + */ + static BaseType_t prvNotifyQueueSetContainer( const Queue_t * const pxQueue ) PRIVILEGED_FUNCTION; +#endif + +/* + * Called after a Queue_t structure has been allocated either statically or + * dynamically to fill in the structure's members. + */ +static void prvInitialiseNewQueue( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, const uint8_t ucQueueType, Queue_t *pxNewQueue ) PRIVILEGED_FUNCTION; + +/* + * Mutexes are a special type of queue. When a mutex is created, first the + * queue is created, then prvInitialiseMutex() is called to configure the queue + * as a mutex. + */ +#if( configUSE_MUTEXES == 1 ) + static void prvInitialiseMutex( Queue_t *pxNewQueue ) PRIVILEGED_FUNCTION; +#endif + +#if( configUSE_MUTEXES == 1 ) + /* + * If a task waiting for a mutex causes the mutex holder to inherit a + * priority, but the waiting task times out, then the holder should + * disinherit the priority - but only down to the highest priority of any + * other tasks that are waiting for the same mutex. This function returns + * that priority. + */ + static UBaseType_t prvGetDisinheritPriorityAfterTimeout( const Queue_t * const pxQueue ) PRIVILEGED_FUNCTION; +#endif +/*-----------------------------------------------------------*/ + +/* + * Macro to mark a queue as locked. Locking a queue prevents an ISR from + * accessing the queue event lists. + */ +#define prvLockQueue( pxQueue ) \ + taskENTER_CRITICAL(); \ + { \ + if( ( pxQueue )->cRxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->cRxLock = queueLOCKED_UNMODIFIED; \ + } \ + if( ( pxQueue )->cTxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->cTxLock = queueLOCKED_UNMODIFIED; \ + } \ + } \ + taskEXIT_CRITICAL() +/*-----------------------------------------------------------*/ + +BaseType_t xQueueGenericReset( QueueHandle_t xQueue, BaseType_t xNewQueue ) +{ +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + { + pxQueue->u.xQueue.pcTail = pxQueue->pcHead + ( pxQueue->uxLength * pxQueue->uxItemSize ); /*lint !e9016 Pointer arithmetic allowed on char types, especially when it assists conveying intent. */ + pxQueue->uxMessagesWaiting = ( UBaseType_t ) 0U; + pxQueue->pcWriteTo = pxQueue->pcHead; + pxQueue->u.xQueue.pcReadFrom = pxQueue->pcHead + ( ( pxQueue->uxLength - 1U ) * pxQueue->uxItemSize ); /*lint !e9016 Pointer arithmetic allowed on char types, especially when it assists conveying intent. */ + pxQueue->cRxLock = queueUNLOCKED; + pxQueue->cTxLock = queueUNLOCKED; + + if( xNewQueue == pdFALSE ) + { + /* If there are tasks blocked waiting to read from the queue, then + the tasks will remain blocked as after this function exits the queue + will still be empty. If there are tasks blocked waiting to write to + the queue, then one should be unblocked as after this function exits + it will be possible to write to it. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* Ensure the event queues start in the correct state. */ + vListInitialise( &( pxQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxQueue->xTasksWaitingToReceive ) ); + } + } + taskEXIT_CRITICAL(); + + /* A value is returned for calling semantic consistency with previous + versions. */ + return pdPASS; +} +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + QueueHandle_t xQueueGenericCreateStatic( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, StaticQueue_t *pxStaticQueue, const uint8_t ucQueueType ) + { + Queue_t *pxNewQueue; + + configASSERT( uxQueueLength > ( UBaseType_t ) 0 ); + + /* The StaticQueue_t structure and the queue storage area must be + supplied. */ + configASSERT( pxStaticQueue != NULL ); + + /* A queue storage area should be provided if the item size is not 0, and + should not be provided if the item size is 0. */ + configASSERT( !( ( pucQueueStorage != NULL ) && ( uxItemSize == 0 ) ) ); + configASSERT( !( ( pucQueueStorage == NULL ) && ( uxItemSize != 0 ) ) ); + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticQueue_t or StaticSemaphore_t equals the size of + the real queue and semaphore structures. */ + volatile size_t xSize = sizeof( StaticQueue_t ); + configASSERT( xSize == sizeof( Queue_t ) ); + ( void ) xSize; /* Keeps lint quiet when configASSERT() is not defined. */ + } + #endif /* configASSERT_DEFINED */ + + /* The address of a statically allocated queue was passed in, use it. + The address of a statically allocated storage area was also passed in + but is already set. */ + pxNewQueue = ( Queue_t * ) pxStaticQueue; /*lint !e740 !e9087 Unusual cast is ok as the structures are designed to have the same alignment, and the size is checked by an assert. */ + + if( pxNewQueue != NULL ) + { + #if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + { + /* Queues can be allocated wither statically or dynamically, so + note this queue was allocated statically in case the queue is + later deleted. */ + pxNewQueue->ucStaticallyAllocated = pdTRUE; + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + + prvInitialiseNewQueue( uxQueueLength, uxItemSize, pucQueueStorage, ucQueueType, pxNewQueue ); + } + else + { + traceQUEUE_CREATE_FAILED( ucQueueType ); + mtCOVERAGE_TEST_MARKER(); + } + + return pxNewQueue; + } + +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + QueueHandle_t xQueueGenericCreate( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType ) + { + Queue_t *pxNewQueue; + size_t xQueueSizeInBytes; + uint8_t *pucQueueStorage; + + configASSERT( uxQueueLength > ( UBaseType_t ) 0 ); + + /* Allocate enough space to hold the maximum number of items that + can be in the queue at any time. It is valid for uxItemSize to be + zero in the case the queue is used as a semaphore. */ + xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + /* Allocate the queue and storage area. Justification for MISRA + deviation as follows: pvPortMalloc() always ensures returned memory + blocks are aligned per the requirements of the MCU stack. In this case + pvPortMalloc() must return a pointer that is guaranteed to meet the + alignment requirements of the Queue_t structure - which in this case + is an int8_t *. Therefore, whenever the stack alignment requirements + are greater than or equal to the pointer to char requirements the cast + is safe. In other cases alignment requirements are not strict (one or + two bytes). */ + pxNewQueue = ( Queue_t * ) pvPortMalloc( sizeof( Queue_t ) + xQueueSizeInBytes ); /*lint !e9087 !e9079 see comment above. */ + + if( pxNewQueue != NULL ) + { + /* Jump past the queue structure to find the location of the queue + storage area. */ + pucQueueStorage = ( uint8_t * ) pxNewQueue; + pucQueueStorage += sizeof( Queue_t ); /*lint !e9016 Pointer arithmetic allowed on char types, especially when it assists conveying intent. */ + + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + /* Queues can be created either statically or dynamically, so + note this task was created dynamically in case it is later + deleted. */ + pxNewQueue->ucStaticallyAllocated = pdFALSE; + } + #endif /* configSUPPORT_STATIC_ALLOCATION */ + + prvInitialiseNewQueue( uxQueueLength, uxItemSize, pucQueueStorage, ucQueueType, pxNewQueue ); + } + else + { + traceQUEUE_CREATE_FAILED( ucQueueType ); + mtCOVERAGE_TEST_MARKER(); + } + + return pxNewQueue; + } + +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +static void prvInitialiseNewQueue( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, const uint8_t ucQueueType, Queue_t *pxNewQueue ) +{ + /* Remove compiler warnings about unused parameters should + configUSE_TRACE_FACILITY not be set to 1. */ + ( void ) ucQueueType; + + if( uxItemSize == ( UBaseType_t ) 0 ) + { + /* No RAM was allocated for the queue storage area, but PC head cannot + be set to NULL because NULL is used as a key to say the queue is used as + a mutex. Therefore just set pcHead to point to the queue as a benign + value that is known to be within the memory map. */ + pxNewQueue->pcHead = ( int8_t * ) pxNewQueue; + } + else + { + /* Set the head to the start of the queue storage area. */ + pxNewQueue->pcHead = ( int8_t * ) pucQueueStorage; + } + + /* Initialise the queue members as described where the queue type is + defined. */ + pxNewQueue->uxLength = uxQueueLength; + pxNewQueue->uxItemSize = uxItemSize; + ( void ) xQueueGenericReset( pxNewQueue, pdTRUE ); + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + pxNewQueue->ucQueueType = ucQueueType; + } + #endif /* configUSE_TRACE_FACILITY */ + + #if( configUSE_QUEUE_SETS == 1 ) + { + pxNewQueue->pxQueueSetContainer = NULL; + } + #endif /* configUSE_QUEUE_SETS */ + + traceQUEUE_CREATE( pxNewQueue ); +} +/*-----------------------------------------------------------*/ + +#if( configUSE_MUTEXES == 1 ) + + static void prvInitialiseMutex( Queue_t *pxNewQueue ) + { + if( pxNewQueue != NULL ) + { + /* The queue create function will set all the queue structure members + correctly for a generic queue, but this function is creating a + mutex. Overwrite those members that need to be set differently - + in particular the information required for priority inheritance. */ + pxNewQueue->u.xSemaphore.xMutexHolder = NULL; + pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; + + /* In case this is a recursive mutex. */ + pxNewQueue->u.xSemaphore.uxRecursiveCallCount = 0; + + traceCREATE_MUTEX( pxNewQueue ); + + /* Start with the semaphore in the expected state. */ + ( void ) xQueueGenericSend( pxNewQueue, NULL, ( TickType_t ) 0U, queueSEND_TO_BACK ); + } + else + { + traceCREATE_MUTEX_FAILED(); + } + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_MUTEXES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + QueueHandle_t xQueueCreateMutex( const uint8_t ucQueueType ) + { + QueueHandle_t xNewQueue; + const UBaseType_t uxMutexLength = ( UBaseType_t ) 1, uxMutexSize = ( UBaseType_t ) 0; + + xNewQueue = xQueueGenericCreate( uxMutexLength, uxMutexSize, ucQueueType ); + prvInitialiseMutex( ( Queue_t * ) xNewQueue ); + + return xNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_MUTEXES == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + + QueueHandle_t xQueueCreateMutexStatic( const uint8_t ucQueueType, StaticQueue_t *pxStaticQueue ) + { + QueueHandle_t xNewQueue; + const UBaseType_t uxMutexLength = ( UBaseType_t ) 1, uxMutexSize = ( UBaseType_t ) 0; + + /* Prevent compiler warnings about unused parameters if + configUSE_TRACE_FACILITY does not equal 1. */ + ( void ) ucQueueType; + + xNewQueue = xQueueGenericCreateStatic( uxMutexLength, uxMutexSize, NULL, pxStaticQueue, ucQueueType ); + prvInitialiseMutex( ( Queue_t * ) xNewQueue ); + + return xNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xSemaphoreGetMutexHolder == 1 ) ) + + TaskHandle_t xQueueGetMutexHolder( QueueHandle_t xSemaphore ) + { + TaskHandle_t pxReturn; + Queue_t * const pxSemaphore = ( Queue_t * ) xSemaphore; + + /* This function is called by xSemaphoreGetMutexHolder(), and should not + be called directly. Note: This is a good way of determining if the + calling task is the mutex holder, but not a good way of determining the + identity of the mutex holder, as the holder may change between the + following critical section exiting and the function returning. */ + taskENTER_CRITICAL(); + { + if( pxSemaphore->uxQueueType == queueQUEUE_IS_MUTEX ) + { + pxReturn = pxSemaphore->u.xSemaphore.xMutexHolder; + } + else + { + pxReturn = NULL; + } + } + taskEXIT_CRITICAL(); + + return pxReturn; + } /*lint !e818 xSemaphore cannot be a pointer to const because it is a typedef. */ + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xSemaphoreGetMutexHolder == 1 ) ) + + TaskHandle_t xQueueGetMutexHolderFromISR( QueueHandle_t xSemaphore ) + { + TaskHandle_t pxReturn; + + configASSERT( xSemaphore ); + + /* Mutexes cannot be used in interrupt service routines, so the mutex + holder should not change in an ISR, and therefore a critical section is + not required here. */ + if( ( ( Queue_t * ) xSemaphore )->uxQueueType == queueQUEUE_IS_MUTEX ) + { + pxReturn = ( ( Queue_t * ) xSemaphore )->u.xSemaphore.xMutexHolder; + } + else + { + pxReturn = NULL; + } + + return pxReturn; + } /*lint !e818 xSemaphore cannot be a pointer to const because it is a typedef. */ + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) + + BaseType_t xQueueGiveMutexRecursive( QueueHandle_t xMutex ) + { + BaseType_t xReturn; + Queue_t * const pxMutex = ( Queue_t * ) xMutex; + + configASSERT( pxMutex ); + + /* If this is the task that holds the mutex then xMutexHolder will not + change outside of this task. If this task does not hold the mutex then + pxMutexHolder can never coincidentally equal the tasks handle, and as + this is the only condition we are interested in it does not matter if + pxMutexHolder is accessed simultaneously by another task. Therefore no + mutual exclusion is required to test the pxMutexHolder variable. */ + if( pxMutex->u.xSemaphore.xMutexHolder == xTaskGetCurrentTaskHandle() ) + { + traceGIVE_MUTEX_RECURSIVE( pxMutex ); + + /* uxRecursiveCallCount cannot be zero if xMutexHolder is equal to + the task handle, therefore no underflow check is required. Also, + uxRecursiveCallCount is only modified by the mutex holder, and as + there can only be one, no mutual exclusion is required to modify the + uxRecursiveCallCount member. */ + ( pxMutex->u.xSemaphore.uxRecursiveCallCount )--; + + /* Has the recursive call count unwound to 0? */ + if( pxMutex->u.xSemaphore.uxRecursiveCallCount == ( UBaseType_t ) 0 ) + { + /* Return the mutex. This will automatically unblock any other + task that might be waiting to access the mutex. */ + ( void ) xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xReturn = pdPASS; + } + else + { + /* The mutex cannot be given because the calling task is not the + holder. */ + xReturn = pdFAIL; + + traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) + + BaseType_t xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xTicksToWait ) + { + BaseType_t xReturn; + Queue_t * const pxMutex = ( Queue_t * ) xMutex; + + configASSERT( pxMutex ); + + /* Comments regarding mutual exclusion as per those within + xQueueGiveMutexRecursive(). */ + + traceTAKE_MUTEX_RECURSIVE( pxMutex ); + + if( pxMutex->u.xSemaphore.xMutexHolder == xTaskGetCurrentTaskHandle() ) + { + ( pxMutex->u.xSemaphore.uxRecursiveCallCount )++; + xReturn = pdPASS; + } + else + { + xReturn = xQueueSemaphoreTake( pxMutex, xTicksToWait ); + + /* pdPASS will only be returned if the mutex was successfully + obtained. The calling task may have entered the Blocked state + before reaching here. */ + if( xReturn != pdFAIL ) + { + ( pxMutex->u.xSemaphore.uxRecursiveCallCount )++; + } + else + { + traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + + QueueHandle_t xQueueCreateCountingSemaphoreStatic( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount, StaticQueue_t *pxStaticQueue ) + { + QueueHandle_t xHandle; + + configASSERT( uxMaxCount != 0 ); + configASSERT( uxInitialCount <= uxMaxCount ); + + xHandle = xQueueGenericCreateStatic( uxMaxCount, queueSEMAPHORE_QUEUE_ITEM_LENGTH, NULL, pxStaticQueue, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); + + if( xHandle != NULL ) + { + ( ( Queue_t * ) xHandle )->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + return xHandle; + } + +#endif /* ( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + QueueHandle_t xQueueCreateCountingSemaphore( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount ) + { + QueueHandle_t xHandle; + + configASSERT( uxMaxCount != 0 ); + configASSERT( uxInitialCount <= uxMaxCount ); + + xHandle = xQueueGenericCreate( uxMaxCount, queueSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); + + if( xHandle != NULL ) + { + ( ( Queue_t * ) xHandle )->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + return xHandle; + } + +#endif /* ( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) */ +/*-----------------------------------------------------------*/ + +BaseType_t xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, const BaseType_t xCopyPosition ) +{ +BaseType_t xEntryTimeSet = pdFALSE, xYieldRequired; +TimeOut_t xTimeOut; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) ); + configASSERT( !( ( xCopyPosition == queueOVERWRITE ) && ( pxQueue->uxLength != 1 ) ) ); + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + + /*lint -save -e904 This function relaxes the coding standard somewhat to + allow return statements within the function itself. This is done in the + interest of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? The running task must be the + highest priority task wanting to access the queue. If the head item + in the queue is to be overwritten then it does not matter if the + queue is full. */ + if( ( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) || ( xCopyPosition == queueOVERWRITE ) ) + { + traceQUEUE_SEND( pxQueue ); + + #if ( configUSE_QUEUE_SETS == 1 ) + { + const UBaseType_t uxPreviousMessagesWaiting = pxQueue->uxMessagesWaiting; + + xYieldRequired = prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + if( pxQueue->pxQueueSetContainer != NULL ) + { + if( ( xCopyPosition == queueOVERWRITE ) && ( uxPreviousMessagesWaiting != ( UBaseType_t ) 0 ) ) + { + /* Do not notify the queue set as an existing item + was overwritten in the queue so the number of items + in the queue has not changed. */ + mtCOVERAGE_TEST_MARKER(); + } + else if( prvNotifyQueueSetContainer( pxQueue ) != pdFALSE ) + { + /* The queue is a member of a queue set, and posting + to the queue set caused a higher priority task to + unblock. A context switch is required. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to + do this from within the critical section - the + kernel takes care of that. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else if( xYieldRequired != pdFALSE ) + { + /* This path is a special case that will only get + executed if the task was holding multiple mutexes + and the mutexes were given back in an order that is + different to that in which they were taken. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + #else /* configUSE_QUEUE_SETS */ + { + xYieldRequired = prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to do + this from within the critical section - the kernel + takes care of that. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else if( xYieldRequired != pdFALSE ) + { + /* This path is a special case that will only get + executed if the task was holding multiple mutexes and + the mutexes were given back in an order that is + different to that in which they were taken. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_QUEUE_SETS */ + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( TickType_t ) 0 ) + { + /* The queue was full and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting + the function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was full and a block time was specified so + configure the timeout structure. */ + vTaskInternalSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + else + { + /* Entry time was already set. */ + mtCOVERAGE_TEST_MARKER(); + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + + /* Unlocking the queue means queue events can effect the + event list. It is possible that interrupts occurring now + remove this task from the event list again - but as the + scheduler is suspended the task will go onto the pending + ready last instead of the actual ready list. */ + prvUnlockQueue( pxQueue ); + + /* Resuming the scheduler will move tasks from the pending + ready list into the ready list - so it is feasible that this + task is already in a ready list before it yields - in which + case the yield will not cause a context switch unless there + is also a higher priority task in the pending ready list. */ + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } /*lint -restore */ +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueGenericSendFromISR( QueueHandle_t xQueue, const void * const pvItemToQueue, BaseType_t * const pxHigherPriorityTaskWoken, const BaseType_t xCopyPosition ) +{ +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) ); + configASSERT( !( ( xCopyPosition == queueOVERWRITE ) && ( pxQueue->uxLength != 1 ) ) ); + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + /* Similar to xQueueGenericSend, except without blocking if there is no room + in the queue. Also don't directly wake a task that was blocked on a queue + read, instead return a flag to say whether a context switch is required or + not (i.e. has a task with a higher priority than us been woken by this + post). */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( ( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) || ( xCopyPosition == queueOVERWRITE ) ) + { + const int8_t cTxLock = pxQueue->cTxLock; + const UBaseType_t uxPreviousMessagesWaiting = pxQueue->uxMessagesWaiting; + + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + /* Semaphores use xQueueGiveFromISR(), so pxQueue will not be a + semaphore or mutex. That means prvCopyDataToQueue() cannot result + in a task disinheriting a priority and prvCopyDataToQueue() can be + called here even though the disinherit function does not check if + the scheduler is suspended before accessing the ready lists. */ + ( void ) prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* The event list is not altered if the queue is locked. This will + be done when the queue is unlocked later. */ + if( cTxLock == queueUNLOCKED ) + { + #if ( configUSE_QUEUE_SETS == 1 ) + { + if( pxQueue->pxQueueSetContainer != NULL ) + { + if( ( xCopyPosition == queueOVERWRITE ) && ( uxPreviousMessagesWaiting != ( UBaseType_t ) 0 ) ) + { + /* Do not notify the queue set as an existing item + was overwritten in the queue so the number of items + in the queue has not changed. */ + mtCOVERAGE_TEST_MARKER(); + } + else if( prvNotifyQueueSetContainer( pxQueue ) != pdFALSE ) + { + /* The queue is a member of a queue set, and posting + to the queue set caused a higher priority task to + unblock. A context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so + record that a context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + #else /* configUSE_QUEUE_SETS */ + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Not used in this path. */ + ( void ) uxPreviousMessagesWaiting; + } + #endif /* configUSE_QUEUE_SETS */ + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + pxQueue->cTxLock = ( int8_t ) ( cTxLock + 1 ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueGiveFromISR( QueueHandle_t xQueue, BaseType_t * const pxHigherPriorityTaskWoken ) +{ +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; +Queue_t * const pxQueue = xQueue; + + /* Similar to xQueueGenericSendFromISR() but used with semaphores where the + item size is 0. Don't directly wake a task that was blocked on a queue + read, instead return a flag to say whether a context switch is required or + not (i.e. has a task with a higher priority than us been woken by this + post). */ + + configASSERT( pxQueue ); + + /* xQueueGenericSendFromISR() should be used instead of xQueueGiveFromISR() + if the item size is not 0. */ + configASSERT( pxQueue->uxItemSize == 0 ); + + /* Normally a mutex would not be given from an interrupt, especially if + there is a mutex holder, as priority inheritance makes no sense for an + interrupts, only tasks. */ + configASSERT( !( ( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) && ( pxQueue->u.xSemaphore.xMutexHolder != NULL ) ) ); + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + const UBaseType_t uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + /* When the queue is used to implement a semaphore no data is ever + moved through the queue but it is still valid to see if the queue 'has + space'. */ + if( uxMessagesWaiting < pxQueue->uxLength ) + { + const int8_t cTxLock = pxQueue->cTxLock; + + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + /* A task can only have an inherited priority if it is a mutex + holder - and if there is a mutex holder then the mutex cannot be + given from an ISR. As this is the ISR version of the function it + can be assumed there is no mutex holder and no need to determine if + priority disinheritance is needed. Simply increase the count of + messages (semaphores) available. */ + pxQueue->uxMessagesWaiting = uxMessagesWaiting + ( UBaseType_t ) 1; + + /* The event list is not altered if the queue is locked. This will + be done when the queue is unlocked later. */ + if( cTxLock == queueUNLOCKED ) + { + #if ( configUSE_QUEUE_SETS == 1 ) + { + if( pxQueue->pxQueueSetContainer != NULL ) + { + if( prvNotifyQueueSetContainer( pxQueue ) != pdFALSE ) + { + /* The semaphore is a member of a queue set, and + posting to the queue set caused a higher priority + task to unblock. A context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so + record that a context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + #else /* configUSE_QUEUE_SETS */ + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_QUEUE_SETS */ + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + pxQueue->cTxLock = ( int8_t ) ( cTxLock + 1 ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) +{ +BaseType_t xEntryTimeSet = pdFALSE; +TimeOut_t xTimeOut; +Queue_t * const pxQueue = xQueue; + + /* Check the pointer is not NULL. */ + configASSERT( ( pxQueue ) ); + + /* The buffer into which data is received can only be NULL if the data size + is zero (so no data is copied into the buffer. */ + configASSERT( !( ( ( pvBuffer ) == NULL ) && ( ( pxQueue )->uxItemSize != ( UBaseType_t ) 0U ) ) ); + + /* Cannot block if the scheduler is suspended. */ + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + + /*lint -save -e904 This function relaxes the coding standard somewhat to + allow return statements within the function itself. This is done in the + interest of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + const UBaseType_t uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + /* Is there data in the queue now? To be running the calling task + must be the highest priority task wanting to access the queue. */ + if( uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* Data available, remove one item. */ + prvCopyDataFromQueue( pxQueue, pvBuffer ); + traceQUEUE_RECEIVE( pxQueue ); + pxQueue->uxMessagesWaiting = uxMessagesWaiting - ( UBaseType_t ) 1; + + /* There is now space in the queue, were any tasks waiting to + post to the queue? If so, unblock the highest priority waiting + task. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( TickType_t ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure. */ + vTaskInternalSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + else + { + /* Entry time was already set. */ + mtCOVERAGE_TEST_MARKER(); + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + /* The timeout has not expired. If the queue is still empty place + the task on the list of tasks waiting to receive from the queue. */ + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* The queue contains data again. Loop back to try and read the + data. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* Timed out. If there is no data in the queue exit, otherwise loop + back and attempt to read the data. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } /*lint -restore */ +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueSemaphoreTake( QueueHandle_t xQueue, TickType_t xTicksToWait ) +{ +BaseType_t xEntryTimeSet = pdFALSE; +TimeOut_t xTimeOut; +Queue_t * const pxQueue = xQueue; + +#if( configUSE_MUTEXES == 1 ) + BaseType_t xInheritanceOccurred = pdFALSE; +#endif + + /* Check the queue pointer is not NULL. */ + configASSERT( ( pxQueue ) ); + + /* Check this really is a semaphore, in which case the item size will be + 0. */ + configASSERT( pxQueue->uxItemSize == 0 ); + + /* Cannot block if the scheduler is suspended. */ + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + + /*lint -save -e904 This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Semaphores are queues with an item size of 0, and where the + number of messages in the queue is the semaphore's count value. */ + const UBaseType_t uxSemaphoreCount = pxQueue->uxMessagesWaiting; + + /* Is there data in the queue now? To be running the calling task + must be the highest priority task wanting to access the queue. */ + if( uxSemaphoreCount > ( UBaseType_t ) 0 ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* Semaphores are queues with a data size of zero and where the + messages waiting is the semaphore's count. Reduce the count. */ + pxQueue->uxMessagesWaiting = uxSemaphoreCount - ( UBaseType_t ) 1; + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->u.xSemaphore.xMutexHolder = pvTaskIncrementMutexHeldCount(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_MUTEXES */ + + /* Check to see if other tasks are blocked waiting to give the + semaphore, and if so, unblock the highest priority such task. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( TickType_t ) 0 ) + { + /* For inheritance to have occurred there must have been an + initial timeout, and an adjusted timeout cannot become 0, as + if it were 0 the function would have exited. */ + #if( configUSE_MUTEXES == 1 ) + { + configASSERT( xInheritanceOccurred == pdFALSE ); + } + #endif /* configUSE_MUTEXES */ + + /* The semaphore count was 0 and no block time is specified + (or the block time has expired) so exit now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The semaphore count was 0 and a block time was specified + so configure the timeout structure ready to block. */ + vTaskInternalSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + else + { + /* Entry time was already set. */ + mtCOVERAGE_TEST_MARKER(); + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can give to and take from the semaphore + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + /* A block time is specified and not expired. If the semaphore + count is 0 then enter the Blocked state to wait for a semaphore to + become available. As semaphores are implemented with queues the + queue being empty is equivalent to the semaphore count being 0. */ + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + taskENTER_CRITICAL(); + { + xInheritanceOccurred = xTaskPriorityInherit( pxQueue->u.xSemaphore.xMutexHolder ); + } + taskEXIT_CRITICAL(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* There was no timeout and the semaphore count was not 0, so + attempt to take the semaphore again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* Timed out. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + /* If the semaphore count is 0 exit now as the timeout has + expired. Otherwise return to attempt to take the semaphore that is + known to be available. As semaphores are implemented by queues the + queue being empty is equivalent to the semaphore count being 0. */ + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + #if ( configUSE_MUTEXES == 1 ) + { + /* xInheritanceOccurred could only have be set if + pxQueue->uxQueueType == queueQUEUE_IS_MUTEX so no need to + test the mutex type again to check it is actually a mutex. */ + if( xInheritanceOccurred != pdFALSE ) + { + taskENTER_CRITICAL(); + { + UBaseType_t uxHighestWaitingPriority; + + /* This task blocking on the mutex caused another + task to inherit this task's priority. Now this task + has timed out the priority should be disinherited + again, but only as low as the next highest priority + task that is waiting for the same mutex. */ + uxHighestWaitingPriority = prvGetDisinheritPriorityAfterTimeout( pxQueue ); + vTaskPriorityDisinheritAfterTimeout( pxQueue->u.xSemaphore.xMutexHolder, uxHighestWaitingPriority ); + } + taskEXIT_CRITICAL(); + } + } + #endif /* configUSE_MUTEXES */ + + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } /*lint -restore */ +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueuePeek( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) +{ +BaseType_t xEntryTimeSet = pdFALSE; +TimeOut_t xTimeOut; +int8_t *pcOriginalReadPosition; +Queue_t * const pxQueue = xQueue; + + /* Check the pointer is not NULL. */ + configASSERT( ( pxQueue ) ); + + /* The buffer into which data is received can only be NULL if the data size + is zero (so no data is copied into the buffer. */ + configASSERT( !( ( ( pvBuffer ) == NULL ) && ( ( pxQueue )->uxItemSize != ( UBaseType_t ) 0U ) ) ); + + /* Cannot block if the scheduler is suspended. */ + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + + /*lint -save -e904 This function relaxes the coding standard somewhat to + allow return statements within the function itself. This is done in the + interest of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + const UBaseType_t uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + /* Is there data in the queue now? To be running the calling task + must be the highest priority task wanting to access the queue. */ + if( uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* Remember the read position so it can be reset after the data + is read from the queue as this function is only peeking the + data, not removing it. */ + pcOriginalReadPosition = pxQueue->u.xQueue.pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + traceQUEUE_PEEK( pxQueue ); + + /* The data is not being removed, so reset the read pointer. */ + pxQueue->u.xQueue.pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( TickType_t ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_PEEK_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure ready to enter the blocked + state. */ + vTaskInternalSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + else + { + /* Entry time was already set. */ + mtCOVERAGE_TEST_MARKER(); + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + /* Timeout has not expired yet, check to see if there is data in the + queue now, and if not enter the Blocked state to wait for data. */ + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_PEEK( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* There is data in the queue now, so don't enter the blocked + state, instead return to try and obtain the data. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. If there is still no data in the queue + exit, otherwise go back and try to read the data again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceQUEUE_PEEK_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } /*lint -restore */ +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueReceiveFromISR( QueueHandle_t xQueue, void * const pvBuffer, BaseType_t * const pxHigherPriorityTaskWoken ) +{ +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) ); + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + const UBaseType_t uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + /* Cannot block in an ISR, so check there is data available. */ + if( uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + const int8_t cRxLock = pxQueue->cRxLock; + + traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + pxQueue->uxMessagesWaiting = uxMessagesWaiting - ( UBaseType_t ) 1; + + /* If the queue is locked the event list will not be modified. + Instead update the lock count so the task that unlocks the queue + will know that an ISR has removed data while the queue was + locked. */ + if( cRxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than us so + force a context switch. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was removed while it was locked. */ + pxQueue->cRxLock = ( int8_t ) ( cRxLock + 1 ); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueuePeekFromISR( QueueHandle_t xQueue, void * const pvBuffer ) +{ +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; +int8_t *pcOriginalReadPosition; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) ); + configASSERT( pxQueue->uxItemSize != 0 ); /* Can't peek a semaphore. */ + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* Cannot block in an ISR, so check there is data available. */ + if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + traceQUEUE_PEEK_FROM_ISR( pxQueue ); + + /* Remember the read position so it can be reset as nothing is + actually being removed from the queue. */ + pcOriginalReadPosition = pxQueue->u.xQueue.pcReadFrom; + prvCopyDataFromQueue( pxQueue, pvBuffer ); + pxQueue->u.xQueue.pcReadFrom = pcOriginalReadPosition; + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_PEEK_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue ) +{ +UBaseType_t uxReturn; + + configASSERT( xQueue ); + + taskENTER_CRITICAL(); + { + uxReturn = ( ( Queue_t * ) xQueue )->uxMessagesWaiting; + } + taskEXIT_CRITICAL(); + + return uxReturn; +} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */ +/*-----------------------------------------------------------*/ + +UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue ) +{ +UBaseType_t uxReturn; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + { + uxReturn = pxQueue->uxLength - pxQueue->uxMessagesWaiting; + } + taskEXIT_CRITICAL(); + + return uxReturn; +} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */ +/*-----------------------------------------------------------*/ + +UBaseType_t uxQueueMessagesWaitingFromISR( const QueueHandle_t xQueue ) +{ +UBaseType_t uxReturn; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + uxReturn = pxQueue->uxMessagesWaiting; + + return uxReturn; +} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */ +/*-----------------------------------------------------------*/ + +void vQueueDelete( QueueHandle_t xQueue ) +{ +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + traceQUEUE_DELETE( pxQueue ); + + #if ( configQUEUE_REGISTRY_SIZE > 0 ) + { + vQueueUnregisterQueue( pxQueue ); + } + #endif + + #if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 0 ) ) + { + /* The queue can only have been allocated dynamically - free it + again. */ + vPortFree( pxQueue ); + } + #elif( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + { + /* The queue could have been allocated statically or dynamically, so + check before attempting to free the memory. */ + if( pxQueue->ucStaticallyAllocated == ( uint8_t ) pdFALSE ) + { + vPortFree( pxQueue ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #else + { + /* The queue must have been statically allocated, so is not going to be + deleted. Avoid compiler warnings about the unused parameter. */ + ( void ) pxQueue; + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxQueueGetQueueNumber( QueueHandle_t xQueue ) + { + return ( ( Queue_t * ) xQueue )->uxQueueNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vQueueSetQueueNumber( QueueHandle_t xQueue, UBaseType_t uxQueueNumber ) + { + ( ( Queue_t * ) xQueue )->uxQueueNumber = uxQueueNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + uint8_t ucQueueGetQueueType( QueueHandle_t xQueue ) + { + return ( ( Queue_t * ) xQueue )->ucQueueType; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if( configUSE_MUTEXES == 1 ) + + static UBaseType_t prvGetDisinheritPriorityAfterTimeout( const Queue_t * const pxQueue ) + { + UBaseType_t uxHighestPriorityOfWaitingTasks; + + /* If a task waiting for a mutex causes the mutex holder to inherit a + priority, but the waiting task times out, then the holder should + disinherit the priority - but only down to the highest priority of any + other tasks that are waiting for the same mutex. For this purpose, + return the priority of the highest priority task that is waiting for the + mutex. */ + if( listCURRENT_LIST_LENGTH( &( pxQueue->xTasksWaitingToReceive ) ) > 0U ) + { + uxHighestPriorityOfWaitingTasks = ( UBaseType_t ) configMAX_PRIORITIES - ( UBaseType_t ) listGET_ITEM_VALUE_OF_HEAD_ENTRY( &( pxQueue->xTasksWaitingToReceive ) ); + } + else + { + uxHighestPriorityOfWaitingTasks = tskIDLE_PRIORITY; + } + + return uxHighestPriorityOfWaitingTasks; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +static BaseType_t prvCopyDataToQueue( Queue_t * const pxQueue, const void *pvItemToQueue, const BaseType_t xPosition ) +{ +BaseType_t xReturn = pdFALSE; +UBaseType_t uxMessagesWaiting; + + /* This function is called from a critical section. */ + + uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + if( pxQueue->uxItemSize == ( UBaseType_t ) 0 ) + { + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* The mutex is no longer being held. */ + xReturn = xTaskPriorityDisinherit( pxQueue->u.xSemaphore.xMutexHolder ); + pxQueue->u.xSemaphore.xMutexHolder = NULL; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_MUTEXES */ + } + else if( xPosition == queueSEND_TO_BACK ) + { + ( void ) memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 !e418 !e9087 MISRA exception as the casts are only redundant for some ports, plus previous logic ensures a null pointer can only be passed to memcpy() if the copy size is 0. Cast to void required by function signature and safe as no alignment requirement and copy length specified in bytes. */ + pxQueue->pcWriteTo += pxQueue->uxItemSize; /*lint !e9016 Pointer arithmetic on char types ok, especially in this use case where it is the clearest way of conveying intent. */ + if( pxQueue->pcWriteTo >= pxQueue->u.xQueue.pcTail ) /*lint !e946 MISRA exception justified as comparison of pointers is the cleanest solution. */ + { + pxQueue->pcWriteTo = pxQueue->pcHead; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + ( void ) memcpy( ( void * ) pxQueue->u.xQueue.pcReadFrom, pvItemToQueue, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 !e9087 !e418 MISRA exception as the casts are only redundant for some ports. Cast to void required by function signature and safe as no alignment requirement and copy length specified in bytes. Assert checks null pointer only used when length is 0. */ + pxQueue->u.xQueue.pcReadFrom -= pxQueue->uxItemSize; + if( pxQueue->u.xQueue.pcReadFrom < pxQueue->pcHead ) /*lint !e946 MISRA exception justified as comparison of pointers is the cleanest solution. */ + { + pxQueue->u.xQueue.pcReadFrom = ( pxQueue->u.xQueue.pcTail - pxQueue->uxItemSize ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xPosition == queueOVERWRITE ) + { + if( uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* An item is not being added but overwritten, so subtract + one from the recorded number of items in the queue so when + one is added again below the number of recorded items remains + correct. */ + --uxMessagesWaiting; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + pxQueue->uxMessagesWaiting = uxMessagesWaiting + ( UBaseType_t ) 1; + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataFromQueue( Queue_t * const pxQueue, void * const pvBuffer ) +{ + if( pxQueue->uxItemSize != ( UBaseType_t ) 0 ) + { + pxQueue->u.xQueue.pcReadFrom += pxQueue->uxItemSize; /*lint !e9016 Pointer arithmetic on char types ok, especially in this use case where it is the clearest way of conveying intent. */ + if( pxQueue->u.xQueue.pcReadFrom >= pxQueue->u.xQueue.pcTail ) /*lint !e946 MISRA exception justified as use of the relational operator is the cleanest solutions. */ + { + pxQueue->u.xQueue.pcReadFrom = pxQueue->pcHead; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + ( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.xQueue.pcReadFrom, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 !e418 !e9087 MISRA exception as the casts are only redundant for some ports. Also previous logic ensures a null pointer can only be passed to memcpy() when the count is 0. Cast to void required by function signature and safe as no alignment requirement and copy length specified in bytes. */ + } +} +/*-----------------------------------------------------------*/ + +static void prvUnlockQueue( Queue_t * const pxQueue ) +{ + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ + + /* The lock counts contains the number of extra data items placed or + removed from the queue while the queue was locked. When a queue is + locked items can be added or removed, but the event lists cannot be + updated. */ + taskENTER_CRITICAL(); + { + int8_t cTxLock = pxQueue->cTxLock; + + /* See if data was added to the queue while it was locked. */ + while( cTxLock > queueLOCKED_UNMODIFIED ) + { + /* Data was posted while the queue was locked. Are any tasks + blocked waiting for data to become available? */ + #if ( configUSE_QUEUE_SETS == 1 ) + { + if( pxQueue->pxQueueSetContainer != NULL ) + { + if( prvNotifyQueueSetContainer( pxQueue ) != pdFALSE ) + { + /* The queue is a member of a queue set, and posting to + the queue set caused a higher priority task to unblock. + A context switch is required. */ + vTaskMissedYield(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* Tasks that are removed from the event list will get + added to the pending ready list as the scheduler is still + suspended. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + vTaskMissedYield(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + break; + } + } + } + #else /* configUSE_QUEUE_SETS */ + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that + a context switch is required. */ + vTaskMissedYield(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + break; + } + } + #endif /* configUSE_QUEUE_SETS */ + + --cTxLock; + } + + pxQueue->cTxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); + + /* Do the same for the Rx lock. */ + taskENTER_CRITICAL(); + { + int8_t cRxLock = pxQueue->cRxLock; + + while( cRxLock > queueLOCKED_UNMODIFIED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + vTaskMissedYield(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + --cRxLock; + } + else + { + break; + } + } + + pxQueue->cRxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +static BaseType_t prvIsQueueEmpty( const Queue_t *pxQueue ) +{ +BaseType_t xReturn; + + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0 ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueIsQueueEmptyFromISR( const QueueHandle_t xQueue ) +{ +BaseType_t xReturn; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0 ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} /*lint !e818 xQueue could not be pointer to const because it is a typedef. */ +/*-----------------------------------------------------------*/ + +static BaseType_t prvIsQueueFull( const Queue_t *pxQueue ) +{ +BaseType_t xReturn; + + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting == pxQueue->uxLength ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueIsQueueFullFromISR( const QueueHandle_t xQueue ) +{ +BaseType_t xReturn; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + if( pxQueue->uxMessagesWaiting == pxQueue->uxLength ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} /*lint !e818 xQueue could not be pointer to const because it is a typedef. */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_CO_ROUTINES == 1 ) + + BaseType_t xQueueCRSend( QueueHandle_t xQueue, const void *pvItemToQueue, TickType_t xTicksToWait ) + { + BaseType_t xReturn; + Queue_t * const pxQueue = xQueue; + + /* If the queue is already full we may have to block. A critical section + is required to prevent an interrupt removing something from the queue + between the check to see if the queue is full and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + /* The queue is full - do we want to block or just leave without + posting? */ + if( xTicksToWait > ( TickType_t ) 0 ) + { + /* As this is called from a coroutine we cannot block directly, but + return indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + /* There is room in the queue, copy the data into the queue. */ + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + xReturn = pdPASS; + + /* Were any co-routines waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The co-routine waiting has a higher priority so record + that a yield might be appropriate. */ + xReturn = errQUEUE_YIELD; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + xReturn = errQUEUE_FULL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; + } + +#endif /* configUSE_CO_ROUTINES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_CO_ROUTINES == 1 ) + + BaseType_t xQueueCRReceive( QueueHandle_t xQueue, void *pvBuffer, TickType_t xTicksToWait ) + { + BaseType_t xReturn; + Queue_t * const pxQueue = xQueue; + + /* If the queue is already empty we may have to block. A critical section + is required to prevent an interrupt adding something to the queue + between the check to see if the queue is empty and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0 ) + { + /* There are no messages in the queue, do we want to block or just + leave with nothing? */ + if( xTicksToWait > ( TickType_t ) 0 ) + { + /* As this is a co-routine we cannot block directly, but return + indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + portENABLE_INTERRUPTS(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* Data is available from the queue. */ + pxQueue->u.xQueue.pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->u.xQueue.pcReadFrom >= pxQueue->u.xQueue.pcTail ) + { + pxQueue->u.xQueue.pcReadFrom = pxQueue->pcHead; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + --( pxQueue->uxMessagesWaiting ); + ( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.xQueue.pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + xReturn = pdPASS; + + /* Were any co-routines waiting for space to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + xReturn = errQUEUE_YIELD; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + xReturn = pdFAIL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; + } + +#endif /* configUSE_CO_ROUTINES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_CO_ROUTINES == 1 ) + + BaseType_t xQueueCRSendFromISR( QueueHandle_t xQueue, const void *pvItemToQueue, BaseType_t xCoRoutinePreviouslyWoken ) + { + Queue_t * const pxQueue = xQueue; + + /* Cannot block within an ISR so if there is no space on the queue then + exit without doing anything. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + + /* We only want to wake one co-routine per ISR, so check that a + co-routine has not already been woken. */ + if( xCoRoutinePreviouslyWoken == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + return pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xCoRoutinePreviouslyWoken; + } + +#endif /* configUSE_CO_ROUTINES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_CO_ROUTINES == 1 ) + + BaseType_t xQueueCRReceiveFromISR( QueueHandle_t xQueue, void *pvBuffer, BaseType_t *pxCoRoutineWoken ) + { + BaseType_t xReturn; + Queue_t * const pxQueue = xQueue; + + /* We cannot block from an ISR, so check there is data available. If + not then just leave without doing anything. */ + if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* Copy the data from the queue. */ + pxQueue->u.xQueue.pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->u.xQueue.pcReadFrom >= pxQueue->u.xQueue.pcTail ) + { + pxQueue->u.xQueue.pcReadFrom = pxQueue->pcHead; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + --( pxQueue->uxMessagesWaiting ); + ( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.xQueue.pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + if( ( *pxCoRoutineWoken ) == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + *pxCoRoutineWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif /* configUSE_CO_ROUTINES */ +/*-----------------------------------------------------------*/ + +#if ( configQUEUE_REGISTRY_SIZE > 0 ) + + void vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcQueueName ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + { + UBaseType_t ux; + + /* See if there is an empty space in the registry. A NULL name denotes + a free slot. */ + for( ux = ( UBaseType_t ) 0U; ux < ( UBaseType_t ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].pcQueueName == NULL ) + { + /* Store the information on this queue. */ + xQueueRegistry[ ux ].pcQueueName = pcQueueName; + xQueueRegistry[ ux ].xHandle = xQueue; + + traceQUEUE_REGISTRY_ADD( xQueue, pcQueueName ); + break; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + +#endif /* configQUEUE_REGISTRY_SIZE */ +/*-----------------------------------------------------------*/ + +#if ( configQUEUE_REGISTRY_SIZE > 0 ) + + const char *pcQueueGetName( QueueHandle_t xQueue ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + { + UBaseType_t ux; + const char *pcReturn = NULL; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + + /* Note there is nothing here to protect against another task adding or + removing entries from the registry while it is being searched. */ + for( ux = ( UBaseType_t ) 0U; ux < ( UBaseType_t ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + pcReturn = xQueueRegistry[ ux ].pcQueueName; + break; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + return pcReturn; + } /*lint !e818 xQueue cannot be a pointer to const because it is a typedef. */ + +#endif /* configQUEUE_REGISTRY_SIZE */ +/*-----------------------------------------------------------*/ + +#if ( configQUEUE_REGISTRY_SIZE > 0 ) + + void vQueueUnregisterQueue( QueueHandle_t xQueue ) + { + UBaseType_t ux; + + /* See if the handle of the queue being unregistered in actually in the + registry. */ + for( ux = ( UBaseType_t ) 0U; ux < ( UBaseType_t ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + /* Set the name to NULL to show that this slot if free again. */ + xQueueRegistry[ ux ].pcQueueName = NULL; + + /* Set the handle to NULL to ensure the same queue handle cannot + appear in the registry twice if it is added, removed, then + added again. */ + xQueueRegistry[ ux ].xHandle = ( QueueHandle_t ) 0; + break; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + } /*lint !e818 xQueue could not be pointer to const because it is a typedef. */ + +#endif /* configQUEUE_REGISTRY_SIZE */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TIMERS == 1 ) + + void vQueueWaitForMessageRestricted( QueueHandle_t xQueue, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) + { + Queue_t * const pxQueue = xQueue; + + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements. + It can result in vListInsert() being called on a list that can only + possibly ever have one item in it, so the list will be fast, but even + so it should be called with the scheduler locked and not from a critical + section. */ + + /* Only do anything if there are no messages in the queue. This function + will not actually cause the task to block, just place it on a blocked + list. It will not block until the scheduler is unlocked - at which + time a yield will be performed. If an item is added to the queue while + the queue is locked, and the calling task blocks on the queue, then the + calling task will be immediately unblocked when the queue is unlocked. */ + prvLockQueue( pxQueue ); + if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0U ) + { + /* There is nothing in the queue, block for the specified period. */ + vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait, xWaitIndefinitely ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + prvUnlockQueue( pxQueue ); + } + +#endif /* configUSE_TIMERS */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_QUEUE_SETS == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + QueueSetHandle_t xQueueCreateSet( const UBaseType_t uxEventQueueLength ) + { + QueueSetHandle_t pxQueue; + + pxQueue = xQueueGenericCreate( uxEventQueueLength, ( UBaseType_t ) sizeof( Queue_t * ), queueQUEUE_TYPE_SET ); + + return pxQueue; + } + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + BaseType_t xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) + { + BaseType_t xReturn; + + taskENTER_CRITICAL(); + { + if( ( ( Queue_t * ) xQueueOrSemaphore )->pxQueueSetContainer != NULL ) + { + /* Cannot add a queue/semaphore to more than one queue set. */ + xReturn = pdFAIL; + } + else if( ( ( Queue_t * ) xQueueOrSemaphore )->uxMessagesWaiting != ( UBaseType_t ) 0 ) + { + /* Cannot add a queue/semaphore to a queue set if there are already + items in the queue/semaphore. */ + xReturn = pdFAIL; + } + else + { + ( ( Queue_t * ) xQueueOrSemaphore )->pxQueueSetContainer = xQueueSet; + xReturn = pdPASS; + } + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + BaseType_t xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) + { + BaseType_t xReturn; + Queue_t * const pxQueueOrSemaphore = ( Queue_t * ) xQueueOrSemaphore; + + if( pxQueueOrSemaphore->pxQueueSetContainer != xQueueSet ) + { + /* The queue was not a member of the set. */ + xReturn = pdFAIL; + } + else if( pxQueueOrSemaphore->uxMessagesWaiting != ( UBaseType_t ) 0 ) + { + /* It is dangerous to remove a queue from a set when the queue is + not empty because the queue set will still hold pending events for + the queue. */ + xReturn = pdFAIL; + } + else + { + taskENTER_CRITICAL(); + { + /* The queue is no longer contained in the set. */ + pxQueueOrSemaphore->pxQueueSetContainer = NULL; + } + taskEXIT_CRITICAL(); + xReturn = pdPASS; + } + + return xReturn; + } /*lint !e818 xQueueSet could not be declared as pointing to const as it is a typedef. */ + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + QueueSetMemberHandle_t xQueueSelectFromSet( QueueSetHandle_t xQueueSet, TickType_t const xTicksToWait ) + { + QueueSetMemberHandle_t xReturn = NULL; + + ( void ) xQueueReceive( ( QueueHandle_t ) xQueueSet, &xReturn, xTicksToWait ); /*lint !e961 Casting from one typedef to another is not redundant. */ + return xReturn; + } + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + QueueSetMemberHandle_t xQueueSelectFromSetFromISR( QueueSetHandle_t xQueueSet ) + { + QueueSetMemberHandle_t xReturn = NULL; + + ( void ) xQueueReceiveFromISR( ( QueueHandle_t ) xQueueSet, &xReturn, NULL ); /*lint !e961 Casting from one typedef to another is not redundant. */ + return xReturn; + } + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + static BaseType_t prvNotifyQueueSetContainer( const Queue_t * const pxQueue ) + { + Queue_t *pxQueueSetContainer = pxQueue->pxQueueSetContainer; + BaseType_t xReturn = pdFALSE; + + /* This function must be called form a critical section. */ + + configASSERT( pxQueueSetContainer ); + configASSERT( pxQueueSetContainer->uxMessagesWaiting < pxQueueSetContainer->uxLength ); + + if( pxQueueSetContainer->uxMessagesWaiting < pxQueueSetContainer->uxLength ) + { + const int8_t cTxLock = pxQueueSetContainer->cTxLock; + + traceQUEUE_SEND( pxQueueSetContainer ); + + /* The data copied is the handle of the queue that contains data. */ + xReturn = prvCopyDataToQueue( pxQueueSetContainer, &pxQueue, queueSEND_TO_BACK ); + + if( cTxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueueSetContainer->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueueSetContainer->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority. */ + xReturn = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + pxQueueSetContainer->cTxLock = ( int8_t ) ( cTxLock + 1 ); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; + } + +#endif /* configUSE_QUEUE_SETS */ + + + + + + + + + + + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/readme.txt b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/readme.txt new file mode 100644 index 0000000..58480c5 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/readme.txt @@ -0,0 +1,17 @@ +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 directory contains the three files that are common to +every port - list.c, queue.c and tasks.c. The kernel is contained within these +three files. croutine.c implements the optional co-routine functionality - which +is normally only used on very memory limited systems. + ++ The FreeRTOS/Source/Portable directory contains the files that are specific to +a particular microcontroller and or compiler. + ++ The FreeRTOS/Source/include directory contains the real time kernel header +files. + +See the readme file in the FreeRTOS/Source/Portable directory for more +information. \ No newline at end of file diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/stream_buffer.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/stream_buffer.c new file mode 100644 index 0000000..b47ce71 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/stream_buffer.c @@ -0,0 +1,1263 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* Standard includes. */ +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* FreeRTOS includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "stream_buffer.h" + +#if( configUSE_TASK_NOTIFICATIONS != 1 ) + #error configUSE_TASK_NOTIFICATIONS must be set to 1 to build stream_buffer.c +#endif + +/* Lint e961, e9021 and e750 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750 !e9021. */ + +/* If the user has not provided application specific Rx notification macros, +or #defined the notification macros away, them provide default implementations +that uses task notifications. */ +/*lint -save -e9026 Function like macros allowed and needed here so they can be overidden. */ +#ifndef sbRECEIVE_COMPLETED + #define sbRECEIVE_COMPLETED( pxStreamBuffer ) \ + vTaskSuspendAll(); \ + { \ + if( ( pxStreamBuffer )->xTaskWaitingToSend != NULL ) \ + { \ + ( void ) xTaskNotify( ( pxStreamBuffer )->xTaskWaitingToSend, \ + ( uint32_t ) 0, \ + eNoAction ); \ + ( pxStreamBuffer )->xTaskWaitingToSend = NULL; \ + } \ + } \ + ( void ) xTaskResumeAll(); +#endif /* sbRECEIVE_COMPLETED */ + +#ifndef sbRECEIVE_COMPLETED_FROM_ISR + #define sbRECEIVE_COMPLETED_FROM_ISR( pxStreamBuffer, \ + pxHigherPriorityTaskWoken ) \ + { \ + UBaseType_t uxSavedInterruptStatus; \ + \ + uxSavedInterruptStatus = ( UBaseType_t ) portSET_INTERRUPT_MASK_FROM_ISR(); \ + { \ + if( ( pxStreamBuffer )->xTaskWaitingToSend != NULL ) \ + { \ + ( void ) xTaskNotifyFromISR( ( pxStreamBuffer )->xTaskWaitingToSend, \ + ( uint32_t ) 0, \ + eNoAction, \ + pxHigherPriorityTaskWoken ); \ + ( pxStreamBuffer )->xTaskWaitingToSend = NULL; \ + } \ + } \ + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); \ + } +#endif /* sbRECEIVE_COMPLETED_FROM_ISR */ + +/* If the user has not provided an application specific Tx notification macro, +or #defined the notification macro away, them provide a default implementation +that uses task notifications. */ +#ifndef sbSEND_COMPLETED + #define sbSEND_COMPLETED( pxStreamBuffer ) \ + vTaskSuspendAll(); \ + { \ + if( ( pxStreamBuffer )->xTaskWaitingToReceive != NULL ) \ + { \ + ( void ) xTaskNotify( ( pxStreamBuffer )->xTaskWaitingToReceive, \ + ( uint32_t ) 0, \ + eNoAction ); \ + ( pxStreamBuffer )->xTaskWaitingToReceive = NULL; \ + } \ + } \ + ( void ) xTaskResumeAll(); +#endif /* sbSEND_COMPLETED */ + +#ifndef sbSEND_COMPLETE_FROM_ISR + #define sbSEND_COMPLETE_FROM_ISR( pxStreamBuffer, pxHigherPriorityTaskWoken ) \ + { \ + UBaseType_t uxSavedInterruptStatus; \ + \ + uxSavedInterruptStatus = ( UBaseType_t ) portSET_INTERRUPT_MASK_FROM_ISR(); \ + { \ + if( ( pxStreamBuffer )->xTaskWaitingToReceive != NULL ) \ + { \ + ( void ) xTaskNotifyFromISR( ( pxStreamBuffer )->xTaskWaitingToReceive, \ + ( uint32_t ) 0, \ + eNoAction, \ + pxHigherPriorityTaskWoken ); \ + ( pxStreamBuffer )->xTaskWaitingToReceive = NULL; \ + } \ + } \ + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); \ + } +#endif /* sbSEND_COMPLETE_FROM_ISR */ +/*lint -restore (9026) */ + +/* The number of bytes used to hold the length of a message in the buffer. */ +#define sbBYTES_TO_STORE_MESSAGE_LENGTH ( sizeof( configMESSAGE_BUFFER_LENGTH_TYPE ) ) + +/* Bits stored in the ucFlags field of the stream buffer. */ +#define sbFLAGS_IS_MESSAGE_BUFFER ( ( uint8_t ) 1 ) /* Set if the stream buffer was created as a message buffer, in which case it holds discrete messages rather than a stream. */ +#define sbFLAGS_IS_STATICALLY_ALLOCATED ( ( uint8_t ) 2 ) /* Set if the stream buffer was created using statically allocated memory. */ + +/*-----------------------------------------------------------*/ + +/* Structure that hold state information on the buffer. */ +typedef struct StreamBufferDef_t /*lint !e9058 Style convention uses tag. */ +{ + volatile size_t xTail; /* Index to the next item to read within the buffer. */ + volatile size_t xHead; /* Index to the next item to write within the buffer. */ + size_t xLength; /* The length of the buffer pointed to by pucBuffer. */ + size_t xTriggerLevelBytes; /* The number of bytes that must be in the stream buffer before a task that is waiting for data is unblocked. */ + volatile TaskHandle_t xTaskWaitingToReceive; /* Holds the handle of a task waiting for data, or NULL if no tasks are waiting. */ + volatile TaskHandle_t xTaskWaitingToSend; /* Holds the handle of a task waiting to send data to a message buffer that is full. */ + uint8_t *pucBuffer; /* Points to the buffer itself - that is - the RAM that stores the data passed through the buffer. */ + uint8_t ucFlags; + + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxStreamBufferNumber; /* Used for tracing purposes. */ + #endif +} StreamBuffer_t; + +/* + * The number of bytes available to be read from the buffer. + */ +static size_t prvBytesInBuffer( const StreamBuffer_t * const pxStreamBuffer ) PRIVILEGED_FUNCTION; + +/* + * Add xCount bytes from pucData into the pxStreamBuffer message buffer. + * Returns the number of bytes written, which will either equal xCount in the + * success case, or 0 if there was not enough space in the buffer (in which case + * no data is written into the buffer). + */ +static size_t prvWriteBytesToBuffer( StreamBuffer_t * const pxStreamBuffer, const uint8_t *pucData, size_t xCount ) PRIVILEGED_FUNCTION; + +/* + * If the stream buffer is being used as a message buffer, then reads an entire + * message out of the buffer. If the stream buffer is being used as a stream + * buffer then read as many bytes as possible from the buffer. + * prvReadBytesFromBuffer() is called to actually extract the bytes from the + * buffer's data storage area. + */ +static size_t prvReadMessageFromBuffer( StreamBuffer_t *pxStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + size_t xBytesAvailable, + size_t xBytesToStoreMessageLength ) PRIVILEGED_FUNCTION; + +/* + * If the stream buffer is being used as a message buffer, then writes an entire + * message to the buffer. If the stream buffer is being used as a stream + * buffer then write as many bytes as possible to the buffer. + * prvWriteBytestoBuffer() is called to actually send the bytes to the buffer's + * data storage area. + */ +static size_t prvWriteMessageToBuffer( StreamBuffer_t * const pxStreamBuffer, + const void * pvTxData, + size_t xDataLengthBytes, + size_t xSpace, + size_t xRequiredSpace ) PRIVILEGED_FUNCTION; + +/* + * Read xMaxCount bytes from the pxStreamBuffer message buffer and write them + * to pucData. + */ +static size_t prvReadBytesFromBuffer( StreamBuffer_t *pxStreamBuffer, + uint8_t *pucData, + size_t xMaxCount, + size_t xBytesAvailable ) PRIVILEGED_FUNCTION; + +/* + * Called by both pxStreamBufferCreate() and pxStreamBufferCreateStatic() to + * initialise the members of the newly created stream buffer structure. + */ +static void prvInitialiseNewStreamBuffer( StreamBuffer_t * const pxStreamBuffer, + uint8_t * const pucBuffer, + size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + uint8_t ucFlags ) PRIVILEGED_FUNCTION; + +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + StreamBufferHandle_t xStreamBufferGenericCreate( size_t xBufferSizeBytes, size_t xTriggerLevelBytes, BaseType_t xIsMessageBuffer ) + { + uint8_t *pucAllocatedMemory; + uint8_t ucFlags; + + /* In case the stream buffer is going to be used as a message buffer + (that is, it will hold discrete messages with a little meta data that + says how big the next message is) check the buffer will be large enough + to hold at least one message. */ + if( xIsMessageBuffer == pdTRUE ) + { + /* Is a message buffer but not statically allocated. */ + ucFlags = sbFLAGS_IS_MESSAGE_BUFFER; + configASSERT( xBufferSizeBytes > sbBYTES_TO_STORE_MESSAGE_LENGTH ); + } + else + { + /* Not a message buffer and not statically allocated. */ + ucFlags = 0; + configASSERT( xBufferSizeBytes > 0 ); + } + configASSERT( xTriggerLevelBytes <= xBufferSizeBytes ); + + /* A trigger level of 0 would cause a waiting task to unblock even when + the buffer was empty. */ + if( xTriggerLevelBytes == ( size_t ) 0 ) + { + xTriggerLevelBytes = ( size_t ) 1; + } + + /* A stream buffer requires a StreamBuffer_t structure and a buffer. + Both are allocated in a single call to pvPortMalloc(). The + StreamBuffer_t structure is placed at the start of the allocated memory + and the buffer follows immediately after. The requested size is + incremented so the free space is returned as the user would expect - + this is a quirk of the implementation that means otherwise the free + space would be reported as one byte smaller than would be logically + expected. */ + xBufferSizeBytes++; + pucAllocatedMemory = ( uint8_t * ) pvPortMalloc( xBufferSizeBytes + sizeof( StreamBuffer_t ) ); /*lint !e9079 malloc() only returns void*. */ + + if( pucAllocatedMemory != NULL ) + { + prvInitialiseNewStreamBuffer( ( StreamBuffer_t * ) pucAllocatedMemory, /* Structure at the start of the allocated memory. */ /*lint !e9087 Safe cast as allocated memory is aligned. */ /*lint !e826 Area is not too small and alignment is guaranteed provided malloc() behaves as expected and returns aligned buffer. */ + pucAllocatedMemory + sizeof( StreamBuffer_t ), /* Storage area follows. */ /*lint !e9016 Indexing past structure valid for uint8_t pointer, also storage area has no alignment requirement. */ + xBufferSizeBytes, + xTriggerLevelBytes, + ucFlags ); + + traceSTREAM_BUFFER_CREATE( ( ( StreamBuffer_t * ) pucAllocatedMemory ), xIsMessageBuffer ); + } + else + { + traceSTREAM_BUFFER_CREATE_FAILED( xIsMessageBuffer ); + } + + return ( StreamBufferHandle_t ) pucAllocatedMemory; /*lint !e9087 !e826 Safe cast as allocated memory is aligned. */ + } + +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + StreamBufferHandle_t xStreamBufferGenericCreateStatic( size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + BaseType_t xIsMessageBuffer, + uint8_t * const pucStreamBufferStorageArea, + StaticStreamBuffer_t * const pxStaticStreamBuffer ) + { + StreamBuffer_t * const pxStreamBuffer = ( StreamBuffer_t * ) pxStaticStreamBuffer; /*lint !e740 !e9087 Safe cast as StaticStreamBuffer_t is opaque Streambuffer_t. */ + StreamBufferHandle_t xReturn; + uint8_t ucFlags; + + configASSERT( pucStreamBufferStorageArea ); + configASSERT( pxStaticStreamBuffer ); + configASSERT( xTriggerLevelBytes <= xBufferSizeBytes ); + + /* A trigger level of 0 would cause a waiting task to unblock even when + the buffer was empty. */ + if( xTriggerLevelBytes == ( size_t ) 0 ) + { + xTriggerLevelBytes = ( size_t ) 1; + } + + if( xIsMessageBuffer != pdFALSE ) + { + /* Statically allocated message buffer. */ + ucFlags = sbFLAGS_IS_MESSAGE_BUFFER | sbFLAGS_IS_STATICALLY_ALLOCATED; + } + else + { + /* Statically allocated stream buffer. */ + ucFlags = sbFLAGS_IS_STATICALLY_ALLOCATED; + } + + /* In case the stream buffer is going to be used as a message buffer + (that is, it will hold discrete messages with a little meta data that + says how big the next message is) check the buffer will be large enough + to hold at least one message. */ + configASSERT( xBufferSizeBytes > sbBYTES_TO_STORE_MESSAGE_LENGTH ); + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticStreamBuffer_t equals the size of the real + message buffer structure. */ + volatile size_t xSize = sizeof( StaticStreamBuffer_t ); + configASSERT( xSize == sizeof( StreamBuffer_t ) ); + } /*lint !e529 xSize is referenced is configASSERT() is defined. */ + #endif /* configASSERT_DEFINED */ + + if( ( pucStreamBufferStorageArea != NULL ) && ( pxStaticStreamBuffer != NULL ) ) + { + prvInitialiseNewStreamBuffer( pxStreamBuffer, + pucStreamBufferStorageArea, + xBufferSizeBytes, + xTriggerLevelBytes, + ucFlags ); + + /* Remember this was statically allocated in case it is ever deleted + again. */ + pxStreamBuffer->ucFlags |= sbFLAGS_IS_STATICALLY_ALLOCATED; + + traceSTREAM_BUFFER_CREATE( pxStreamBuffer, xIsMessageBuffer ); + + xReturn = ( StreamBufferHandle_t ) pxStaticStreamBuffer; /*lint !e9087 Data hiding requires cast to opaque type. */ + } + else + { + xReturn = NULL; + traceSTREAM_BUFFER_CREATE_STATIC_FAILED( xReturn, xIsMessageBuffer ); + } + + return xReturn; + } + +#endif /* ( configSUPPORT_STATIC_ALLOCATION == 1 ) */ +/*-----------------------------------------------------------*/ + +void vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer ) +{ +StreamBuffer_t * pxStreamBuffer = xStreamBuffer; + + configASSERT( pxStreamBuffer ); + + traceSTREAM_BUFFER_DELETE( xStreamBuffer ); + + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_STATICALLY_ALLOCATED ) == ( uint8_t ) pdFALSE ) + { + #if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + { + /* Both the structure and the buffer were allocated using a single call + to pvPortMalloc(), hence only one call to vPortFree() is required. */ + vPortFree( ( void * ) pxStreamBuffer ); /*lint !e9087 Standard free() semantics require void *, plus pxStreamBuffer was allocated by pvPortMalloc(). */ + } + #else + { + /* Should not be possible to get here, ucFlags must be corrupt. + Force an assert. */ + configASSERT( xStreamBuffer == ( StreamBufferHandle_t ) ~0 ); + } + #endif + } + else + { + /* The structure and buffer were not allocated dynamically and cannot be + freed - just scrub the structure so future use will assert. */ + ( void ) memset( pxStreamBuffer, 0x00, sizeof( StreamBuffer_t ) ); + } +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferReset( StreamBufferHandle_t xStreamBuffer ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn = pdFAIL; + +#if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxStreamBufferNumber; +#endif + + configASSERT( pxStreamBuffer ); + + #if( configUSE_TRACE_FACILITY == 1 ) + { + /* Store the stream buffer number so it can be restored after the + reset. */ + uxStreamBufferNumber = pxStreamBuffer->uxStreamBufferNumber; + } + #endif + + /* Can only reset a message buffer if there are no tasks blocked on it. */ + taskENTER_CRITICAL(); + { + if( pxStreamBuffer->xTaskWaitingToReceive == NULL ) + { + if( pxStreamBuffer->xTaskWaitingToSend == NULL ) + { + prvInitialiseNewStreamBuffer( pxStreamBuffer, + pxStreamBuffer->pucBuffer, + pxStreamBuffer->xLength, + pxStreamBuffer->xTriggerLevelBytes, + pxStreamBuffer->ucFlags ); + xReturn = pdPASS; + + #if( configUSE_TRACE_FACILITY == 1 ) + { + pxStreamBuffer->uxStreamBufferNumber = uxStreamBufferNumber; + } + #endif + + traceSTREAM_BUFFER_RESET( xStreamBuffer ); + } + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn; + + configASSERT( pxStreamBuffer ); + + /* It is not valid for the trigger level to be 0. */ + if( xTriggerLevel == ( size_t ) 0 ) + { + xTriggerLevel = ( size_t ) 1; + } + + /* The trigger level is the number of bytes that must be in the stream + buffer before a task that is waiting for data is unblocked. */ + if( xTriggerLevel <= pxStreamBuffer->xLength ) + { + pxStreamBuffer->xTriggerLevelBytes = xTriggerLevel; + xReturn = pdPASS; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer ) +{ +const StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xSpace; + + configASSERT( pxStreamBuffer ); + + xSpace = pxStreamBuffer->xLength + pxStreamBuffer->xTail; + xSpace -= pxStreamBuffer->xHead; + xSpace -= ( size_t ) 1; + + if( xSpace >= pxStreamBuffer->xLength ) + { + xSpace -= pxStreamBuffer->xLength; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xSpace; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer ) +{ +const StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReturn; + + configASSERT( pxStreamBuffer ); + + xReturn = prvBytesInBuffer( pxStreamBuffer ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferSend( StreamBufferHandle_t xStreamBuffer, + const void *pvTxData, + size_t xDataLengthBytes, + TickType_t xTicksToWait ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReturn, xSpace = 0; +size_t xRequiredSpace = xDataLengthBytes; +TimeOut_t xTimeOut; + + configASSERT( pvTxData ); + configASSERT( pxStreamBuffer ); + + /* This send function is used to write to both message buffers and stream + buffers. If this is a message buffer then the space needed must be + increased by the amount of bytes needed to store the length of the + message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xRequiredSpace += sbBYTES_TO_STORE_MESSAGE_LENGTH; + + /* Overflow? */ + configASSERT( xRequiredSpace > xDataLengthBytes ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xTicksToWait != ( TickType_t ) 0 ) + { + vTaskSetTimeOutState( &xTimeOut ); + + do + { + /* Wait until the required number of bytes are free in the message + buffer. */ + taskENTER_CRITICAL(); + { + xSpace = xStreamBufferSpacesAvailable( pxStreamBuffer ); + + if( xSpace < xRequiredSpace ) + { + /* Clear notification state as going to wait for space. */ + ( void ) xTaskNotifyStateClear( NULL ); + + /* Should only be one writer. */ + configASSERT( pxStreamBuffer->xTaskWaitingToSend == NULL ); + pxStreamBuffer->xTaskWaitingToSend = xTaskGetCurrentTaskHandle(); + } + else + { + taskEXIT_CRITICAL(); + break; + } + } + taskEXIT_CRITICAL(); + + traceBLOCKING_ON_STREAM_BUFFER_SEND( xStreamBuffer ); + ( void ) xTaskNotifyWait( ( uint32_t ) 0, ( uint32_t ) 0, NULL, xTicksToWait ); + pxStreamBuffer->xTaskWaitingToSend = NULL; + + } while( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xSpace == ( size_t ) 0 ) + { + xSpace = xStreamBufferSpacesAvailable( pxStreamBuffer ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xReturn = prvWriteMessageToBuffer( pxStreamBuffer, pvTxData, xDataLengthBytes, xSpace, xRequiredSpace ); + + if( xReturn > ( size_t ) 0 ) + { + traceSTREAM_BUFFER_SEND( xStreamBuffer, xReturn ); + + /* Was a task waiting for the data? */ + if( prvBytesInBuffer( pxStreamBuffer ) >= pxStreamBuffer->xTriggerLevelBytes ) + { + sbSEND_COMPLETED( pxStreamBuffer ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + traceSTREAM_BUFFER_SEND_FAILED( xStreamBuffer ); + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferSendFromISR( StreamBufferHandle_t xStreamBuffer, + const void *pvTxData, + size_t xDataLengthBytes, + BaseType_t * const pxHigherPriorityTaskWoken ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReturn, xSpace; +size_t xRequiredSpace = xDataLengthBytes; + + configASSERT( pvTxData ); + configASSERT( pxStreamBuffer ); + + /* This send function is used to write to both message buffers and stream + buffers. If this is a message buffer then the space needed must be + increased by the amount of bytes needed to store the length of the + message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xRequiredSpace += sbBYTES_TO_STORE_MESSAGE_LENGTH; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xSpace = xStreamBufferSpacesAvailable( pxStreamBuffer ); + xReturn = prvWriteMessageToBuffer( pxStreamBuffer, pvTxData, xDataLengthBytes, xSpace, xRequiredSpace ); + + if( xReturn > ( size_t ) 0 ) + { + /* Was a task waiting for the data? */ + if( prvBytesInBuffer( pxStreamBuffer ) >= pxStreamBuffer->xTriggerLevelBytes ) + { + sbSEND_COMPLETE_FROM_ISR( pxStreamBuffer, pxHigherPriorityTaskWoken ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceSTREAM_BUFFER_SEND_FROM_ISR( xStreamBuffer, xReturn ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static size_t prvWriteMessageToBuffer( StreamBuffer_t * const pxStreamBuffer, + const void * pvTxData, + size_t xDataLengthBytes, + size_t xSpace, + size_t xRequiredSpace ) +{ + BaseType_t xShouldWrite; + size_t xReturn; + + if( xSpace == ( size_t ) 0 ) + { + /* Doesn't matter if this is a stream buffer or a message buffer, there + is no space to write. */ + xShouldWrite = pdFALSE; + } + else if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) == ( uint8_t ) 0 ) + { + /* This is a stream buffer, as opposed to a message buffer, so writing a + stream of bytes rather than discrete messages. Write as many bytes as + possible. */ + xShouldWrite = pdTRUE; + xDataLengthBytes = configMIN( xDataLengthBytes, xSpace ); + } + else if( xSpace >= xRequiredSpace ) + { + /* This is a message buffer, as opposed to a stream buffer, and there + is enough space to write both the message length and the message itself + into the buffer. Start by writing the length of the data, the data + itself will be written later in this function. */ + xShouldWrite = pdTRUE; + ( void ) prvWriteBytesToBuffer( pxStreamBuffer, ( const uint8_t * ) &( xDataLengthBytes ), sbBYTES_TO_STORE_MESSAGE_LENGTH ); + } + else + { + /* There is space available, but not enough space. */ + xShouldWrite = pdFALSE; + } + + if( xShouldWrite != pdFALSE ) + { + /* Writes the data itself. */ + xReturn = prvWriteBytesToBuffer( pxStreamBuffer, ( const uint8_t * ) pvTxData, xDataLengthBytes ); /*lint !e9079 Storage buffer is implemented as uint8_t for ease of sizing, alighment and access. */ + } + else + { + xReturn = 0; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + TickType_t xTicksToWait ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReceivedLength = 0, xBytesAvailable, xBytesToStoreMessageLength; + + configASSERT( pvRxData ); + configASSERT( pxStreamBuffer ); + + /* This receive function is used by both message buffers, which store + discrete messages, and stream buffers, which store a continuous stream of + bytes. Discrete messages include an additional + sbBYTES_TO_STORE_MESSAGE_LENGTH bytes that hold the length of the + message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xBytesToStoreMessageLength = sbBYTES_TO_STORE_MESSAGE_LENGTH; + } + else + { + xBytesToStoreMessageLength = 0; + } + + if( xTicksToWait != ( TickType_t ) 0 ) + { + /* Checking if there is data and clearing the notification state must be + performed atomically. */ + taskENTER_CRITICAL(); + { + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + + /* If this function was invoked by a message buffer read then + xBytesToStoreMessageLength holds the number of bytes used to hold + the length of the next discrete message. If this function was + invoked by a stream buffer read then xBytesToStoreMessageLength will + be 0. */ + if( xBytesAvailable <= xBytesToStoreMessageLength ) + { + /* Clear notification state as going to wait for data. */ + ( void ) xTaskNotifyStateClear( NULL ); + + /* Should only be one reader. */ + configASSERT( pxStreamBuffer->xTaskWaitingToReceive == NULL ); + pxStreamBuffer->xTaskWaitingToReceive = xTaskGetCurrentTaskHandle(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + if( xBytesAvailable <= xBytesToStoreMessageLength ) + { + /* Wait for data to be available. */ + traceBLOCKING_ON_STREAM_BUFFER_RECEIVE( xStreamBuffer ); + ( void ) xTaskNotifyWait( ( uint32_t ) 0, ( uint32_t ) 0, NULL, xTicksToWait ); + pxStreamBuffer->xTaskWaitingToReceive = NULL; + + /* Recheck the data available after blocking. */ + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + } + + /* Whether receiving a discrete message (where xBytesToStoreMessageLength + holds the number of bytes used to store the message length) or a stream of + bytes (where xBytesToStoreMessageLength is zero), the number of bytes + available must be greater than xBytesToStoreMessageLength to be able to + read bytes from the buffer. */ + if( xBytesAvailable > xBytesToStoreMessageLength ) + { + xReceivedLength = prvReadMessageFromBuffer( pxStreamBuffer, pvRxData, xBufferLengthBytes, xBytesAvailable, xBytesToStoreMessageLength ); + + /* Was a task waiting for space in the buffer? */ + if( xReceivedLength != ( size_t ) 0 ) + { + traceSTREAM_BUFFER_RECEIVE( xStreamBuffer, xReceivedLength ); + sbRECEIVE_COMPLETED( pxStreamBuffer ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + traceSTREAM_BUFFER_RECEIVE_FAILED( xStreamBuffer ); + mtCOVERAGE_TEST_MARKER(); + } + + return xReceivedLength; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferNextMessageLengthBytes( StreamBufferHandle_t xStreamBuffer ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReturn, xBytesAvailable, xOriginalTail; +configMESSAGE_BUFFER_LENGTH_TYPE xTempReturn; + + configASSERT( pxStreamBuffer ); + + /* Ensure the stream buffer is being used as a message buffer. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + if( xBytesAvailable > sbBYTES_TO_STORE_MESSAGE_LENGTH ) + { + /* The number of bytes available is greater than the number of bytes + required to hold the length of the next message, so another message + is available. Return its length without removing the length bytes + from the buffer. A copy of the tail is stored so the buffer can be + returned to its prior state as the message is not actually being + removed from the buffer. */ + xOriginalTail = pxStreamBuffer->xTail; + ( void ) prvReadBytesFromBuffer( pxStreamBuffer, ( uint8_t * ) &xTempReturn, sbBYTES_TO_STORE_MESSAGE_LENGTH, xBytesAvailable ); + xReturn = ( size_t ) xTempReturn; + pxStreamBuffer->xTail = xOriginalTail; + } + else + { + /* The minimum amount of bytes in a message buffer is + ( sbBYTES_TO_STORE_MESSAGE_LENGTH + 1 ), so if xBytesAvailable is + less than sbBYTES_TO_STORE_MESSAGE_LENGTH the only other valid + value is 0. */ + configASSERT( xBytesAvailable == 0 ); + xReturn = 0; + } + } + else + { + xReturn = 0; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferReceiveFromISR( StreamBufferHandle_t xStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + BaseType_t * const pxHigherPriorityTaskWoken ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReceivedLength = 0, xBytesAvailable, xBytesToStoreMessageLength; + + configASSERT( pvRxData ); + configASSERT( pxStreamBuffer ); + + /* This receive function is used by both message buffers, which store + discrete messages, and stream buffers, which store a continuous stream of + bytes. Discrete messages include an additional + sbBYTES_TO_STORE_MESSAGE_LENGTH bytes that hold the length of the + message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xBytesToStoreMessageLength = sbBYTES_TO_STORE_MESSAGE_LENGTH; + } + else + { + xBytesToStoreMessageLength = 0; + } + + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + + /* Whether receiving a discrete message (where xBytesToStoreMessageLength + holds the number of bytes used to store the message length) or a stream of + bytes (where xBytesToStoreMessageLength is zero), the number of bytes + available must be greater than xBytesToStoreMessageLength to be able to + read bytes from the buffer. */ + if( xBytesAvailable > xBytesToStoreMessageLength ) + { + xReceivedLength = prvReadMessageFromBuffer( pxStreamBuffer, pvRxData, xBufferLengthBytes, xBytesAvailable, xBytesToStoreMessageLength ); + + /* Was a task waiting for space in the buffer? */ + if( xReceivedLength != ( size_t ) 0 ) + { + sbRECEIVE_COMPLETED_FROM_ISR( pxStreamBuffer, pxHigherPriorityTaskWoken ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceSTREAM_BUFFER_RECEIVE_FROM_ISR( xStreamBuffer, xReceivedLength ); + + return xReceivedLength; +} +/*-----------------------------------------------------------*/ + +static size_t prvReadMessageFromBuffer( StreamBuffer_t *pxStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + size_t xBytesAvailable, + size_t xBytesToStoreMessageLength ) +{ +size_t xOriginalTail, xReceivedLength, xNextMessageLength; +configMESSAGE_BUFFER_LENGTH_TYPE xTempNextMessageLength; + + if( xBytesToStoreMessageLength != ( size_t ) 0 ) + { + /* A discrete message is being received. First receive the length + of the message. A copy of the tail is stored so the buffer can be + returned to its prior state if the length of the message is too + large for the provided buffer. */ + xOriginalTail = pxStreamBuffer->xTail; + ( void ) prvReadBytesFromBuffer( pxStreamBuffer, ( uint8_t * ) &xTempNextMessageLength, xBytesToStoreMessageLength, xBytesAvailable ); + xNextMessageLength = ( size_t ) xTempNextMessageLength; + + /* Reduce the number of bytes available by the number of bytes just + read out. */ + xBytesAvailable -= xBytesToStoreMessageLength; + + /* Check there is enough space in the buffer provided by the + user. */ + if( xNextMessageLength > xBufferLengthBytes ) + { + /* The user has provided insufficient space to read the message + so return the buffer to its previous state (so the length of + the message is in the buffer again). */ + pxStreamBuffer->xTail = xOriginalTail; + xNextMessageLength = 0; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* A stream of bytes is being received (as opposed to a discrete + message), so read as many bytes as possible. */ + xNextMessageLength = xBufferLengthBytes; + } + + /* Read the actual data. */ + xReceivedLength = prvReadBytesFromBuffer( pxStreamBuffer, ( uint8_t * ) pvRxData, xNextMessageLength, xBytesAvailable ); /*lint !e9079 Data storage area is implemented as uint8_t array for ease of sizing, indexing and alignment. */ + + return xReceivedLength; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer ) +{ +const StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn; +size_t xTail; + + configASSERT( pxStreamBuffer ); + + /* True if no bytes are available. */ + xTail = pxStreamBuffer->xTail; + if( pxStreamBuffer->xHead == xTail ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer ) +{ +BaseType_t xReturn; +size_t xBytesToStoreMessageLength; +const StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; + + configASSERT( pxStreamBuffer ); + + /* This generic version of the receive function is used by both message + buffers, which store discrete messages, and stream buffers, which store a + continuous stream of bytes. Discrete messages include an additional + sbBYTES_TO_STORE_MESSAGE_LENGTH bytes that hold the length of the message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xBytesToStoreMessageLength = sbBYTES_TO_STORE_MESSAGE_LENGTH; + } + else + { + xBytesToStoreMessageLength = 0; + } + + /* True if the available space equals zero. */ + if( xStreamBufferSpacesAvailable( xStreamBuffer ) <= xBytesToStoreMessageLength ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferSendCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; + + configASSERT( pxStreamBuffer ); + + uxSavedInterruptStatus = ( UBaseType_t ) portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( ( pxStreamBuffer )->xTaskWaitingToReceive != NULL ) + { + ( void ) xTaskNotifyFromISR( ( pxStreamBuffer )->xTaskWaitingToReceive, + ( uint32_t ) 0, + eNoAction, + pxHigherPriorityTaskWoken ); + ( pxStreamBuffer )->xTaskWaitingToReceive = NULL; + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferReceiveCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; + + configASSERT( pxStreamBuffer ); + + uxSavedInterruptStatus = ( UBaseType_t ) portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( ( pxStreamBuffer )->xTaskWaitingToSend != NULL ) + { + ( void ) xTaskNotifyFromISR( ( pxStreamBuffer )->xTaskWaitingToSend, + ( uint32_t ) 0, + eNoAction, + pxHigherPriorityTaskWoken ); + ( pxStreamBuffer )->xTaskWaitingToSend = NULL; + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static size_t prvWriteBytesToBuffer( StreamBuffer_t * const pxStreamBuffer, const uint8_t *pucData, size_t xCount ) +{ +size_t xNextHead, xFirstLength; + + configASSERT( xCount > ( size_t ) 0 ); + + xNextHead = pxStreamBuffer->xHead; + + /* Calculate the number of bytes that can be added in the first write - + which may be less than the total number of bytes that need to be added if + the buffer will wrap back to the beginning. */ + xFirstLength = configMIN( pxStreamBuffer->xLength - xNextHead, xCount ); + + /* Write as many bytes as can be written in the first write. */ + configASSERT( ( xNextHead + xFirstLength ) <= pxStreamBuffer->xLength ); + ( void ) memcpy( ( void* ) ( &( pxStreamBuffer->pucBuffer[ xNextHead ] ) ), ( const void * ) pucData, xFirstLength ); /*lint !e9087 memcpy() requires void *. */ + + /* If the number of bytes written was less than the number that could be + written in the first write... */ + if( xCount > xFirstLength ) + { + /* ...then write the remaining bytes to the start of the buffer. */ + configASSERT( ( xCount - xFirstLength ) <= pxStreamBuffer->xLength ); + ( void ) memcpy( ( void * ) pxStreamBuffer->pucBuffer, ( const void * ) &( pucData[ xFirstLength ] ), xCount - xFirstLength ); /*lint !e9087 memcpy() requires void *. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xNextHead += xCount; + if( xNextHead >= pxStreamBuffer->xLength ) + { + xNextHead -= pxStreamBuffer->xLength; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + pxStreamBuffer->xHead = xNextHead; + + return xCount; +} +/*-----------------------------------------------------------*/ + +static size_t prvReadBytesFromBuffer( StreamBuffer_t *pxStreamBuffer, uint8_t *pucData, size_t xMaxCount, size_t xBytesAvailable ) +{ +size_t xCount, xFirstLength, xNextTail; + + /* Use the minimum of the wanted bytes and the available bytes. */ + xCount = configMIN( xBytesAvailable, xMaxCount ); + + if( xCount > ( size_t ) 0 ) + { + xNextTail = pxStreamBuffer->xTail; + + /* Calculate the number of bytes that can be read - which may be + less than the number wanted if the data wraps around to the start of + the buffer. */ + xFirstLength = configMIN( pxStreamBuffer->xLength - xNextTail, xCount ); + + /* Obtain the number of bytes it is possible to obtain in the first + read. Asserts check bounds of read and write. */ + configASSERT( xFirstLength <= xMaxCount ); + configASSERT( ( xNextTail + xFirstLength ) <= pxStreamBuffer->xLength ); + ( void ) memcpy( ( void * ) pucData, ( const void * ) &( pxStreamBuffer->pucBuffer[ xNextTail ] ), xFirstLength ); /*lint !e9087 memcpy() requires void *. */ + + /* If the total number of wanted bytes is greater than the number + that could be read in the first read... */ + if( xCount > xFirstLength ) + { + /*...then read the remaining bytes from the start of the buffer. */ + configASSERT( xCount <= xMaxCount ); + ( void ) memcpy( ( void * ) &( pucData[ xFirstLength ] ), ( void * ) ( pxStreamBuffer->pucBuffer ), xCount - xFirstLength ); /*lint !e9087 memcpy() requires void *. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Move the tail pointer to effectively remove the data read from + the buffer. */ + xNextTail += xCount; + + if( xNextTail >= pxStreamBuffer->xLength ) + { + xNextTail -= pxStreamBuffer->xLength; + } + + pxStreamBuffer->xTail = xNextTail; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xCount; +} +/*-----------------------------------------------------------*/ + +static size_t prvBytesInBuffer( const StreamBuffer_t * const pxStreamBuffer ) +{ +/* Returns the distance between xTail and xHead. */ +size_t xCount; + + xCount = pxStreamBuffer->xLength + pxStreamBuffer->xHead; + xCount -= pxStreamBuffer->xTail; + if ( xCount >= pxStreamBuffer->xLength ) + { + xCount -= pxStreamBuffer->xLength; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xCount; +} +/*-----------------------------------------------------------*/ + +static void prvInitialiseNewStreamBuffer( StreamBuffer_t * const pxStreamBuffer, + uint8_t * const pucBuffer, + size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + uint8_t ucFlags ) +{ + /* Assert here is deliberately writing to the entire buffer to ensure it can + be written to without generating exceptions, and is setting the buffer to a + known value to assist in development/debugging. */ + #if( configASSERT_DEFINED == 1 ) + { + /* The value written just has to be identifiable when looking at the + memory. Don't use 0xA5 as that is the stack fill value and could + result in confusion as to what is actually being observed. */ + const BaseType_t xWriteValue = 0x55; + configASSERT( memset( pucBuffer, ( int ) xWriteValue, xBufferSizeBytes ) == pucBuffer ); + } /*lint !e529 !e438 xWriteValue is only used if configASSERT() is defined. */ + #endif + + ( void ) memset( ( void * ) pxStreamBuffer, 0x00, sizeof( StreamBuffer_t ) ); /*lint !e9087 memset() requires void *. */ + pxStreamBuffer->pucBuffer = pucBuffer; + pxStreamBuffer->xLength = xBufferSizeBytes; + pxStreamBuffer->xTriggerLevelBytes = xTriggerLevelBytes; + pxStreamBuffer->ucFlags = ucFlags; +} + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxStreamBufferGetStreamBufferNumber( StreamBufferHandle_t xStreamBuffer ) + { + return xStreamBuffer->uxStreamBufferNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vStreamBufferSetStreamBufferNumber( StreamBufferHandle_t xStreamBuffer, UBaseType_t uxStreamBufferNumber ) + { + xStreamBuffer->uxStreamBufferNumber = uxStreamBufferNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + uint8_t ucStreamBufferGetStreamBufferType( StreamBufferHandle_t xStreamBuffer ) + { + return ( xStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ); + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/tasks.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/tasks.c new file mode 100644 index 0000000..522521c --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/tasks.c @@ -0,0 +1,5310 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* Standard includes. */ +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* FreeRTOS includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "timers.h" +#include "stack_macros.h" + +/* Lint e9021, e961 and e750 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750 !e9021. */ + +/* Set configUSE_STATS_FORMATTING_FUNCTIONS to 2 to include the stats formatting +functions but without including stdio.h here. */ +#if ( configUSE_STATS_FORMATTING_FUNCTIONS == 1 ) + /* At the bottom of this file are two optional functions that can be used + to generate human readable text from the raw data generated by the + uxTaskGetSystemState() function. Note the formatting functions are provided + for convenience only, and are NOT considered part of the kernel. */ + #include +#endif /* configUSE_STATS_FORMATTING_FUNCTIONS == 1 ) */ + +#if( configUSE_PREEMPTION == 0 ) + /* If the cooperative scheduler is being used then a yield should not be + performed just because a higher priority task has been woken. */ + #define taskYIELD_IF_USING_PREEMPTION() +#else + #define taskYIELD_IF_USING_PREEMPTION() portYIELD_WITHIN_API() +#endif + +/* Values that can be assigned to the ucNotifyState member of the TCB. */ +#define taskNOT_WAITING_NOTIFICATION ( ( uint8_t ) 0 ) +#define taskWAITING_NOTIFICATION ( ( uint8_t ) 1 ) +#define taskNOTIFICATION_RECEIVED ( ( uint8_t ) 2 ) + +/* + * The value used to fill the stack of a task when the task is created. This + * is used purely for checking the high water mark for tasks. + */ +#define tskSTACK_FILL_BYTE ( 0xa5U ) + +/* Bits used to recored how a task's stack and TCB were allocated. */ +#define tskDYNAMICALLY_ALLOCATED_STACK_AND_TCB ( ( uint8_t ) 0 ) +#define tskSTATICALLY_ALLOCATED_STACK_ONLY ( ( uint8_t ) 1 ) +#define tskSTATICALLY_ALLOCATED_STACK_AND_TCB ( ( uint8_t ) 2 ) + +/* If any of the following are set then task stacks are filled with a known +value so the high water mark can be determined. If none of the following are +set then don't fill the stack so there is no unnecessary dependency on memset. */ +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) || ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) ) + #define tskSET_NEW_STACKS_TO_KNOWN_VALUE 1 +#else + #define tskSET_NEW_STACKS_TO_KNOWN_VALUE 0 +#endif + +/* + * Macros used by vListTask to indicate which state a task is in. + */ +#define tskRUNNING_CHAR ( 'X' ) +#define tskBLOCKED_CHAR ( 'B' ) +#define tskREADY_CHAR ( 'R' ) +#define tskDELETED_CHAR ( 'D' ) +#define tskSUSPENDED_CHAR ( 'S' ) + +/* + * Some kernel aware debuggers require the data the debugger needs access to be + * global, rather than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + +/* The name allocated to the Idle task. This can be overridden by defining +configIDLE_TASK_NAME in FreeRTOSConfig.h. */ +#ifndef configIDLE_TASK_NAME + #define configIDLE_TASK_NAME "IDLE" +#endif + +#if ( configUSE_PORT_OPTIMISED_TASK_SELECTION == 0 ) + + /* If configUSE_PORT_OPTIMISED_TASK_SELECTION is 0 then task selection is + performed in a generic way that is not optimised to any particular + microcontroller architecture. */ + + /* uxTopReadyPriority holds the priority of the highest priority ready + state task. */ + #define taskRECORD_READY_PRIORITY( uxPriority ) \ + { \ + if( ( uxPriority ) > uxTopReadyPriority ) \ + { \ + uxTopReadyPriority = ( uxPriority ); \ + } \ + } /* taskRECORD_READY_PRIORITY */ + + /*-----------------------------------------------------------*/ + + #define taskSELECT_HIGHEST_PRIORITY_TASK() \ + { \ + UBaseType_t uxTopPriority = uxTopReadyPriority; \ + \ + /* Find the highest priority queue that contains ready tasks. */ \ + while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopPriority ] ) ) ) \ + { \ + configASSERT( uxTopPriority ); \ + --uxTopPriority; \ + } \ + \ + /* listGET_OWNER_OF_NEXT_ENTRY indexes through the list, so the tasks of \ + the same priority get an equal share of the processor time. */ \ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopPriority ] ) ); \ + uxTopReadyPriority = uxTopPriority; \ + } /* taskSELECT_HIGHEST_PRIORITY_TASK */ + + /*-----------------------------------------------------------*/ + + /* Define away taskRESET_READY_PRIORITY() and portRESET_READY_PRIORITY() as + they are only required when a port optimised method of task selection is + being used. */ + #define taskRESET_READY_PRIORITY( uxPriority ) + #define portRESET_READY_PRIORITY( uxPriority, uxTopReadyPriority ) + +#else /* configUSE_PORT_OPTIMISED_TASK_SELECTION */ + + /* If configUSE_PORT_OPTIMISED_TASK_SELECTION is 1 then task selection is + performed in a way that is tailored to the particular microcontroller + architecture being used. */ + + /* A port optimised version is provided. Call the port defined macros. */ + #define taskRECORD_READY_PRIORITY( uxPriority ) portRECORD_READY_PRIORITY( uxPriority, uxTopReadyPriority ) + + /*-----------------------------------------------------------*/ + + #define taskSELECT_HIGHEST_PRIORITY_TASK() \ + { \ + UBaseType_t uxTopPriority; \ + \ + /* Find the highest priority list that contains ready tasks. */ \ + portGET_HIGHEST_PRIORITY( uxTopPriority, uxTopReadyPriority ); \ + configASSERT( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ uxTopPriority ] ) ) > 0 ); \ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopPriority ] ) ); \ + } /* taskSELECT_HIGHEST_PRIORITY_TASK() */ + + /*-----------------------------------------------------------*/ + + /* A port optimised version is provided, call it only if the TCB being reset + is being referenced from a ready list. If it is referenced from a delayed + or suspended list then it won't be in a ready list. */ + #define taskRESET_READY_PRIORITY( uxPriority ) \ + { \ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ ( uxPriority ) ] ) ) == ( UBaseType_t ) 0 ) \ + { \ + portRESET_READY_PRIORITY( ( uxPriority ), ( uxTopReadyPriority ) ); \ + } \ + } + +#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */ + +/*-----------------------------------------------------------*/ + +/* pxDelayedTaskList and pxOverflowDelayedTaskList are switched when the tick +count overflows. */ +#define taskSWITCH_DELAYED_LISTS() \ +{ \ + List_t *pxTemp; \ + \ + /* The delayed tasks list should be empty when the lists are switched. */ \ + configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); \ + \ + pxTemp = pxDelayedTaskList; \ + pxDelayedTaskList = pxOverflowDelayedTaskList; \ + pxOverflowDelayedTaskList = pxTemp; \ + xNumOfOverflows++; \ + prvResetNextTaskUnblockTime(); \ +} + +/*-----------------------------------------------------------*/ + +/* + * Place the task represented by pxTCB into the appropriate ready list for + * the task. It is inserted at the end of the list. + */ +#define prvAddTaskToReadyList( pxTCB ) \ + traceMOVED_TASK_TO_READY_STATE( pxTCB ); \ + taskRECORD_READY_PRIORITY( ( pxTCB )->uxPriority ); \ + vListInsertEnd( &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xStateListItem ) ); \ + tracePOST_MOVED_TASK_TO_READY_STATE( pxTCB ) +/*-----------------------------------------------------------*/ + +/* + * Several functions take an TaskHandle_t parameter that can optionally be NULL, + * where NULL is used to indicate that the handle of the currently executing + * task should be used in place of the parameter. This macro simply checks to + * see if the parameter is NULL and returns a pointer to the appropriate TCB. + */ +#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? pxCurrentTCB : ( pxHandle ) ) + +/* The item value of the event list item is normally used to hold the priority +of the task to which it belongs (coded to allow it to be held in reverse +priority order). However, it is occasionally borrowed for other purposes. It +is important its value is not updated due to a task priority change while it is +being used for another purpose. The following bit definition is used to inform +the scheduler that the value should not be changed - in which case it is the +responsibility of whichever module is using the value to ensure it gets set back +to its original value when it is released. */ +#if( configUSE_16_BIT_TICKS == 1 ) + #define taskEVENT_LIST_ITEM_VALUE_IN_USE 0x8000U +#else + #define taskEVENT_LIST_ITEM_VALUE_IN_USE 0x80000000UL +#endif + +/* + * Task control block. A task control block (TCB) is allocated for each task, + * and stores task state information, including a pointer to the task's context + * (the task's run time environment, including register values) + */ +typedef struct tskTaskControlBlock /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +{ + volatile StackType_t *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE TCB STRUCT. */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE TCB STRUCT. */ + #endif + + ListItem_t xStateListItem; /*< The list that the state list item of a task is reference from denotes the state of that task (Ready, Blocked, Suspended ). */ + ListItem_t xEventListItem; /*< Used to reference a task from an event list. */ + UBaseType_t uxPriority; /*< The priority of the task. 0 is the lowest priority. */ + StackType_t *pxStack; /*< Points to the start of the stack. */ + char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + + #if ( ( portSTACK_GROWTH > 0 ) || ( configRECORD_STACK_HIGH_ADDRESS == 1 ) ) + StackType_t *pxEndOfStack; /*< Points to the highest valid address for the stack. */ + #endif + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + UBaseType_t uxCriticalNesting; /*< Holds the critical section nesting depth for ports that do not maintain their own count in the port layer. */ + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxTCBNumber; /*< Stores a number that increments each time a TCB is created. It allows debuggers to determine when a task has been deleted and then recreated. */ + UBaseType_t uxTaskNumber; /*< Stores a number specifically for use by third party trace code. */ + #endif + + #if ( configUSE_MUTEXES == 1 ) + UBaseType_t uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ + UBaseType_t uxMutexesHeld; + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + TaskHookFunction_t pxTaskTag; + #endif + + #if( configNUM_THREAD_LOCAL_STORAGE_POINTERS > 0 ) + void *pvThreadLocalStoragePointers[ configNUM_THREAD_LOCAL_STORAGE_POINTERS ]; + #endif + + #if( configGENERATE_RUN_TIME_STATS == 1 ) + uint32_t ulRunTimeCounter; /*< Stores the amount of time the task has spent in the Running state. */ + #endif + + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + /* Allocate a Newlib reent structure that is specific to this task. + Note Newlib support has been included by popular demand, but is not + used by the FreeRTOS maintainers themselves. FreeRTOS is not + responsible for resulting newlib operation. User must be familiar with + newlib and must provide system-wide implementations of the necessary + stubs. Be warned that (at the time of writing) the current newlib design + implements a system-wide malloc() that must be provided with locks. + + See the third party link http://www.nadler.com/embedded/newlibAndFreeRTOS.html + for additional information. */ + struct _reent xNewLib_reent; + #endif + + #if( configUSE_TASK_NOTIFICATIONS == 1 ) + volatile uint32_t ulNotifiedValue; + volatile uint8_t ucNotifyState; + #endif + + /* See the comments in FreeRTOS.h with the definition of + tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE. */ + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) /*lint !e731 !e9029 Macro has been consolidated for readability reasons. */ + uint8_t ucStaticallyAllocated; /*< Set to pdTRUE if the task is a statically allocated to ensure no attempt is made to free the memory. */ + #endif + + #if( INCLUDE_xTaskAbortDelay == 1 ) + uint8_t ucDelayAborted; + #endif + + #if( configUSE_POSIX_ERRNO == 1 ) + int iTaskErrno; + #endif + +} tskTCB; + +/* The old tskTCB name is maintained above then typedefed to the new TCB_t name +below to enable the use of older kernel aware debuggers. */ +typedef tskTCB TCB_t; + +/*lint -save -e956 A manual analysis and inspection has been used to determine +which static variables must be declared volatile. */ +PRIVILEGED_DATA TCB_t * volatile pxCurrentTCB = NULL; + +/* Lists for ready and blocked tasks. -------------------- +xDelayedTaskList1 and xDelayedTaskList2 could be move to function scople but +doing so breaks some kernel aware debuggers and debuggers that rely on removing +the static qualifier. */ +PRIVILEGED_DATA static List_t pxReadyTasksLists[ configMAX_PRIORITIES ];/*< Prioritised ready tasks. */ +PRIVILEGED_DATA static List_t xDelayedTaskList1; /*< Delayed tasks. */ +PRIVILEGED_DATA static List_t xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ +PRIVILEGED_DATA static List_t * volatile pxDelayedTaskList; /*< Points to the delayed task list currently being used. */ +PRIVILEGED_DATA static List_t * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ +PRIVILEGED_DATA static List_t xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready list when the scheduler is resumed. */ + +#if( INCLUDE_vTaskDelete == 1 ) + + PRIVILEGED_DATA static List_t xTasksWaitingTermination; /*< Tasks that have been deleted - but their memory not yet freed. */ + PRIVILEGED_DATA static volatile UBaseType_t uxDeletedTasksWaitingCleanUp = ( UBaseType_t ) 0U; + +#endif + +#if ( INCLUDE_vTaskSuspend == 1 ) + + PRIVILEGED_DATA static List_t xSuspendedTaskList; /*< Tasks that are currently suspended. */ + +#endif + +/* Global POSIX errno. Its value is changed upon context switching to match +the errno of the currently running task. */ +#if ( configUSE_POSIX_ERRNO == 1 ) + int FreeRTOS_errno = 0; +#endif + +/* Other file private variables. --------------------------------*/ +PRIVILEGED_DATA static volatile UBaseType_t uxCurrentNumberOfTasks = ( UBaseType_t ) 0U; +PRIVILEGED_DATA static volatile TickType_t xTickCount = ( TickType_t ) configINITIAL_TICK_COUNT; +PRIVILEGED_DATA static volatile UBaseType_t uxTopReadyPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile BaseType_t xSchedulerRunning = pdFALSE; +PRIVILEGED_DATA static volatile TickType_t xPendedTicks = ( TickType_t ) 0U; +PRIVILEGED_DATA static volatile BaseType_t xYieldPending = pdFALSE; +PRIVILEGED_DATA static volatile BaseType_t xNumOfOverflows = ( BaseType_t ) 0; +PRIVILEGED_DATA static UBaseType_t uxTaskNumber = ( UBaseType_t ) 0U; +PRIVILEGED_DATA static volatile TickType_t xNextTaskUnblockTime = ( TickType_t ) 0U; /* Initialised to portMAX_DELAY before the scheduler starts. */ +PRIVILEGED_DATA static TaskHandle_t xIdleTaskHandle = NULL; /*< Holds the handle of the idle task. The idle task is created automatically when the scheduler is started. */ + +/* Context switches are held pending while the scheduler is suspended. Also, +interrupts must not manipulate the xStateListItem of a TCB, or any of the +lists the xStateListItem can be referenced from, if the scheduler is suspended. +If an interrupt needs to unblock a task while the scheduler is suspended then it +moves the task's event list item into the xPendingReadyList, ready for the +kernel to move the task from the pending ready list into the real ready list +when the scheduler is unsuspended. The pending ready list itself can only be +accessed from a critical section. */ +PRIVILEGED_DATA static volatile UBaseType_t uxSchedulerSuspended = ( UBaseType_t ) pdFALSE; + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + /* Do not move these variables to function scope as doing so prevents the + code working with debuggers that need to remove the static qualifier. */ + PRIVILEGED_DATA static uint32_t ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ + PRIVILEGED_DATA static uint32_t ulTotalRunTime = 0UL; /*< Holds the total amount of execution time as defined by the run time counter clock. */ + +#endif + +/*lint -restore */ + +/*-----------------------------------------------------------*/ + +/* Callback function prototypes. --------------------------*/ +#if( configCHECK_FOR_STACK_OVERFLOW > 0 ) + + extern void vApplicationStackOverflowHook( TaskHandle_t xTask, char *pcTaskName ); + +#endif + +#if( configUSE_TICK_HOOK > 0 ) + + extern void vApplicationTickHook( void ); /*lint !e526 Symbol not defined as it is an application callback. */ + +#endif + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + extern void vApplicationGetIdleTaskMemory( StaticTask_t **ppxIdleTaskTCBBuffer, StackType_t **ppxIdleTaskStackBuffer, uint32_t *pulIdleTaskStackSize ); /*lint !e526 Symbol not defined as it is an application callback. */ + +#endif + +/* File private functions. --------------------------------*/ + +/** + * Utility task that simply returns pdTRUE if the task referenced by xTask is + * currently in the Suspended state, or pdFALSE if the task referenced by xTask + * is in any other state. + */ +#if ( INCLUDE_vTaskSuspend == 1 ) + + static BaseType_t prvTaskIsTaskSuspended( const TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +#endif /* INCLUDE_vTaskSuspend */ + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first task. + */ +static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; + +/* + * The idle task, which as all tasks is implemented as a never ending loop. + * The idle task is automatically created and added to the ready lists upon + * creation of the first user task. + * + * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); + +/* + * Utility to free all memory allocated by the scheduler to hold a TCB, + * including the stack pointed to by the TCB. + * + * This does not free memory allocated by the task itself (i.e. memory + * allocated by calls to pvPortMalloc from within the tasks application code). + */ +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( TCB_t *pxTCB ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Used only by the idle task. This checks to see if anything has been placed + * in the list of tasks waiting to be deleted. If so the task is cleaned up + * and its TCB deleted. + */ +static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; + +/* + * The currently executing task is entering the Blocked state. Add the task to + * either the current or the overflow delayed task list. + */ +static void prvAddCurrentTaskToDelayedList( TickType_t xTicksToWait, const BaseType_t xCanBlockIndefinitely ) PRIVILEGED_FUNCTION; + +/* + * Fills an TaskStatus_t structure with information on each task that is + * referenced from the pxList list (which may be a ready list, a delayed list, + * a suspended list, etc.). + * + * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM + * NORMAL APPLICATION CODE. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + static UBaseType_t prvListTasksWithinSingleList( TaskStatus_t *pxTaskStatusArray, List_t *pxList, eTaskState eState ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Searches pxList for a task with name pcNameToQuery - returning a handle to + * the task if it is found, or NULL if the task is not found. + */ +#if ( INCLUDE_xTaskGetHandle == 1 ) + + static TCB_t *prvSearchForNameWithinSingleList( List_t *pxList, const char pcNameToQuery[] ) PRIVILEGED_FUNCTION; + +#endif + +/* + * When a task is created, the stack of the task is filled with a known value. + * This function determines the 'high water mark' of the task stack by + * determining how much of the stack remains at the original preset value. + */ +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) ) + + static configSTACK_DEPTH_TYPE prvTaskCheckFreeStackSpace( const uint8_t * pucStackByte ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Return the amount of time, in ticks, that will pass before the kernel will + * next move a task from the Blocked state to the Running state. + * + * This conditional compilation should use inequality to 0, not equality to 1. + * This is to ensure portSUPPRESS_TICKS_AND_SLEEP() can be called when user + * defined low power mode implementations require configUSE_TICKLESS_IDLE to be + * set to a value other than 1. + */ +#if ( configUSE_TICKLESS_IDLE != 0 ) + + static TickType_t prvGetExpectedIdleTime( void ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Set xNextTaskUnblockTime to the time at which the next Blocked state task + * will exit the Blocked state. + */ +static void prvResetNextTaskUnblockTime( void ); + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) ) + + /* + * Helper function used to pad task names with spaces when printing out + * human readable tables of task information. + */ + static char *prvWriteNameToBuffer( char *pcBuffer, const char *pcTaskName ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Called after a Task_t structure has been allocated either statically or + * dynamically to fill in the structure's members. + */ +static void prvInitialiseNewTask( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const uint32_t ulStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t * const pxCreatedTask, + TCB_t *pxNewTCB, + const MemoryRegion_t * const xRegions ) PRIVILEGED_FUNCTION; + +/* + * Called after a new task has been created and initialised to place the task + * under the control of the scheduler. + */ +static void prvAddNewTaskToReadyList( TCB_t *pxNewTCB ) PRIVILEGED_FUNCTION; + +/* + * freertos_tasks_c_additions_init() should only be called if the user definable + * macro FREERTOS_TASKS_C_ADDITIONS_INIT() is defined, as that is the only macro + * called by the function. + */ +#ifdef FREERTOS_TASKS_C_ADDITIONS_INIT + + static void freertos_tasks_c_additions_init( void ) PRIVILEGED_FUNCTION; + +#endif + +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + TaskHandle_t xTaskCreateStatic( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const uint32_t ulStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + StackType_t * const puxStackBuffer, + StaticTask_t * const pxTaskBuffer ) + { + TCB_t *pxNewTCB; + TaskHandle_t xReturn; + + configASSERT( puxStackBuffer != NULL ); + configASSERT( pxTaskBuffer != NULL ); + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticTask_t equals the size of the real task + structure. */ + volatile size_t xSize = sizeof( StaticTask_t ); + configASSERT( xSize == sizeof( TCB_t ) ); + ( void ) xSize; /* Prevent lint warning when configASSERT() is not used. */ + } + #endif /* configASSERT_DEFINED */ + + + if( ( pxTaskBuffer != NULL ) && ( puxStackBuffer != NULL ) ) + { + /* The memory used for the task's TCB and stack are passed into this + function - use them. */ + pxNewTCB = ( TCB_t * ) pxTaskBuffer; /*lint !e740 !e9087 Unusual cast is ok as the structures are designed to have the same alignment, and the size is checked by an assert. */ + pxNewTCB->pxStack = ( StackType_t * ) puxStackBuffer; + + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) /*lint !e731 !e9029 Macro has been consolidated for readability reasons. */ + { + /* Tasks can be created statically or dynamically, so note this + task was created statically in case the task is later deleted. */ + pxNewTCB->ucStaticallyAllocated = tskSTATICALLY_ALLOCATED_STACK_AND_TCB; + } + #endif /* tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE */ + + prvInitialiseNewTask( pxTaskCode, pcName, ulStackDepth, pvParameters, uxPriority, &xReturn, pxNewTCB, NULL ); + prvAddNewTaskToReadyList( pxNewTCB ); + } + else + { + xReturn = NULL; + } + + return xReturn; + } + +#endif /* SUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + + BaseType_t xTaskCreateRestrictedStatic( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) + { + TCB_t *pxNewTCB; + BaseType_t xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + + configASSERT( pxTaskDefinition->puxStackBuffer != NULL ); + configASSERT( pxTaskDefinition->pxTaskBuffer != NULL ); + + if( ( pxTaskDefinition->puxStackBuffer != NULL ) && ( pxTaskDefinition->pxTaskBuffer != NULL ) ) + { + /* Allocate space for the TCB. Where the memory comes from depends + on the implementation of the port malloc function and whether or + not static allocation is being used. */ + pxNewTCB = ( TCB_t * ) pxTaskDefinition->pxTaskBuffer; + + /* Store the stack location in the TCB. */ + pxNewTCB->pxStack = pxTaskDefinition->puxStackBuffer; + + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) + { + /* Tasks can be created statically or dynamically, so note this + task was created statically in case the task is later deleted. */ + pxNewTCB->ucStaticallyAllocated = tskSTATICALLY_ALLOCATED_STACK_AND_TCB; + } + #endif /* tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE */ + + prvInitialiseNewTask( pxTaskDefinition->pvTaskCode, + pxTaskDefinition->pcName, + ( uint32_t ) pxTaskDefinition->usStackDepth, + pxTaskDefinition->pvParameters, + pxTaskDefinition->uxPriority, + pxCreatedTask, pxNewTCB, + pxTaskDefinition->xRegions ); + + prvAddNewTaskToReadyList( pxNewTCB ); + xReturn = pdPASS; + } + + return xReturn; + } + +#endif /* ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + BaseType_t xTaskCreateRestricted( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) + { + TCB_t *pxNewTCB; + BaseType_t xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + + configASSERT( pxTaskDefinition->puxStackBuffer ); + + if( pxTaskDefinition->puxStackBuffer != NULL ) + { + /* Allocate space for the TCB. Where the memory comes from depends + on the implementation of the port malloc function and whether or + not static allocation is being used. */ + pxNewTCB = ( TCB_t * ) pvPortMalloc( sizeof( TCB_t ) ); + + if( pxNewTCB != NULL ) + { + /* Store the stack location in the TCB. */ + pxNewTCB->pxStack = pxTaskDefinition->puxStackBuffer; + + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) + { + /* Tasks can be created statically or dynamically, so note + this task had a statically allocated stack in case it is + later deleted. The TCB was allocated dynamically. */ + pxNewTCB->ucStaticallyAllocated = tskSTATICALLY_ALLOCATED_STACK_ONLY; + } + #endif /* tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE */ + + prvInitialiseNewTask( pxTaskDefinition->pvTaskCode, + pxTaskDefinition->pcName, + ( uint32_t ) pxTaskDefinition->usStackDepth, + pxTaskDefinition->pvParameters, + pxTaskDefinition->uxPriority, + pxCreatedTask, pxNewTCB, + pxTaskDefinition->xRegions ); + + prvAddNewTaskToReadyList( pxNewTCB ); + xReturn = pdPASS; + } + } + + return xReturn; + } + +#endif /* portUSING_MPU_WRAPPERS */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + BaseType_t xTaskCreate( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const configSTACK_DEPTH_TYPE usStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t * const pxCreatedTask ) + { + TCB_t *pxNewTCB; + BaseType_t xReturn; + + /* If the stack grows down then allocate the stack then the TCB so the stack + does not grow into the TCB. Likewise if the stack grows up then allocate + the TCB then the stack. */ + #if( portSTACK_GROWTH > 0 ) + { + /* Allocate space for the TCB. Where the memory comes from depends on + the implementation of the port malloc function and whether or not static + allocation is being used. */ + pxNewTCB = ( TCB_t * ) pvPortMalloc( sizeof( TCB_t ) ); + + if( pxNewTCB != NULL ) + { + /* Allocate space for the stack used by the task being created. + The base of the stack memory stored in the TCB so the task can + be deleted later if required. */ + pxNewTCB->pxStack = ( StackType_t * ) pvPortMalloc( ( ( ( size_t ) usStackDepth ) * sizeof( StackType_t ) ) ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + if( pxNewTCB->pxStack == NULL ) + { + /* Could not allocate the stack. Delete the allocated TCB. */ + vPortFree( pxNewTCB ); + pxNewTCB = NULL; + } + } + } + #else /* portSTACK_GROWTH */ + { + StackType_t *pxStack; + + /* Allocate space for the stack used by the task being created. */ + pxStack = pvPortMalloc( ( ( ( size_t ) usStackDepth ) * sizeof( StackType_t ) ) ); /*lint !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack and this allocation is the stack. */ + + if( pxStack != NULL ) + { + /* Allocate space for the TCB. */ + pxNewTCB = ( TCB_t * ) pvPortMalloc( sizeof( TCB_t ) ); /*lint !e9087 !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack, and the first member of TCB_t is always a pointer to the task's stack. */ + + if( pxNewTCB != NULL ) + { + /* Store the stack location in the TCB. */ + pxNewTCB->pxStack = pxStack; + } + else + { + /* The stack cannot be used as the TCB was not created. Free + it again. */ + vPortFree( pxStack ); + } + } + else + { + pxNewTCB = NULL; + } + } + #endif /* portSTACK_GROWTH */ + + if( pxNewTCB != NULL ) + { + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) /*lint !e9029 !e731 Macro has been consolidated for readability reasons. */ + { + /* Tasks can be created statically or dynamically, so note this + task was created dynamically in case it is later deleted. */ + pxNewTCB->ucStaticallyAllocated = tskDYNAMICALLY_ALLOCATED_STACK_AND_TCB; + } + #endif /* tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE */ + + prvInitialiseNewTask( pxTaskCode, pcName, ( uint32_t ) usStackDepth, pvParameters, uxPriority, pxCreatedTask, pxNewTCB, NULL ); + prvAddNewTaskToReadyList( pxNewTCB ); + xReturn = pdPASS; + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + } + + return xReturn; + } + +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +static void prvInitialiseNewTask( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const uint32_t ulStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t * const pxCreatedTask, + TCB_t *pxNewTCB, + const MemoryRegion_t * const xRegions ) +{ +StackType_t *pxTopOfStack; +UBaseType_t x; + + #if( portUSING_MPU_WRAPPERS == 1 ) + /* Should the task be created in privileged mode? */ + BaseType_t xRunPrivileged; + if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) + { + xRunPrivileged = pdTRUE; + } + else + { + xRunPrivileged = pdFALSE; + } + uxPriority &= ~portPRIVILEGE_BIT; + #endif /* portUSING_MPU_WRAPPERS == 1 */ + + /* Avoid dependency on memset() if it is not required. */ + #if( tskSET_NEW_STACKS_TO_KNOWN_VALUE == 1 ) + { + /* Fill the stack with a known value to assist debugging. */ + ( void ) memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) ulStackDepth * sizeof( StackType_t ) ); + } + #endif /* tskSET_NEW_STACKS_TO_KNOWN_VALUE */ + + /* Calculate the top of stack address. This depends on whether the stack + grows from high memory to low (as per the 80x86) or vice versa. + portSTACK_GROWTH is used to make the result positive or negative as required + by the port. */ + #if( portSTACK_GROWTH < 0 ) + { + pxTopOfStack = &( pxNewTCB->pxStack[ ulStackDepth - ( uint32_t ) 1 ] ); + pxTopOfStack = ( StackType_t * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ~( ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) ) ); /*lint !e923 !e9033 !e9078 MISRA exception. Avoiding casts between pointers and integers is not practical. Size differences accounted for using portPOINTER_SIZE_TYPE type. Checked by assert(). */ + + /* Check the alignment of the calculated top of stack is correct. */ + configASSERT( ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack & ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + #if( configRECORD_STACK_HIGH_ADDRESS == 1 ) + { + /* Also record the stack's high address, which may assist + debugging. */ + pxNewTCB->pxEndOfStack = pxTopOfStack; + } + #endif /* configRECORD_STACK_HIGH_ADDRESS */ + } + #else /* portSTACK_GROWTH */ + { + pxTopOfStack = pxNewTCB->pxStack; + + /* Check the alignment of the stack buffer is correct. */ + configASSERT( ( ( ( portPOINTER_SIZE_TYPE ) pxNewTCB->pxStack & ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + /* The other extreme of the stack space is required if stack checking is + performed. */ + pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( ulStackDepth - ( uint32_t ) 1 ); + } + #endif /* portSTACK_GROWTH */ + + /* Store the task name in the TCB. */ + if( pcName != NULL ) + { + for( x = ( UBaseType_t ) 0; x < ( UBaseType_t ) configMAX_TASK_NAME_LEN; x++ ) + { + pxNewTCB->pcTaskName[ x ] = pcName[ x ]; + + /* Don't copy all configMAX_TASK_NAME_LEN if the string is shorter than + configMAX_TASK_NAME_LEN characters just in case the memory after the + string is not accessible (extremely unlikely). */ + if( pcName[ x ] == ( char ) 0x00 ) + { + break; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + /* Ensure the name string is terminated in the case that the string length + was greater or equal to configMAX_TASK_NAME_LEN. */ + pxNewTCB->pcTaskName[ configMAX_TASK_NAME_LEN - 1 ] = '\0'; + } + else + { + /* The task has not been given a name, so just ensure there is a NULL + terminator when it is read out. */ + pxNewTCB->pcTaskName[ 0 ] = 0x00; + } + + /* This is used as an array index so must ensure it's not too large. First + remove the privilege bit if one is present. */ + if( uxPriority >= ( UBaseType_t ) configMAX_PRIORITIES ) + { + uxPriority = ( UBaseType_t ) configMAX_PRIORITIES - ( UBaseType_t ) 1U; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + pxNewTCB->uxPriority = uxPriority; + #if ( configUSE_MUTEXES == 1 ) + { + pxNewTCB->uxBasePriority = uxPriority; + pxNewTCB->uxMutexesHeld = 0; + } + #endif /* configUSE_MUTEXES */ + + vListInitialiseItem( &( pxNewTCB->xStateListItem ) ); + vListInitialiseItem( &( pxNewTCB->xEventListItem ) ); + + /* Set the pxNewTCB as a link back from the ListItem_t. This is so we can get + back to the containing TCB from a generic item in a list. */ + listSET_LIST_ITEM_OWNER( &( pxNewTCB->xStateListItem ), pxNewTCB ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxNewTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + listSET_LIST_ITEM_OWNER( &( pxNewTCB->xEventListItem ), pxNewTCB ); + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + { + pxNewTCB->uxCriticalNesting = ( UBaseType_t ) 0U; + } + #endif /* portCRITICAL_NESTING_IN_TCB */ + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + { + pxNewTCB->pxTaskTag = NULL; + } + #endif /* configUSE_APPLICATION_TASK_TAG */ + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxNewTCB->ulRunTimeCounter = 0UL; + } + #endif /* configGENERATE_RUN_TIME_STATS */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + { + vPortStoreTaskMPUSettings( &( pxNewTCB->xMPUSettings ), xRegions, pxNewTCB->pxStack, ulStackDepth ); + } + #else + { + /* Avoid compiler warning about unreferenced parameter. */ + ( void ) xRegions; + } + #endif + + #if( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 ) + { + for( x = 0; x < ( UBaseType_t ) configNUM_THREAD_LOCAL_STORAGE_POINTERS; x++ ) + { + pxNewTCB->pvThreadLocalStoragePointers[ x ] = NULL; + } + } + #endif + + #if ( configUSE_TASK_NOTIFICATIONS == 1 ) + { + pxNewTCB->ulNotifiedValue = 0; + pxNewTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + } + #endif + + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + { + /* Initialise this task's Newlib reent structure. + See the third party link http://www.nadler.com/embedded/newlibAndFreeRTOS.html + for additional information. */ + _REENT_INIT_PTR( ( &( pxNewTCB->xNewLib_reent ) ) ); + } + #endif + + #if( INCLUDE_xTaskAbortDelay == 1 ) + { + pxNewTCB->ucDelayAborted = pdFALSE; + } + #endif + + /* Initialize the TCB stack to look as if the task was already running, + but had been interrupted by the scheduler. The return address is set + to the start of the task function. Once the stack has been initialised + the top of stack variable is updated. */ + #if( portUSING_MPU_WRAPPERS == 1 ) + { + /* If the port has capability to detect stack overflow, + pass the stack end address to the stack initialization + function as well. */ + #if( portHAS_STACK_OVERFLOW_CHECKING == 1 ) + { + #if( portSTACK_GROWTH < 0 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #else /* portSTACK_GROWTH */ + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxEndOfStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #endif /* portSTACK_GROWTH */ + } + #else /* portHAS_STACK_OVERFLOW_CHECKING */ + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #endif /* portHAS_STACK_OVERFLOW_CHECKING */ + } + #else /* portUSING_MPU_WRAPPERS */ + { + /* If the port has capability to detect stack overflow, + pass the stack end address to the stack initialization + function as well. */ + #if( portHAS_STACK_OVERFLOW_CHECKING == 1 ) + { + #if( portSTACK_GROWTH < 0 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxStack, pxTaskCode, pvParameters ); + } + #else /* portSTACK_GROWTH */ + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxEndOfStack, pxTaskCode, pvParameters ); + } + #endif /* portSTACK_GROWTH */ + } + #else /* portHAS_STACK_OVERFLOW_CHECKING */ + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); + } + #endif /* portHAS_STACK_OVERFLOW_CHECKING */ + } + #endif /* portUSING_MPU_WRAPPERS */ + + if( pxCreatedTask != NULL ) + { + /* Pass the handle out in an anonymous way. The handle can be used to + change the created task's priority, delete the created task, etc.*/ + *pxCreatedTask = ( TaskHandle_t ) pxNewTCB; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } +} +/*-----------------------------------------------------------*/ + +static void prvAddNewTaskToReadyList( TCB_t *pxNewTCB ) +{ + /* Ensure interrupts don't access the task lists while the lists are being + updated. */ + taskENTER_CRITICAL(); + { + uxCurrentNumberOfTasks++; + if( pxCurrentTCB == NULL ) + { + /* There are no other tasks, or all the other tasks are in + the suspended state - make this the current task. */ + pxCurrentTCB = pxNewTCB; + + if( uxCurrentNumberOfTasks == ( UBaseType_t ) 1 ) + { + /* This is the first task to be created so do the preliminary + initialisation required. We will not recover if this call + fails, but we will report the failure. */ + prvInitialiseTaskLists(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* If the scheduler is not already running, make this task the + current task if it is the highest priority task to be created + so far. */ + if( xSchedulerRunning == pdFALSE ) + { + if( pxCurrentTCB->uxPriority <= pxNewTCB->uxPriority ) + { + pxCurrentTCB = pxNewTCB; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + uxTaskNumber++; + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + /* Add a counter into the TCB for tracing only. */ + pxNewTCB->uxTCBNumber = uxTaskNumber; + } + #endif /* configUSE_TRACE_FACILITY */ + traceTASK_CREATE( pxNewTCB ); + + prvAddTaskToReadyList( pxNewTCB ); + + portSETUP_TCB( pxNewTCB ); + } + taskEXIT_CRITICAL(); + + if( xSchedulerRunning != pdFALSE ) + { + /* If the created task is of a higher priority than the current task + then it should run now. */ + if( pxCurrentTCB->uxPriority < pxNewTCB->uxPriority ) + { + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + void vTaskDelete( TaskHandle_t xTaskToDelete ) + { + TCB_t *pxTCB; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then it is the calling task that is + being deleted. */ + pxTCB = prvGetTCBFromHandle( xTaskToDelete ); + + /* Remove task from the ready/delayed list. */ + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + taskRESET_READY_PRIORITY( pxTCB->uxPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Is the task waiting on an event also? */ + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Increment the uxTaskNumber also so kernel aware debuggers can + detect that the task lists need re-generating. This is done before + portPRE_TASK_DELETE_HOOK() as in the Windows port that macro will + not return. */ + uxTaskNumber++; + + if( pxTCB == pxCurrentTCB ) + { + /* A task is deleting itself. This cannot complete within the + task itself, as a context switch to another task is required. + Place the task in the termination list. The idle task will + check the termination list and free up any memory allocated by + the scheduler for the TCB and stack of the deleted task. */ + vListInsertEnd( &xTasksWaitingTermination, &( pxTCB->xStateListItem ) ); + + /* Increment the ucTasksDeleted variable so the idle task knows + there is a task that has been deleted and that it should therefore + check the xTasksWaitingTermination list. */ + ++uxDeletedTasksWaitingCleanUp; + + /* Call the delete hook before portPRE_TASK_DELETE_HOOK() as + portPRE_TASK_DELETE_HOOK() does not return in the Win32 port. */ + traceTASK_DELETE( pxTCB ); + + /* The pre-delete hook is primarily for the Windows simulator, + in which Windows specific clean up operations are performed, + after which it is not possible to yield away from this task - + hence xYieldPending is used to latch that a context switch is + required. */ + portPRE_TASK_DELETE_HOOK( pxTCB, &xYieldPending ); + } + else + { + --uxCurrentNumberOfTasks; + traceTASK_DELETE( pxTCB ); + prvDeleteTCB( pxTCB ); + + /* Reset the next expected unblock time in case it referred to + the task that has just been deleted. */ + prvResetNextTaskUnblockTime(); + } + } + taskEXIT_CRITICAL(); + + /* Force a reschedule if it is the currently running task that has just + been deleted. */ + if( xSchedulerRunning != pdFALSE ) + { + if( pxTCB == pxCurrentTCB ) + { + configASSERT( uxSchedulerSuspended == 0 ); + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + +#endif /* INCLUDE_vTaskDelete */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelayUntil == 1 ) + + void vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, const TickType_t xTimeIncrement ) + { + TickType_t xTimeToWake; + BaseType_t xAlreadyYielded, xShouldDelay = pdFALSE; + + configASSERT( pxPreviousWakeTime ); + configASSERT( ( xTimeIncrement > 0U ) ); + configASSERT( uxSchedulerSuspended == 0 ); + + vTaskSuspendAll(); + { + /* Minor optimisation. The tick count cannot change in this + block. */ + const TickType_t xConstTickCount = xTickCount; + + /* Generate the tick time at which the task wants to wake. */ + xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; + + if( xConstTickCount < *pxPreviousWakeTime ) + { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xConstTickCount ) ) + { + xShouldDelay = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xConstTickCount ) ) + { + xShouldDelay = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + /* Update the wake time ready for the next call. */ + *pxPreviousWakeTime = xTimeToWake; + + if( xShouldDelay != pdFALSE ) + { + traceTASK_DELAY_UNTIL( xTimeToWake ); + + /* prvAddCurrentTaskToDelayedList() needs the block time, not + the time to wake, so subtract the current tick count. */ + prvAddCurrentTaskToDelayedList( xTimeToWake - xConstTickCount, pdFALSE ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + xAlreadyYielded = xTaskResumeAll(); + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* INCLUDE_vTaskDelayUntil */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelay == 1 ) + + void vTaskDelay( const TickType_t xTicksToDelay ) + { + BaseType_t xAlreadyYielded = pdFALSE; + + /* A delay time of zero just forces a reschedule. */ + if( xTicksToDelay > ( TickType_t ) 0U ) + { + configASSERT( uxSchedulerSuspended == 0 ); + vTaskSuspendAll(); + { + traceTASK_DELAY(); + + /* A task that is removed from the event list while the + scheduler is suspended will not get placed in the ready + list or removed from the blocked list until the scheduler + is resumed. + + This task cannot be in an event list as it is the currently + executing task. */ + prvAddCurrentTaskToDelayedList( xTicksToDelay, pdFALSE ); + } + xAlreadyYielded = xTaskResumeAll(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* INCLUDE_vTaskDelay */ +/*-----------------------------------------------------------*/ + +#if( ( INCLUDE_eTaskGetState == 1 ) || ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_xTaskAbortDelay == 1 ) ) + + eTaskState eTaskGetState( TaskHandle_t xTask ) + { + eTaskState eReturn; + List_t const * pxStateList, *pxDelayedList, *pxOverflowedDelayedList; + const TCB_t * const pxTCB = xTask; + + configASSERT( pxTCB ); + + if( pxTCB == pxCurrentTCB ) + { + /* The task calling this function is querying its own state. */ + eReturn = eRunning; + } + else + { + taskENTER_CRITICAL(); + { + pxStateList = listLIST_ITEM_CONTAINER( &( pxTCB->xStateListItem ) ); + pxDelayedList = pxDelayedTaskList; + pxOverflowedDelayedList = pxOverflowDelayedTaskList; + } + taskEXIT_CRITICAL(); + + if( ( pxStateList == pxDelayedList ) || ( pxStateList == pxOverflowedDelayedList ) ) + { + /* The task being queried is referenced from one of the Blocked + lists. */ + eReturn = eBlocked; + } + + #if ( INCLUDE_vTaskSuspend == 1 ) + else if( pxStateList == &xSuspendedTaskList ) + { + /* The task being queried is referenced from the suspended + list. Is it genuinely suspended or is it blocked + indefinitely? */ + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL ) + { + #if( configUSE_TASK_NOTIFICATIONS == 1 ) + { + /* The task does not appear on the event list item of + and of the RTOS objects, but could still be in the + blocked state if it is waiting on its notification + rather than waiting on an object. */ + if( pxTCB->ucNotifyState == taskWAITING_NOTIFICATION ) + { + eReturn = eBlocked; + } + else + { + eReturn = eSuspended; + } + } + #else + { + eReturn = eSuspended; + } + #endif + } + else + { + eReturn = eBlocked; + } + } + #endif + + #if ( INCLUDE_vTaskDelete == 1 ) + else if( ( pxStateList == &xTasksWaitingTermination ) || ( pxStateList == NULL ) ) + { + /* The task being queried is referenced from the deleted + tasks list, or it is not referenced from any lists at + all. */ + eReturn = eDeleted; + } + #endif + + else /*lint !e525 Negative indentation is intended to make use of pre-processor clearer. */ + { + /* If the task is not in any other state, it must be in the + Ready (including pending ready) state. */ + eReturn = eReady; + } + } + + return eReturn; + } /*lint !e818 xTask cannot be a pointer to const because it is a typedef. */ + +#endif /* INCLUDE_eTaskGetState */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + UBaseType_t uxTaskPriorityGet( const TaskHandle_t xTask ) + { + TCB_t const *pxTCB; + UBaseType_t uxReturn; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then it is the priority of the task + that called uxTaskPriorityGet() that is being queried. */ + pxTCB = prvGetTCBFromHandle( xTask ); + uxReturn = pxTCB->uxPriority; + } + taskEXIT_CRITICAL(); + + return uxReturn; + } + +#endif /* INCLUDE_uxTaskPriorityGet */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + UBaseType_t uxTaskPriorityGetFromISR( const TaskHandle_t xTask ) + { + TCB_t const *pxTCB; + UBaseType_t uxReturn, uxSavedInterruptState; + + /* RTOS ports that support interrupt nesting have the concept of a + maximum system call (or maximum API call) interrupt priority. + Interrupts that are above the maximum system call priority are keep + permanently enabled, even when the RTOS kernel is in a critical section, + but cannot make any calls to FreeRTOS API functions. If configASSERT() + is defined in FreeRTOSConfig.h then + portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has + been assigned a priority above the configured maximum system call + priority. Only FreeRTOS functions that end in FromISR can be called + from interrupts that have been assigned a priority at or (logically) + below the maximum system call interrupt priority. FreeRTOS maintains a + separate interrupt safe API to ensure interrupt entry is as fast and as + simple as possible. More information (albeit Cortex-M specific) is + provided on the following link: + https://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptState = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* If null is passed in here then it is the priority of the calling + task that is being queried. */ + pxTCB = prvGetTCBFromHandle( xTask ); + uxReturn = pxTCB->uxPriority; + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptState ); + + return uxReturn; + } + +#endif /* INCLUDE_uxTaskPriorityGet */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskPrioritySet == 1 ) + + void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority ) + { + TCB_t *pxTCB; + UBaseType_t uxCurrentBasePriority, uxPriorityUsedOnEntry; + BaseType_t xYieldRequired = pdFALSE; + + configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); + + /* Ensure the new priority is valid. */ + if( uxNewPriority >= ( UBaseType_t ) configMAX_PRIORITIES ) + { + uxNewPriority = ( UBaseType_t ) configMAX_PRIORITIES - ( UBaseType_t ) 1U; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + taskENTER_CRITICAL(); + { + /* If null is passed in here then it is the priority of the calling + task that is being changed. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + traceTASK_PRIORITY_SET( pxTCB, uxNewPriority ); + + #if ( configUSE_MUTEXES == 1 ) + { + uxCurrentBasePriority = pxTCB->uxBasePriority; + } + #else + { + uxCurrentBasePriority = pxTCB->uxPriority; + } + #endif + + if( uxCurrentBasePriority != uxNewPriority ) + { + /* The priority change may have readied a task of higher + priority than the calling task. */ + if( uxNewPriority > uxCurrentBasePriority ) + { + if( pxTCB != pxCurrentTCB ) + { + /* The priority of a task other than the currently + running task is being raised. Is the priority being + raised above that of the running task? */ + if( uxNewPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* The priority of the running task is being raised, + but the running task must already be the highest + priority task able to run so no yield is required. */ + } + } + else if( pxTCB == pxCurrentTCB ) + { + /* Setting the priority of the running task down means + there may now be another task of higher priority that + is ready to execute. */ + xYieldRequired = pdTRUE; + } + else + { + /* Setting the priority of any other task down does not + require a yield as the running task must be above the + new priority of the task being modified. */ + } + + /* Remember the ready list the task might be referenced from + before its uxPriority member is changed so the + taskRESET_READY_PRIORITY() macro can function correctly. */ + uxPriorityUsedOnEntry = pxTCB->uxPriority; + + #if ( configUSE_MUTEXES == 1 ) + { + /* Only change the priority being used if the task is not + currently using an inherited priority. */ + if( pxTCB->uxBasePriority == pxTCB->uxPriority ) + { + pxTCB->uxPriority = uxNewPriority; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The base priority gets set whatever. */ + pxTCB->uxBasePriority = uxNewPriority; + } + #else + { + pxTCB->uxPriority = uxNewPriority; + } + #endif + + /* Only reset the event list item value if the value is not + being used for anything else. */ + if( ( listGET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ) ) & taskEVENT_LIST_ITEM_VALUE_IN_USE ) == 0UL ) + { + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) uxNewPriority ) ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* If the task is in the blocked or suspended list we need do + nothing more than change its priority variable. However, if + the task is in a ready list it needs to be removed and placed + in the list appropriate to its new priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxPriorityUsedOnEntry ] ), &( pxTCB->xStateListItem ) ) != pdFALSE ) + { + /* The task is currently in its ready list - remove before + adding it to it's new ready list. As we are in a critical + section we can do this even if the scheduler is suspended. */ + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + /* It is known that the task is in its ready list so + there is no need to check again and the port level + reset macro can be called directly. */ + portRESET_READY_PRIORITY( uxPriorityUsedOnEntry, uxTopReadyPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + prvAddTaskToReadyList( pxTCB ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xYieldRequired != pdFALSE ) + { + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Remove compiler warning about unused variables when the port + optimised task selection is not being used. */ + ( void ) uxPriorityUsedOnEntry; + } + } + taskEXIT_CRITICAL(); + } + +#endif /* INCLUDE_vTaskPrioritySet */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskSuspend( TaskHandle_t xTaskToSuspend ) + { + TCB_t *pxTCB; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then it is the running task that is + being suspended. */ + pxTCB = prvGetTCBFromHandle( xTaskToSuspend ); + + traceTASK_SUSPEND( pxTCB ); + + /* Remove task from the ready/delayed list and place in the + suspended list. */ + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + taskRESET_READY_PRIORITY( pxTCB->uxPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Is the task waiting on an event also? */ + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + vListInsertEnd( &xSuspendedTaskList, &( pxTCB->xStateListItem ) ); + + #if( configUSE_TASK_NOTIFICATIONS == 1 ) + { + if( pxTCB->ucNotifyState == taskWAITING_NOTIFICATION ) + { + /* The task was blocked to wait for a notification, but is + now suspended, so no notification was received. */ + pxTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + } + } + #endif + } + taskEXIT_CRITICAL(); + + if( xSchedulerRunning != pdFALSE ) + { + /* Reset the next expected unblock time in case it referred to the + task that is now in the Suspended state. */ + taskENTER_CRITICAL(); + { + prvResetNextTaskUnblockTime(); + } + taskEXIT_CRITICAL(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( pxTCB == pxCurrentTCB ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* The current task has just been suspended. */ + configASSERT( uxSchedulerSuspended == 0 ); + portYIELD_WITHIN_API(); + } + else + { + /* The scheduler is not running, but the task that was pointed + to by pxCurrentTCB has just been suspended and pxCurrentTCB + must be adjusted to point to a different task. */ + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) /*lint !e931 Right has no side effect, just volatile. */ + { + /* No other tasks are ready, so set pxCurrentTCB back to + NULL so when the next task is created pxCurrentTCB will + be set to point to it no matter what its relative priority + is. */ + pxCurrentTCB = NULL; + } + else + { + vTaskSwitchContext(); + } + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* INCLUDE_vTaskSuspend */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + static BaseType_t prvTaskIsTaskSuspended( const TaskHandle_t xTask ) + { + BaseType_t xReturn = pdFALSE; + const TCB_t * const pxTCB = xTask; + + /* Accesses xPendingReadyList so must be called from a critical + section. */ + + /* It does not make sense to check if the calling task is suspended. */ + configASSERT( xTask ); + + /* Is the task being resumed actually in the suspended list? */ + if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xStateListItem ) ) != pdFALSE ) + { + /* Has the task already been resumed from within an ISR? */ + if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) == pdFALSE ) + { + /* Is it in the suspended list because it is in the Suspended + state, or because is is blocked with no timeout? */ + if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) != pdFALSE ) /*lint !e961. The cast is only redundant when NULL is used. */ + { + xReturn = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; + } /*lint !e818 xTask cannot be a pointer to const because it is a typedef. */ + +#endif /* INCLUDE_vTaskSuspend */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskResume( TaskHandle_t xTaskToResume ) + { + TCB_t * const pxTCB = xTaskToResume; + + /* It does not make sense to resume the calling task. */ + configASSERT( xTaskToResume ); + + /* The parameter cannot be NULL as it is impossible to resume the + currently executing task. */ + if( ( pxTCB != pxCurrentTCB ) && ( pxTCB != NULL ) ) + { + taskENTER_CRITICAL(); + { + if( prvTaskIsTaskSuspended( pxTCB ) != pdFALSE ) + { + traceTASK_RESUME( pxTCB ); + + /* The ready list can be accessed even if the scheduler is + suspended because this is inside a critical section. */ + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + + /* A higher priority task may have just been resumed. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* This yield may not cause the task just resumed to run, + but will leave the lists in the correct state for the + next yield. */ + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* INCLUDE_vTaskSuspend */ + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + BaseType_t xTaskResumeFromISR( TaskHandle_t xTaskToResume ) + { + BaseType_t xYieldRequired = pdFALSE; + TCB_t * const pxTCB = xTaskToResume; + UBaseType_t uxSavedInterruptStatus; + + configASSERT( xTaskToResume ); + + /* RTOS ports that support interrupt nesting have the concept of a + maximum system call (or maximum API call) interrupt priority. + Interrupts that are above the maximum system call priority are keep + permanently enabled, even when the RTOS kernel is in a critical section, + but cannot make any calls to FreeRTOS API functions. If configASSERT() + is defined in FreeRTOSConfig.h then + portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has + been assigned a priority above the configured maximum system call + priority. Only FreeRTOS functions that end in FromISR can be called + from interrupts that have been assigned a priority at or (logically) + below the maximum system call interrupt priority. FreeRTOS maintains a + separate interrupt safe API to ensure interrupt entry is as fast and as + simple as possible. More information (albeit Cortex-M specific) is + provided on the following link: + https://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( prvTaskIsTaskSuspended( pxTCB ) != pdFALSE ) + { + traceTASK_RESUME_FROM_ISR( pxTCB ); + + /* Check the ready lists can be accessed. */ + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + /* Ready lists can be accessed so move the task from the + suspended list to the ready list directly. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + } + else + { + /* The delayed or ready lists cannot be accessed so the task + is held in the pending ready list until the scheduler is + unsuspended. */ + vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xYieldRequired; + } + +#endif /* ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) */ +/*-----------------------------------------------------------*/ + +void vTaskStartScheduler( void ) +{ +BaseType_t xReturn; + + /* Add the idle task at the lowest priority. */ + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + StaticTask_t *pxIdleTaskTCBBuffer = NULL; + StackType_t *pxIdleTaskStackBuffer = NULL; + uint32_t ulIdleTaskStackSize; + + /* The Idle task is created using user provided RAM - obtain the + address of the RAM then create the idle task. */ + vApplicationGetIdleTaskMemory( &pxIdleTaskTCBBuffer, &pxIdleTaskStackBuffer, &ulIdleTaskStackSize ); + xIdleTaskHandle = xTaskCreateStatic( prvIdleTask, + configIDLE_TASK_NAME, + ulIdleTaskStackSize, + ( void * ) NULL, /*lint !e961. The cast is not redundant for all compilers. */ + portPRIVILEGE_BIT, /* In effect ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), but tskIDLE_PRIORITY is zero. */ + pxIdleTaskStackBuffer, + pxIdleTaskTCBBuffer ); /*lint !e961 MISRA exception, justified as it is not a redundant explicit cast to all supported compilers. */ + + if( xIdleTaskHandle != NULL ) + { + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + } + #else + { + /* The Idle task is being created using dynamically allocated RAM. */ + xReturn = xTaskCreate( prvIdleTask, + configIDLE_TASK_NAME, + configMINIMAL_STACK_SIZE, + ( void * ) NULL, + portPRIVILEGE_BIT, /* In effect ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), but tskIDLE_PRIORITY is zero. */ + &xIdleTaskHandle ); /*lint !e961 MISRA exception, justified as it is not a redundant explicit cast to all supported compilers. */ + } + #endif /* configSUPPORT_STATIC_ALLOCATION */ + + #if ( configUSE_TIMERS == 1 ) + { + if( xReturn == pdPASS ) + { + xReturn = xTimerCreateTimerTask(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_TIMERS */ + + if( xReturn == pdPASS ) + { + /* freertos_tasks_c_additions_init() should only be called if the user + definable macro FREERTOS_TASKS_C_ADDITIONS_INIT() is defined, as that is + the only macro called by the function. */ + #ifdef FREERTOS_TASKS_C_ADDITIONS_INIT + { + freertos_tasks_c_additions_init(); + } + #endif + + /* Interrupts are turned off here, to ensure a tick does not occur + before or during the call to xPortStartScheduler(). The stacks of + the created tasks contain a status word with interrupts switched on + so interrupts will automatically get re-enabled when the first task + starts to run. */ + portDISABLE_INTERRUPTS(); + + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + { + /* Switch Newlib's _impure_ptr variable to point to the _reent + structure specific to the task that will run first. + See the third party link http://www.nadler.com/embedded/newlibAndFreeRTOS.html + for additional information. */ + _impure_ptr = &( pxCurrentTCB->xNewLib_reent ); + } + #endif /* configUSE_NEWLIB_REENTRANT */ + + xNextTaskUnblockTime = portMAX_DELAY; + xSchedulerRunning = pdTRUE; + xTickCount = ( TickType_t ) configINITIAL_TICK_COUNT; + + /* If configGENERATE_RUN_TIME_STATS is defined then the following + macro must be defined to configure the timer/counter used to generate + the run time counter time base. NOTE: If configGENERATE_RUN_TIME_STATS + is set to 0 and the following line fails to build then ensure you do not + have portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() defined in your + FreeRTOSConfig.h file. */ + portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); + + traceTASK_SWITCHED_IN(); + + /* Setting up the timer tick is hardware specific and thus in the + portable interface. */ + if( xPortStartScheduler() != pdFALSE ) + { + /* Should not reach here as if the scheduler is running the + function will not return. */ + } + else + { + /* Should only reach here if a task calls xTaskEndScheduler(). */ + } + } + else + { + /* This line will only be reached if the kernel could not be started, + because there was not enough FreeRTOS heap to create the idle task + or the timer task. */ + configASSERT( xReturn != errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ); + } + + /* Prevent compiler warnings if INCLUDE_xTaskGetIdleTaskHandle is set to 0, + meaning xIdleTaskHandle is not used anywhere else. */ + ( void ) xIdleTaskHandle; +} +/*-----------------------------------------------------------*/ + +void vTaskEndScheduler( void ) +{ + /* Stop the scheduler interrupts and call the portable scheduler end + routine so the original ISRs can be restored if necessary. The port + layer must ensure interrupts enable bit is left in the correct state. */ + portDISABLE_INTERRUPTS(); + xSchedulerRunning = pdFALSE; + vPortEndScheduler(); +} +/*----------------------------------------------------------*/ + +void vTaskSuspendAll( void ) +{ + /* A critical section is not required as the variable is of type + BaseType_t. Please read Richard Barry's reply in the following link to a + post in the FreeRTOS support forum before reporting this as a bug! - + http://goo.gl/wu4acr */ + + /* portSOFRWARE_BARRIER() is only implemented for emulated/simulated ports that + do not otherwise exhibit real time behaviour. */ + portSOFTWARE_BARRIER(); + + /* The scheduler is suspended if uxSchedulerSuspended is non-zero. An increment + is used to allow calls to vTaskSuspendAll() to nest. */ + ++uxSchedulerSuspended; + + /* Enforces ordering for ports and optimised compilers that may otherwise place + the above increment elsewhere. */ + portMEMORY_BARRIER(); +} +/*----------------------------------------------------------*/ + +#if ( configUSE_TICKLESS_IDLE != 0 ) + + static TickType_t prvGetExpectedIdleTime( void ) + { + TickType_t xReturn; + UBaseType_t uxHigherPriorityReadyTasks = pdFALSE; + + /* uxHigherPriorityReadyTasks takes care of the case where + configUSE_PREEMPTION is 0, so there may be tasks above the idle priority + task that are in the Ready state, even though the idle task is + running. */ + #if( configUSE_PORT_OPTIMISED_TASK_SELECTION == 0 ) + { + if( uxTopReadyPriority > tskIDLE_PRIORITY ) + { + uxHigherPriorityReadyTasks = pdTRUE; + } + } + #else + { + const UBaseType_t uxLeastSignificantBit = ( UBaseType_t ) 0x01; + + /* When port optimised task selection is used the uxTopReadyPriority + variable is used as a bit map. If bits other than the least + significant bit are set then there are tasks that have a priority + above the idle priority that are in the Ready state. This takes + care of the case where the co-operative scheduler is in use. */ + if( uxTopReadyPriority > uxLeastSignificantBit ) + { + uxHigherPriorityReadyTasks = pdTRUE; + } + } + #endif + + if( pxCurrentTCB->uxPriority > tskIDLE_PRIORITY ) + { + xReturn = 0; + } + else if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > 1 ) + { + /* There are other idle priority tasks in the ready state. If + time slicing is used then the very next tick interrupt must be + processed. */ + xReturn = 0; + } + else if( uxHigherPriorityReadyTasks != pdFALSE ) + { + /* There are tasks in the Ready state that have a priority above the + idle priority. This path can only be reached if + configUSE_PREEMPTION is 0. */ + xReturn = 0; + } + else + { + xReturn = xNextTaskUnblockTime - xTickCount; + } + + return xReturn; + } + +#endif /* configUSE_TICKLESS_IDLE */ +/*----------------------------------------------------------*/ + +BaseType_t xTaskResumeAll( void ) +{ +TCB_t *pxTCB = NULL; +BaseType_t xAlreadyYielded = pdFALSE; + + /* If uxSchedulerSuspended is zero then this function does not match a + previous call to vTaskSuspendAll(). */ + configASSERT( uxSchedulerSuspended ); + + /* It is possible that an ISR caused a task to be removed from an event + list while the scheduler was suspended. If this was the case then the + removed task will have been added to the xPendingReadyList. Once the + scheduler has been resumed it is safe to move all the pending ready + tasks from this list into their appropriate ready list. */ + taskENTER_CRITICAL(); + { + --uxSchedulerSuspended; + + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + if( uxCurrentNumberOfTasks > ( UBaseType_t ) 0U ) + { + /* Move any readied tasks from the pending list into the + appropriate ready list. */ + while( listLIST_IS_EMPTY( &xPendingReadyList ) == pdFALSE ) + { + pxTCB = listGET_OWNER_OF_HEAD_ENTRY( ( &xPendingReadyList ) ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + + /* If the moved task has a priority higher than the current + task then a yield must be performed. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + if( pxTCB != NULL ) + { + /* A task was unblocked while the scheduler was suspended, + which may have prevented the next unblock time from being + re-calculated, in which case re-calculate it now. Mainly + important for low power tickless implementations, where + this can prevent an unnecessary exit from low power + state. */ + prvResetNextTaskUnblockTime(); + } + + /* If any ticks occurred while the scheduler was suspended then + they should be processed now. This ensures the tick count does + not slip, and that any delayed tasks are resumed at the correct + time. */ + { + TickType_t xPendedCounts = xPendedTicks; /* Non-volatile copy. */ + + if( xPendedCounts > ( TickType_t ) 0U ) + { + do + { + if( xTaskIncrementTick() != pdFALSE ) + { + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + --xPendedCounts; + } while( xPendedCounts > ( TickType_t ) 0U ); + + xPendedTicks = 0; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + if( xYieldPending != pdFALSE ) + { + #if( configUSE_PREEMPTION != 0 ) + { + xAlreadyYielded = pdTRUE; + } + #endif + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + return xAlreadyYielded; +} +/*-----------------------------------------------------------*/ + +TickType_t xTaskGetTickCount( void ) +{ +TickType_t xTicks; + + /* Critical section required if running on a 16 bit processor. */ + portTICK_TYPE_ENTER_CRITICAL(); + { + xTicks = xTickCount; + } + portTICK_TYPE_EXIT_CRITICAL(); + + return xTicks; +} +/*-----------------------------------------------------------*/ + +TickType_t xTaskGetTickCountFromISR( void ) +{ +TickType_t xReturn; +UBaseType_t uxSavedInterruptStatus; + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: https://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR(); + { + xReturn = xTickCount; + } + portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +UBaseType_t uxTaskGetNumberOfTasks( void ) +{ + /* A critical section is not required because the variables are of type + BaseType_t. */ + return uxCurrentNumberOfTasks; +} +/*-----------------------------------------------------------*/ + +char *pcTaskGetName( TaskHandle_t xTaskToQuery ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ +{ +TCB_t *pxTCB; + + /* If null is passed in here then the name of the calling task is being + queried. */ + pxTCB = prvGetTCBFromHandle( xTaskToQuery ); + configASSERT( pxTCB ); + return &( pxTCB->pcTaskName[ 0 ] ); +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetHandle == 1 ) + + static TCB_t *prvSearchForNameWithinSingleList( List_t *pxList, const char pcNameToQuery[] ) + { + TCB_t *pxNextTCB, *pxFirstTCB, *pxReturn = NULL; + UBaseType_t x; + char cNextChar; + BaseType_t xBreakLoop; + + /* This function is called with the scheduler suspended. */ + + if( listCURRENT_LIST_LENGTH( pxList ) > ( UBaseType_t ) 0 ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + + /* Check each character in the name looking for a match or + mismatch. */ + xBreakLoop = pdFALSE; + for( x = ( UBaseType_t ) 0; x < ( UBaseType_t ) configMAX_TASK_NAME_LEN; x++ ) + { + cNextChar = pxNextTCB->pcTaskName[ x ]; + + if( cNextChar != pcNameToQuery[ x ] ) + { + /* Characters didn't match. */ + xBreakLoop = pdTRUE; + } + else if( cNextChar == ( char ) 0x00 ) + { + /* Both strings terminated, a match must have been + found. */ + pxReturn = pxNextTCB; + xBreakLoop = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xBreakLoop != pdFALSE ) + { + break; + } + } + + if( pxReturn != NULL ) + { + /* The handle has been found. */ + break; + } + + } while( pxNextTCB != pxFirstTCB ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return pxReturn; + } + +#endif /* INCLUDE_xTaskGetHandle */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetHandle == 1 ) + + TaskHandle_t xTaskGetHandle( const char *pcNameToQuery ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + { + UBaseType_t uxQueue = configMAX_PRIORITIES; + TCB_t* pxTCB; + + /* Task names will be truncated to configMAX_TASK_NAME_LEN - 1 bytes. */ + configASSERT( strlen( pcNameToQuery ) < configMAX_TASK_NAME_LEN ); + + vTaskSuspendAll(); + { + /* Search the ready lists. */ + do + { + uxQueue--; + pxTCB = prvSearchForNameWithinSingleList( ( List_t * ) &( pxReadyTasksLists[ uxQueue ] ), pcNameToQuery ); + + if( pxTCB != NULL ) + { + /* Found the handle. */ + break; + } + + } while( uxQueue > ( UBaseType_t ) tskIDLE_PRIORITY ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + /* Search the delayed lists. */ + if( pxTCB == NULL ) + { + pxTCB = prvSearchForNameWithinSingleList( ( List_t * ) pxDelayedTaskList, pcNameToQuery ); + } + + if( pxTCB == NULL ) + { + pxTCB = prvSearchForNameWithinSingleList( ( List_t * ) pxOverflowDelayedTaskList, pcNameToQuery ); + } + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( pxTCB == NULL ) + { + /* Search the suspended list. */ + pxTCB = prvSearchForNameWithinSingleList( &xSuspendedTaskList, pcNameToQuery ); + } + } + #endif + + #if( INCLUDE_vTaskDelete == 1 ) + { + if( pxTCB == NULL ) + { + /* Search the deleted list. */ + pxTCB = prvSearchForNameWithinSingleList( &xTasksWaitingTermination, pcNameToQuery ); + } + } + #endif + } + ( void ) xTaskResumeAll(); + + return pxTCB; + } + +#endif /* INCLUDE_xTaskGetHandle */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, const UBaseType_t uxArraySize, uint32_t * const pulTotalRunTime ) + { + UBaseType_t uxTask = 0, uxQueue = configMAX_PRIORITIES; + + vTaskSuspendAll(); + { + /* Is there a space in the array for each task in the system? */ + if( uxArraySize >= uxCurrentNumberOfTasks ) + { + /* Fill in an TaskStatus_t structure with information on each + task in the Ready state. */ + do + { + uxQueue--; + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &( pxReadyTasksLists[ uxQueue ] ), eReady ); + + } while( uxQueue > ( UBaseType_t ) tskIDLE_PRIORITY ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + /* Fill in an TaskStatus_t structure with information on each + task in the Blocked state. */ + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), ( List_t * ) pxDelayedTaskList, eBlocked ); + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), ( List_t * ) pxOverflowDelayedTaskList, eBlocked ); + + #if( INCLUDE_vTaskDelete == 1 ) + { + /* Fill in an TaskStatus_t structure with information on + each task that has been deleted but not yet cleaned up. */ + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &xTasksWaitingTermination, eDeleted ); + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + /* Fill in an TaskStatus_t structure with information on + each task in the Suspended state. */ + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &xSuspendedTaskList, eSuspended ); + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1) + { + if( pulTotalRunTime != NULL ) + { + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ( *pulTotalRunTime ) ); + #else + *pulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + } + } + #else + { + if( pulTotalRunTime != NULL ) + { + *pulTotalRunTime = 0; + } + } + #endif + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + ( void ) xTaskResumeAll(); + + return uxTask; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + TaskHandle_t xTaskGetIdleTaskHandle( void ) + { + /* If xTaskGetIdleTaskHandle() is called before the scheduler has been + started, then xIdleTaskHandle will be NULL. */ + configASSERT( ( xIdleTaskHandle != NULL ) ); + return xIdleTaskHandle; + } + +#endif /* INCLUDE_xTaskGetIdleTaskHandle */ +/*----------------------------------------------------------*/ + +/* This conditional compilation should use inequality to 0, not equality to 1. +This is to ensure vTaskStepTick() is available when user defined low power mode +implementations require configUSE_TICKLESS_IDLE to be set to a value other than +1. */ +#if ( configUSE_TICKLESS_IDLE != 0 ) + + void vTaskStepTick( const TickType_t xTicksToJump ) + { + /* Correct the tick count value after a period during which the tick + was suppressed. Note this does *not* call the tick hook function for + each stepped tick. */ + configASSERT( ( xTickCount + xTicksToJump ) <= xNextTaskUnblockTime ); + xTickCount += xTicksToJump; + traceINCREASE_TICK_COUNT( xTicksToJump ); + } + +#endif /* configUSE_TICKLESS_IDLE */ +/*----------------------------------------------------------*/ + +BaseType_t xTaskCatchUpTicks( TickType_t xTicksToCatchUp ) +{ +BaseType_t xYieldRequired = pdFALSE; + + /* Must not be called with the scheduler suspended as the implementation + relies on xPendedTicks being wound down to 0 in xTaskResumeAll(). */ + configASSERT( uxSchedulerSuspended == 0 ); + + /* Use xPendedTicks to mimic xTicksToCatchUp number of ticks occurring when + the scheduler is suspended so the ticks are executed in xTaskResumeAll(). */ + vTaskSuspendAll(); + xPendedTicks += xTicksToCatchUp; + xYieldRequired = xTaskResumeAll(); + + return xYieldRequired; +} +/*----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskAbortDelay == 1 ) + + BaseType_t xTaskAbortDelay( TaskHandle_t xTask ) + { + TCB_t *pxTCB = xTask; + BaseType_t xReturn; + + configASSERT( pxTCB ); + + vTaskSuspendAll(); + { + /* A task can only be prematurely removed from the Blocked state if + it is actually in the Blocked state. */ + if( eTaskGetState( xTask ) == eBlocked ) + { + xReturn = pdPASS; + + /* Remove the reference to the task from the blocked list. An + interrupt won't touch the xStateListItem because the + scheduler is suspended. */ + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + + /* Is the task waiting on an event also? If so remove it from + the event list too. Interrupts can touch the event list item, + even though the scheduler is suspended, so a critical section + is used. */ + taskENTER_CRITICAL(); + { + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + + /* This lets the task know it was forcibly removed from the + blocked state so it should not re-evaluate its block time and + then block again. */ + pxTCB->ucDelayAborted = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + /* Place the unblocked task into the appropriate ready list. */ + prvAddTaskToReadyList( pxTCB ); + + /* A task being unblocked cannot cause an immediate context + switch if preemption is turned off. */ + #if ( configUSE_PREEMPTION == 1 ) + { + /* Preemption is on, but a context switch should only be + performed if the unblocked task has a priority that is + equal to or higher than the currently executing task. */ + if( pxTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* Pend the yield to be performed when the scheduler + is unsuspended. */ + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_PREEMPTION */ + } + else + { + xReturn = pdFAIL; + } + } + ( void ) xTaskResumeAll(); + + return xReturn; + } + +#endif /* INCLUDE_xTaskAbortDelay */ +/*----------------------------------------------------------*/ + +BaseType_t xTaskIncrementTick( void ) +{ +TCB_t * pxTCB; +TickType_t xItemValue; +BaseType_t xSwitchRequired = pdFALSE; + + /* Called by the portable layer each time a tick interrupt occurs. + Increments the tick then checks to see if the new tick value will cause any + tasks to be unblocked. */ + traceTASK_INCREMENT_TICK( xTickCount ); + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + /* Minor optimisation. The tick count cannot change in this + block. */ + const TickType_t xConstTickCount = xTickCount + ( TickType_t ) 1; + + /* Increment the RTOS tick, switching the delayed and overflowed + delayed lists if it wraps to 0. */ + xTickCount = xConstTickCount; + + if( xConstTickCount == ( TickType_t ) 0U ) /*lint !e774 'if' does not always evaluate to false as it is looking for an overflow. */ + { + taskSWITCH_DELAYED_LISTS(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* See if this tick has made a timeout expire. Tasks are stored in + the queue in the order of their wake time - meaning once one task + has been found whose block time has not expired there is no need to + look any further down the list. */ + if( xConstTickCount >= xNextTaskUnblockTime ) + { + for( ;; ) + { + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) + { + /* The delayed list is empty. Set xNextTaskUnblockTime + to the maximum possible value so it is extremely + unlikely that the + if( xTickCount >= xNextTaskUnblockTime ) test will pass + next time through. */ + xNextTaskUnblockTime = portMAX_DELAY; /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + break; + } + else + { + /* The delayed list is not empty, get the value of the + item at the head of the delayed list. This is the time + at which the task at the head of the delayed list must + be removed from the Blocked state. */ + pxTCB = listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xStateListItem ) ); + + if( xConstTickCount < xItemValue ) + { + /* It is not time to unblock this item yet, but the + item value is the time at which the task at the head + of the blocked list must be removed from the Blocked + state - so record the item value in + xNextTaskUnblockTime. */ + xNextTaskUnblockTime = xItemValue; + break; /*lint !e9011 Code structure here is deedmed easier to understand with multiple breaks. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* It is time to remove the item from the Blocked state. */ + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + + /* Is the task waiting on an event also? If so remove + it from the event list. */ + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Place the unblocked task into the appropriate ready + list. */ + prvAddTaskToReadyList( pxTCB ); + + /* A task being unblocked cannot cause an immediate + context switch if preemption is turned off. */ + #if ( configUSE_PREEMPTION == 1 ) + { + /* Preemption is on, but a context switch should + only be performed if the unblocked task has a + priority that is equal to or higher than the + currently executing task. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xSwitchRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_PREEMPTION */ + } + } + } + + /* Tasks of equal priority to the currently running task will share + processing time (time slice) if preemption is on, and the application + writer has not explicitly turned time slicing off. */ + #if ( ( configUSE_PREEMPTION == 1 ) && ( configUSE_TIME_SLICING == 1 ) ) + { + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ pxCurrentTCB->uxPriority ] ) ) > ( UBaseType_t ) 1 ) + { + xSwitchRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* ( ( configUSE_PREEMPTION == 1 ) && ( configUSE_TIME_SLICING == 1 ) ) */ + + #if ( configUSE_TICK_HOOK == 1 ) + { + /* Guard against the tick hook being called when the pended tick + count is being unwound (when the scheduler is being unlocked). */ + if( xPendedTicks == ( TickType_t ) 0 ) + { + vApplicationTickHook(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_TICK_HOOK */ + + #if ( configUSE_PREEMPTION == 1 ) + { + if( xYieldPending != pdFALSE ) + { + xSwitchRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_PREEMPTION */ + } + else + { + ++xPendedTicks; + + /* The tick hook gets called at regular intervals, even if the + scheduler is locked. */ + #if ( configUSE_TICK_HOOK == 1 ) + { + vApplicationTickHook(); + } + #endif + } + + return xSwitchRequired; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction ) + { + TCB_t *xTCB; + + /* If xTask is NULL then it is the task hook of the calling task that is + getting set. */ + if( xTask == NULL ) + { + xTCB = ( TCB_t * ) pxCurrentTCB; + } + else + { + xTCB = xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + { + xTCB->pxTaskTag = pxHookFunction; + } + taskEXIT_CRITICAL(); + } + +#endif /* configUSE_APPLICATION_TASK_TAG */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + TaskHookFunction_t xTaskGetApplicationTaskTag( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + TaskHookFunction_t xReturn; + + /* If xTask is NULL then set the calling task's hook. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + { + xReturn = pxTCB->pxTaskTag; + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_APPLICATION_TASK_TAG */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + TaskHookFunction_t xTaskGetApplicationTaskTagFromISR( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + TaskHookFunction_t xReturn; + UBaseType_t uxSavedInterruptStatus; + + /* If xTask is NULL then set the calling task's hook. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + xReturn = pxTCB->pxTaskTag; + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; + } + +#endif /* configUSE_APPLICATION_TASK_TAG */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter ) + { + TCB_t *xTCB; + BaseType_t xReturn; + + /* If xTask is NULL then we are calling our own task hook. */ + if( xTask == NULL ) + { + xTCB = pxCurrentTCB; + } + else + { + xTCB = xTask; + } + + if( xTCB->pxTaskTag != NULL ) + { + xReturn = xTCB->pxTaskTag( pvParameter ); + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif /* configUSE_APPLICATION_TASK_TAG */ +/*-----------------------------------------------------------*/ + +void vTaskSwitchContext( void ) +{ + if( uxSchedulerSuspended != ( UBaseType_t ) pdFALSE ) + { + /* The scheduler is currently suspended - do not allow a context + switch. */ + xYieldPending = pdTRUE; + } + else + { + xYieldPending = pdFALSE; + traceTASK_SWITCHED_OUT(); + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); + #else + ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Add the amount of time the task has been running to the + accumulated time so far. The time the task started running was + stored in ulTaskSwitchedInTime. Note that there is no overflow + protection here so count values are only valid until the timer + overflows. The guard against negative values is to protect + against suspect run time stat counter implementations - which + are provided by the application, not the kernel. */ + if( ulTotalRunTime > ulTaskSwitchedInTime ) + { + pxCurrentTCB->ulRunTimeCounter += ( ulTotalRunTime - ulTaskSwitchedInTime ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + ulTaskSwitchedInTime = ulTotalRunTime; + } + #endif /* configGENERATE_RUN_TIME_STATS */ + + /* Check for stack overflow, if configured. */ + taskCHECK_FOR_STACK_OVERFLOW(); + + /* Before the currently running task is switched out, save its errno. */ + #if( configUSE_POSIX_ERRNO == 1 ) + { + pxCurrentTCB->iTaskErrno = FreeRTOS_errno; + } + #endif + + /* Select a new task to run using either the generic C or port + optimised asm code. */ + taskSELECT_HIGHEST_PRIORITY_TASK(); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + traceTASK_SWITCHED_IN(); + + /* After the new task is switched in, update the global errno. */ + #if( configUSE_POSIX_ERRNO == 1 ) + { + FreeRTOS_errno = pxCurrentTCB->iTaskErrno; + } + #endif + + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + { + /* Switch Newlib's _impure_ptr variable to point to the _reent + structure specific to this task. + See the third party link http://www.nadler.com/embedded/newlibAndFreeRTOS.html + for additional information. */ + _impure_ptr = &( pxCurrentTCB->xNewLib_reent ); + } + #endif /* configUSE_NEWLIB_REENTRANT */ + } +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnEventList( List_t * const pxEventList, const TickType_t xTicksToWait ) +{ + configASSERT( pxEventList ); + + /* THIS FUNCTION MUST BE CALLED WITH EITHER INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED AND THE QUEUE BEING ACCESSED LOCKED. */ + + /* Place the event list item of the TCB in the appropriate event list. + This is placed in the list in priority order so the highest priority task + is the first to be woken by the event. The queue that contains the event + list is locked, preventing simultaneous access from interrupts. */ + vListInsert( pxEventList, &( pxCurrentTCB->xEventListItem ) ); + + prvAddCurrentTaskToDelayedList( xTicksToWait, pdTRUE ); +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnUnorderedEventList( List_t * pxEventList, const TickType_t xItemValue, const TickType_t xTicksToWait ) +{ + configASSERT( pxEventList ); + + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. It is used by + the event groups implementation. */ + configASSERT( uxSchedulerSuspended != 0 ); + + /* Store the item value in the event list item. It is safe to access the + event list item here as interrupts won't access the event list item of a + task that is not in the Blocked state. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ), xItemValue | taskEVENT_LIST_ITEM_VALUE_IN_USE ); + + /* Place the event list item of the TCB at the end of the appropriate event + list. It is safe to access the event list here because it is part of an + event group implementation - and interrupts don't access event groups + directly (instead they access them indirectly by pending function calls to + the task level). */ + vListInsertEnd( pxEventList, &( pxCurrentTCB->xEventListItem ) ); + + prvAddCurrentTaskToDelayedList( xTicksToWait, pdTRUE ); +} +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + + void vTaskPlaceOnEventListRestricted( List_t * const pxEventList, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) + { + configASSERT( pxEventList ); + + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements - + it should be called with the scheduler suspended. */ + + + /* Place the event list item of the TCB in the appropriate event list. + In this case it is assume that this is the only task that is going to + be waiting on this event list, so the faster vListInsertEnd() function + can be used in place of vListInsert. */ + vListInsertEnd( pxEventList, &( pxCurrentTCB->xEventListItem ) ); + + /* If the task should block indefinitely then set the block time to a + value that will be recognised as an indefinite delay inside the + prvAddCurrentTaskToDelayedList() function. */ + if( xWaitIndefinitely != pdFALSE ) + { + xTicksToWait = portMAX_DELAY; + } + + traceTASK_DELAY_UNTIL( ( xTickCount + xTicksToWait ) ); + prvAddCurrentTaskToDelayedList( xTicksToWait, xWaitIndefinitely ); + } + +#endif /* configUSE_TIMERS */ +/*-----------------------------------------------------------*/ + +BaseType_t xTaskRemoveFromEventList( const List_t * const pxEventList ) +{ +TCB_t *pxUnblockedTCB; +BaseType_t xReturn; + + /* THIS FUNCTION MUST BE CALLED FROM A CRITICAL SECTION. It can also be + called from a critical section within an ISR. */ + + /* The event list is sorted in priority order, so the first in the list can + be removed as it is known to be the highest priority. Remove the TCB from + the delayed list, and add it to the ready list. + + If an event is for a queue that is locked then this function will never + get called - the lock count on the queue will get modified instead. This + means exclusive access to the event list is guaranteed here. + + This function assumes that a check has already been made to ensure that + pxEventList is not empty. */ + pxUnblockedTCB = listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + configASSERT( pxUnblockedTCB ); + ( void ) uxListRemove( &( pxUnblockedTCB->xEventListItem ) ); + + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + ( void ) uxListRemove( &( pxUnblockedTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxUnblockedTCB ); + + #if( configUSE_TICKLESS_IDLE != 0 ) + { + /* If a task is blocked on a kernel object then xNextTaskUnblockTime + might be set to the blocked task's time out time. If the task is + unblocked for a reason other than a timeout xNextTaskUnblockTime is + normally left unchanged, because it is automatically reset to a new + value when the tick count equals xNextTaskUnblockTime. However if + tickless idling is used it might be more important to enter sleep mode + at the earliest possible time - so reset xNextTaskUnblockTime here to + ensure it is updated at the earliest possible time. */ + prvResetNextTaskUnblockTime(); + } + #endif + } + else + { + /* The delayed and ready lists cannot be accessed, so hold this task + pending until the scheduler is resumed. */ + vListInsertEnd( &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); + } + + if( pxUnblockedTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* Return true if the task removed from the event list has a higher + priority than the calling task. This allows the calling task to know if + it should force a context switch now. */ + xReturn = pdTRUE; + + /* Mark that a yield is pending in case the user is not using the + "xHigherPriorityTaskWoken" parameter to an ISR safe FreeRTOS function. */ + xYieldPending = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskRemoveFromUnorderedEventList( ListItem_t * pxEventListItem, const TickType_t xItemValue ) +{ +TCB_t *pxUnblockedTCB; + + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. It is used by + the event flags implementation. */ + configASSERT( uxSchedulerSuspended != pdFALSE ); + + /* Store the new item value in the event list. */ + listSET_LIST_ITEM_VALUE( pxEventListItem, xItemValue | taskEVENT_LIST_ITEM_VALUE_IN_USE ); + + /* Remove the event list form the event flag. Interrupts do not access + event flags. */ + pxUnblockedTCB = listGET_LIST_ITEM_OWNER( pxEventListItem ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + configASSERT( pxUnblockedTCB ); + ( void ) uxListRemove( pxEventListItem ); + + #if( configUSE_TICKLESS_IDLE != 0 ) + { + /* If a task is blocked on a kernel object then xNextTaskUnblockTime + might be set to the blocked task's time out time. If the task is + unblocked for a reason other than a timeout xNextTaskUnblockTime is + normally left unchanged, because it is automatically reset to a new + value when the tick count equals xNextTaskUnblockTime. However if + tickless idling is used it might be more important to enter sleep mode + at the earliest possible time - so reset xNextTaskUnblockTime here to + ensure it is updated at the earliest possible time. */ + prvResetNextTaskUnblockTime(); + } + #endif + + /* Remove the task from the delayed list and add it to the ready list. The + scheduler is suspended so interrupts will not be accessing the ready + lists. */ + ( void ) uxListRemove( &( pxUnblockedTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxUnblockedTCB ); + + if( pxUnblockedTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* The unblocked task has a priority above that of the calling task, so + a context switch is required. This function is called with the + scheduler suspended so xYieldPending is set so the context switch + occurs immediately that the scheduler is resumed (unsuspended). */ + xYieldPending = pdTRUE; + } +} +/*-----------------------------------------------------------*/ + +void vTaskSetTimeOutState( TimeOut_t * const pxTimeOut ) +{ + configASSERT( pxTimeOut ); + taskENTER_CRITICAL(); + { + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +void vTaskInternalSetTimeOutState( TimeOut_t * const pxTimeOut ) +{ + /* For internal use only as it does not use a critical section. */ + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; +} +/*-----------------------------------------------------------*/ + +BaseType_t xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait ) +{ +BaseType_t xReturn; + + configASSERT( pxTimeOut ); + configASSERT( pxTicksToWait ); + + taskENTER_CRITICAL(); + { + /* Minor optimisation. The tick count cannot change in this block. */ + const TickType_t xConstTickCount = xTickCount; + const TickType_t xElapsedTime = xConstTickCount - pxTimeOut->xTimeOnEntering; + + #if( INCLUDE_xTaskAbortDelay == 1 ) + if( pxCurrentTCB->ucDelayAborted != ( uint8_t ) pdFALSE ) + { + /* The delay was aborted, which is not the same as a time out, + but has the same result. */ + pxCurrentTCB->ucDelayAborted = pdFALSE; + xReturn = pdTRUE; + } + else + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + if( *pxTicksToWait == portMAX_DELAY ) + { + /* If INCLUDE_vTaskSuspend is set to 1 and the block time + specified is the maximum block time then the task should block + indefinitely, and therefore never time out. */ + xReturn = pdFALSE; + } + else + #endif + + if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( xConstTickCount >= pxTimeOut->xTimeOnEntering ) ) /*lint !e525 Indentation preferred as is to make code within pre-processor directives clearer. */ + { + /* The tick count is greater than the time at which + vTaskSetTimeout() was called, but has also overflowed since + vTaskSetTimeOut() was called. It must have wrapped all the way + around and gone past again. This passed since vTaskSetTimeout() + was called. */ + xReturn = pdTRUE; + } + else if( xElapsedTime < *pxTicksToWait ) /*lint !e961 Explicit casting is only redundant with some compilers, whereas others require it to prevent integer conversion errors. */ + { + /* Not a genuine timeout. Adjust parameters for time remaining. */ + *pxTicksToWait -= xElapsedTime; + vTaskInternalSetTimeOutState( pxTimeOut ); + xReturn = pdFALSE; + } + else + { + *pxTicksToWait = 0; + xReturn = pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskMissedYield( void ) +{ + xYieldPending = pdTRUE; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxTaskGetTaskNumber( TaskHandle_t xTask ) + { + UBaseType_t uxReturn; + TCB_t const *pxTCB; + + if( xTask != NULL ) + { + pxTCB = xTask; + uxReturn = pxTCB->uxTaskNumber; + } + else + { + uxReturn = 0U; + } + + return uxReturn; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskSetTaskNumber( TaskHandle_t xTask, const UBaseType_t uxHandle ) + { + TCB_t * pxTCB; + + if( xTask != NULL ) + { + pxTCB = xTask; + pxTCB->uxTaskNumber = uxHandle; + } + } + +#endif /* configUSE_TRACE_FACILITY */ + +/* + * ----------------------------------------------------------- + * The Idle task. + * ---------------------------------------------------------- + * + * The portTASK_FUNCTION() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION( prvIdleTask, pvParameters ) +{ + /* Stop warnings. */ + ( void ) pvParameters; + + /** THIS IS THE RTOS IDLE TASK - WHICH IS CREATED AUTOMATICALLY WHEN THE + SCHEDULER IS STARTED. **/ + + /* In case a task that has a secure context deletes itself, in which case + the idle task is responsible for deleting the task's secure context, if + any. */ + portALLOCATE_SECURE_CONTEXT( configMINIMAL_SECURE_STACK_SIZE ); + + for( ;; ) + { + /* See if any tasks have deleted themselves - if so then the idle task + is responsible for freeing the deleted task's TCB and stack. */ + prvCheckTasksWaitingTermination(); + + #if ( configUSE_PREEMPTION == 0 ) + { + /* If we are not using preemption we keep forcing a task switch to + see if any other task has become available. If we are using + preemption we don't need to do this as any task becoming available + will automatically get the processor anyway. */ + taskYIELD(); + } + #endif /* configUSE_PREEMPTION */ + + #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) + { + /* When using preemption tasks of equal priority will be + timesliced. If a task that is sharing the idle priority is ready + to run then the idle task should yield before the end of the + timeslice. + + A critical region is not required here as we are just reading from + the list, and an occasional incorrect value will not matter. If + the ready list at the idle priority contains more than one task + then a task other than the idle task is ready to execute. */ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( UBaseType_t ) 1 ) + { + taskYIELD(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) */ + + #if ( configUSE_IDLE_HOOK == 1 ) + { + extern void vApplicationIdleHook( void ); + + /* Call the user defined function from within the idle task. This + allows the application designer to add background functionality + without the overhead of a separate task. + NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, + CALL A FUNCTION THAT MIGHT BLOCK. */ + vApplicationIdleHook(); + } + #endif /* configUSE_IDLE_HOOK */ + + /* This conditional compilation should use inequality to 0, not equality + to 1. This is to ensure portSUPPRESS_TICKS_AND_SLEEP() is called when + user defined low power mode implementations require + configUSE_TICKLESS_IDLE to be set to a value other than 1. */ + #if ( configUSE_TICKLESS_IDLE != 0 ) + { + TickType_t xExpectedIdleTime; + + /* It is not desirable to suspend then resume the scheduler on + each iteration of the idle task. Therefore, a preliminary + test of the expected idle time is performed without the + scheduler suspended. The result here is not necessarily + valid. */ + xExpectedIdleTime = prvGetExpectedIdleTime(); + + if( xExpectedIdleTime >= configEXPECTED_IDLE_TIME_BEFORE_SLEEP ) + { + vTaskSuspendAll(); + { + /* Now the scheduler is suspended, the expected idle + time can be sampled again, and this time its value can + be used. */ + configASSERT( xNextTaskUnblockTime >= xTickCount ); + xExpectedIdleTime = prvGetExpectedIdleTime(); + + /* Define the following macro to set xExpectedIdleTime to 0 + if the application does not want + portSUPPRESS_TICKS_AND_SLEEP() to be called. */ + configPRE_SUPPRESS_TICKS_AND_SLEEP_PROCESSING( xExpectedIdleTime ); + + if( xExpectedIdleTime >= configEXPECTED_IDLE_TIME_BEFORE_SLEEP ) + { + traceLOW_POWER_IDLE_BEGIN(); + portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ); + traceLOW_POWER_IDLE_END(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + ( void ) xTaskResumeAll(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_TICKLESS_IDLE */ + } +} +/*-----------------------------------------------------------*/ + +#if( configUSE_TICKLESS_IDLE != 0 ) + + eSleepModeStatus eTaskConfirmSleepModeStatus( void ) + { + /* The idle task exists in addition to the application tasks. */ + const UBaseType_t uxNonApplicationTasks = 1; + eSleepModeStatus eReturn = eStandardSleep; + + /* This function must be called from a critical section. */ + + if( listCURRENT_LIST_LENGTH( &xPendingReadyList ) != 0 ) + { + /* A task was made ready while the scheduler was suspended. */ + eReturn = eAbortSleep; + } + else if( xYieldPending != pdFALSE ) + { + /* A yield was pended while the scheduler was suspended. */ + eReturn = eAbortSleep; + } + else + { + /* If all the tasks are in the suspended list (which might mean they + have an infinite block time rather than actually being suspended) + then it is safe to turn all clocks off and just wait for external + interrupts. */ + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == ( uxCurrentNumberOfTasks - uxNonApplicationTasks ) ) + { + eReturn = eNoTasksWaitingTimeout; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + return eReturn; + } + +#endif /* configUSE_TICKLESS_IDLE */ +/*-----------------------------------------------------------*/ + +#if ( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 ) + + void vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue ) + { + TCB_t *pxTCB; + + if( xIndex < configNUM_THREAD_LOCAL_STORAGE_POINTERS ) + { + pxTCB = prvGetTCBFromHandle( xTaskToSet ); + configASSERT( pxTCB != NULL ); + pxTCB->pvThreadLocalStoragePointers[ xIndex ] = pvValue; + } + } + +#endif /* configNUM_THREAD_LOCAL_STORAGE_POINTERS */ +/*-----------------------------------------------------------*/ + +#if ( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 ) + + void *pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex ) + { + void *pvReturn = NULL; + TCB_t *pxTCB; + + if( xIndex < configNUM_THREAD_LOCAL_STORAGE_POINTERS ) + { + pxTCB = prvGetTCBFromHandle( xTaskToQuery ); + pvReturn = pxTCB->pvThreadLocalStoragePointers[ xIndex ]; + } + else + { + pvReturn = NULL; + } + + return pvReturn; + } + +#endif /* configNUM_THREAD_LOCAL_STORAGE_POINTERS */ +/*-----------------------------------------------------------*/ + +#if ( portUSING_MPU_WRAPPERS == 1 ) + + void vTaskAllocateMPURegions( TaskHandle_t xTaskToModify, const MemoryRegion_t * const xRegions ) + { + TCB_t *pxTCB; + + /* If null is passed in here then we are modifying the MPU settings of + the calling task. */ + pxTCB = prvGetTCBFromHandle( xTaskToModify ); + + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); + } + +#endif /* portUSING_MPU_WRAPPERS */ +/*-----------------------------------------------------------*/ + +static void prvInitialiseTaskLists( void ) +{ +UBaseType_t uxPriority; + + for( uxPriority = ( UBaseType_t ) 0U; uxPriority < ( UBaseType_t ) configMAX_PRIORITIES; uxPriority++ ) + { + vListInitialise( &( pxReadyTasksLists[ uxPriority ] ) ); + } + + vListInitialise( &xDelayedTaskList1 ); + vListInitialise( &xDelayedTaskList2 ); + vListInitialise( &xPendingReadyList ); + + #if ( INCLUDE_vTaskDelete == 1 ) + { + vListInitialise( &xTasksWaitingTermination ); + } + #endif /* INCLUDE_vTaskDelete */ + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + vListInitialise( &xSuspendedTaskList ); + } + #endif /* INCLUDE_vTaskSuspend */ + + /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList + using list2. */ + pxDelayedTaskList = &xDelayedTaskList1; + pxOverflowDelayedTaskList = &xDelayedTaskList2; +} +/*-----------------------------------------------------------*/ + +static void prvCheckTasksWaitingTermination( void ) +{ + + /** THIS FUNCTION IS CALLED FROM THE RTOS IDLE TASK **/ + + #if ( INCLUDE_vTaskDelete == 1 ) + { + TCB_t *pxTCB; + + /* uxDeletedTasksWaitingCleanUp is used to prevent taskENTER_CRITICAL() + being called too often in the idle task. */ + while( uxDeletedTasksWaitingCleanUp > ( UBaseType_t ) 0U ) + { + taskENTER_CRITICAL(); + { + pxTCB = listGET_OWNER_OF_HEAD_ENTRY( ( &xTasksWaitingTermination ) ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + --uxCurrentNumberOfTasks; + --uxDeletedTasksWaitingCleanUp; + } + taskEXIT_CRITICAL(); + + prvDeleteTCB( pxTCB ); + } + } + #endif /* INCLUDE_vTaskDelete */ +} +/*-----------------------------------------------------------*/ + +#if( configUSE_TRACE_FACILITY == 1 ) + + void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) + { + TCB_t *pxTCB; + + /* xTask is NULL then get the state of the calling task. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + pxTaskStatus->xHandle = ( TaskHandle_t ) pxTCB; + pxTaskStatus->pcTaskName = ( const char * ) &( pxTCB->pcTaskName [ 0 ] ); + pxTaskStatus->uxCurrentPriority = pxTCB->uxPriority; + pxTaskStatus->pxStackBase = pxTCB->pxStack; + pxTaskStatus->xTaskNumber = pxTCB->uxTCBNumber; + + #if ( configUSE_MUTEXES == 1 ) + { + pxTaskStatus->uxBasePriority = pxTCB->uxBasePriority; + } + #else + { + pxTaskStatus->uxBasePriority = 0; + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxTaskStatus->ulRunTimeCounter = pxTCB->ulRunTimeCounter; + } + #else + { + pxTaskStatus->ulRunTimeCounter = 0; + } + #endif + + /* Obtaining the task state is a little fiddly, so is only done if the + value of eState passed into this function is eInvalid - otherwise the + state is just set to whatever is passed in. */ + if( eState != eInvalid ) + { + if( pxTCB == pxCurrentTCB ) + { + pxTaskStatus->eCurrentState = eRunning; + } + else + { + pxTaskStatus->eCurrentState = eState; + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + /* If the task is in the suspended list then there is a + chance it is actually just blocked indefinitely - so really + it should be reported as being in the Blocked state. */ + if( eState == eSuspended ) + { + vTaskSuspendAll(); + { + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + pxTaskStatus->eCurrentState = eBlocked; + } + } + ( void ) xTaskResumeAll(); + } + } + #endif /* INCLUDE_vTaskSuspend */ + } + } + else + { + pxTaskStatus->eCurrentState = eTaskGetState( pxTCB ); + } + + /* Obtaining the stack space takes some time, so the xGetFreeStackSpace + parameter is provided to allow it to be skipped. */ + if( xGetFreeStackSpace != pdFALSE ) + { + #if ( portSTACK_GROWTH > 0 ) + { + pxTaskStatus->usStackHighWaterMark = prvTaskCheckFreeStackSpace( ( uint8_t * ) pxTCB->pxEndOfStack ); + } + #else + { + pxTaskStatus->usStackHighWaterMark = prvTaskCheckFreeStackSpace( ( uint8_t * ) pxTCB->pxStack ); + } + #endif + } + else + { + pxTaskStatus->usStackHighWaterMark = 0; + } + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + static UBaseType_t prvListTasksWithinSingleList( TaskStatus_t *pxTaskStatusArray, List_t *pxList, eTaskState eState ) + { + configLIST_VOLATILE TCB_t *pxNextTCB, *pxFirstTCB; + UBaseType_t uxTask = 0; + + if( listCURRENT_LIST_LENGTH( pxList ) > ( UBaseType_t ) 0 ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + + /* Populate an TaskStatus_t structure within the + pxTaskStatusArray array for each task that is referenced from + pxList. See the definition of TaskStatus_t in task.h for the + meaning of each TaskStatus_t structure member. */ + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + vTaskGetInfo( ( TaskHandle_t ) pxNextTCB, &( pxTaskStatusArray[ uxTask ] ), pdTRUE, eState ); + uxTask++; + } while( pxNextTCB != pxFirstTCB ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return uxTask; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) ) + + static configSTACK_DEPTH_TYPE prvTaskCheckFreeStackSpace( const uint8_t * pucStackByte ) + { + uint32_t ulCount = 0U; + + while( *pucStackByte == ( uint8_t ) tskSTACK_FILL_BYTE ) + { + pucStackByte -= portSTACK_GROWTH; + ulCount++; + } + + ulCount /= ( uint32_t ) sizeof( StackType_t ); /*lint !e961 Casting is not redundant on smaller architectures. */ + + return ( configSTACK_DEPTH_TYPE ) ulCount; + } + +#endif /* ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) ) */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) + + /* uxTaskGetStackHighWaterMark() and uxTaskGetStackHighWaterMark2() are the + same except for their return type. Using configSTACK_DEPTH_TYPE allows the + user to determine the return type. It gets around the problem of the value + overflowing on 8-bit types without breaking backward compatibility for + applications that expect an 8-bit return type. */ + configSTACK_DEPTH_TYPE uxTaskGetStackHighWaterMark2( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + uint8_t *pucEndOfStack; + configSTACK_DEPTH_TYPE uxReturn; + + /* uxTaskGetStackHighWaterMark() and uxTaskGetStackHighWaterMark2() are + the same except for their return type. Using configSTACK_DEPTH_TYPE + allows the user to determine the return type. It gets around the + problem of the value overflowing on 8-bit types without breaking + backward compatibility for applications that expect an 8-bit return + type. */ + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pucEndOfStack = ( uint8_t * ) pxTCB->pxStack; + } + #else + { + pucEndOfStack = ( uint8_t * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = prvTaskCheckFreeStackSpace( pucEndOfStack ); + + return uxReturn; + } + +#endif /* INCLUDE_uxTaskGetStackHighWaterMark2 */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) + + UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + uint8_t *pucEndOfStack; + UBaseType_t uxReturn; + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pucEndOfStack = ( uint8_t * ) pxTCB->pxStack; + } + #else + { + pucEndOfStack = ( uint8_t * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = ( UBaseType_t ) prvTaskCheckFreeStackSpace( pucEndOfStack ); + + return uxReturn; + } + +#endif /* INCLUDE_uxTaskGetStackHighWaterMark */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( TCB_t *pxTCB ) + { + /* This call is required specifically for the TriCore port. It must be + above the vPortFree() calls. The call is also used by ports/demos that + want to allocate and clean RAM statically. */ + portCLEAN_UP_TCB( pxTCB ); + + /* Free up the memory allocated by the scheduler for the task. It is up + to the task to free any memory allocated at the application level. + See the third party link http://www.nadler.com/embedded/newlibAndFreeRTOS.html + for additional information. */ + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + { + _reclaim_reent( &( pxTCB->xNewLib_reent ) ); + } + #endif /* configUSE_NEWLIB_REENTRANT */ + + #if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 0 ) && ( portUSING_MPU_WRAPPERS == 0 ) ) + { + /* The task can only have been allocated dynamically - free both + the stack and TCB. */ + vPortFree( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + #elif( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) /*lint !e731 !e9029 Macro has been consolidated for readability reasons. */ + { + /* The task could have been allocated statically or dynamically, so + check what was statically allocated before trying to free the + memory. */ + if( pxTCB->ucStaticallyAllocated == tskDYNAMICALLY_ALLOCATED_STACK_AND_TCB ) + { + /* Both the stack and TCB were allocated dynamically, so both + must be freed. */ + vPortFree( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + else if( pxTCB->ucStaticallyAllocated == tskSTATICALLY_ALLOCATED_STACK_ONLY ) + { + /* Only the stack was statically allocated, so the TCB is the + only memory that must be freed. */ + vPortFree( pxTCB ); + } + else + { + /* Neither the stack nor the TCB were allocated dynamically, so + nothing needs to be freed. */ + configASSERT( pxTCB->ucStaticallyAllocated == tskSTATICALLY_ALLOCATED_STACK_AND_TCB ); + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + } + +#endif /* INCLUDE_vTaskDelete */ +/*-----------------------------------------------------------*/ + +static void prvResetNextTaskUnblockTime( void ) +{ +TCB_t *pxTCB; + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) + { + /* The new current delayed list is empty. Set xNextTaskUnblockTime to + the maximum possible value so it is extremely unlikely that the + if( xTickCount >= xNextTaskUnblockTime ) test will pass until + there is an item in the delayed list. */ + xNextTaskUnblockTime = portMAX_DELAY; + } + else + { + /* The new current delayed list is not empty, get the value of + the item at the head of the delayed list. This is the time at + which the task at the head of the delayed list should be removed + from the Blocked state. */ + ( pxTCB ) = listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( ( pxTCB )->xStateListItem ) ); + } +} +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) + + TaskHandle_t xTaskGetCurrentTaskHandle( void ) + { + TaskHandle_t xReturn; + + /* A critical section is not required as this is not called from + an interrupt and the current TCB will always be the same for any + individual execution thread. */ + xReturn = pxCurrentTCB; + + return xReturn; + } + +#endif /* ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) */ +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + + BaseType_t xTaskGetSchedulerState( void ) + { + BaseType_t xReturn; + + if( xSchedulerRunning == pdFALSE ) + { + xReturn = taskSCHEDULER_NOT_STARTED; + } + else + { + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + xReturn = taskSCHEDULER_RUNNING; + } + else + { + xReturn = taskSCHEDULER_SUSPENDED; + } + } + + return xReturn; + } + +#endif /* ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + BaseType_t xTaskPriorityInherit( TaskHandle_t const pxMutexHolder ) + { + TCB_t * const pxMutexHolderTCB = pxMutexHolder; + BaseType_t xReturn = pdFALSE; + + /* If the mutex was given back by an interrupt while the queue was + locked then the mutex holder might now be NULL. _RB_ Is this still + needed as interrupts can no longer use mutexes? */ + if( pxMutexHolder != NULL ) + { + /* If the holder of the mutex has a priority below the priority of + the task attempting to obtain the mutex then it will temporarily + inherit the priority of the task attempting to obtain the mutex. */ + if( pxMutexHolderTCB->uxPriority < pxCurrentTCB->uxPriority ) + { + /* Adjust the mutex holder state to account for its new + priority. Only reset the event list item value if the value is + not being used for anything else. */ + if( ( listGET_LIST_ITEM_VALUE( &( pxMutexHolderTCB->xEventListItem ) ) & taskEVENT_LIST_ITEM_VALUE_IN_USE ) == 0UL ) + { + listSET_LIST_ITEM_VALUE( &( pxMutexHolderTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxCurrentTCB->uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* If the task being modified is in the ready state it will need + to be moved into a new list. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxMutexHolderTCB->uxPriority ] ), &( pxMutexHolderTCB->xStateListItem ) ) != pdFALSE ) + { + if( uxListRemove( &( pxMutexHolderTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + /* It is known that the task is in its ready list so + there is no need to check again and the port level + reset macro can be called directly. */ + portRESET_READY_PRIORITY( pxMutexHolderTCB->uxPriority, uxTopReadyPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Inherit the priority before being moved into the new list. */ + pxMutexHolderTCB->uxPriority = pxCurrentTCB->uxPriority; + prvAddTaskToReadyList( pxMutexHolderTCB ); + } + else + { + /* Just inherit the priority. */ + pxMutexHolderTCB->uxPriority = pxCurrentTCB->uxPriority; + } + + traceTASK_PRIORITY_INHERIT( pxMutexHolderTCB, pxCurrentTCB->uxPriority ); + + /* Inheritance occurred. */ + xReturn = pdTRUE; + } + else + { + if( pxMutexHolderTCB->uxBasePriority < pxCurrentTCB->uxPriority ) + { + /* The base priority of the mutex holder is lower than the + priority of the task attempting to take the mutex, but the + current priority of the mutex holder is not lower than the + priority of the task attempting to take the mutex. + Therefore the mutex holder must have already inherited a + priority, but inheritance would have occurred if that had + not been the case. */ + xReturn = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + BaseType_t xTaskPriorityDisinherit( TaskHandle_t const pxMutexHolder ) + { + TCB_t * const pxTCB = pxMutexHolder; + BaseType_t xReturn = pdFALSE; + + if( pxMutexHolder != NULL ) + { + /* A task can only have an inherited priority if it holds the mutex. + If the mutex is held by a task then it cannot be given from an + interrupt, and if a mutex is given by the holding task then it must + be the running state task. */ + configASSERT( pxTCB == pxCurrentTCB ); + configASSERT( pxTCB->uxMutexesHeld ); + ( pxTCB->uxMutexesHeld )--; + + /* Has the holder of the mutex inherited the priority of another + task? */ + if( pxTCB->uxPriority != pxTCB->uxBasePriority ) + { + /* Only disinherit if no other mutexes are held. */ + if( pxTCB->uxMutexesHeld == ( UBaseType_t ) 0 ) + { + /* A task can only have an inherited priority if it holds + the mutex. If the mutex is held by a task then it cannot be + given from an interrupt, and if a mutex is given by the + holding task then it must be the running state task. Remove + the holding task from the ready/delayed list. */ + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + taskRESET_READY_PRIORITY( pxTCB->uxPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Disinherit the priority before adding the task into the + new ready list. */ + traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); + pxTCB->uxPriority = pxTCB->uxBasePriority; + + /* Reset the event list item value. It cannot be in use for + any other purpose if this task is running, and it must be + running to give back the mutex. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxTCB->uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + prvAddTaskToReadyList( pxTCB ); + + /* Return true to indicate that a context switch is required. + This is only actually required in the corner case whereby + multiple mutexes were held and the mutexes were given back + in an order different to that in which they were taken. + If a context switch did not occur when the first mutex was + returned, even if a task was waiting on it, then a context + switch should occur when the last mutex is returned whether + a task is waiting on it or not. */ + xReturn = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityDisinheritAfterTimeout( TaskHandle_t const pxMutexHolder, UBaseType_t uxHighestPriorityWaitingTask ) + { + TCB_t * const pxTCB = pxMutexHolder; + UBaseType_t uxPriorityUsedOnEntry, uxPriorityToUse; + const UBaseType_t uxOnlyOneMutexHeld = ( UBaseType_t ) 1; + + if( pxMutexHolder != NULL ) + { + /* If pxMutexHolder is not NULL then the holder must hold at least + one mutex. */ + configASSERT( pxTCB->uxMutexesHeld ); + + /* Determine the priority to which the priority of the task that + holds the mutex should be set. This will be the greater of the + holding task's base priority and the priority of the highest + priority task that is waiting to obtain the mutex. */ + if( pxTCB->uxBasePriority < uxHighestPriorityWaitingTask ) + { + uxPriorityToUse = uxHighestPriorityWaitingTask; + } + else + { + uxPriorityToUse = pxTCB->uxBasePriority; + } + + /* Does the priority need to change? */ + if( pxTCB->uxPriority != uxPriorityToUse ) + { + /* Only disinherit if no other mutexes are held. This is a + simplification in the priority inheritance implementation. If + the task that holds the mutex is also holding other mutexes then + the other mutexes may have caused the priority inheritance. */ + if( pxTCB->uxMutexesHeld == uxOnlyOneMutexHeld ) + { + /* If a task has timed out because it already holds the + mutex it was trying to obtain then it cannot of inherited + its own priority. */ + configASSERT( pxTCB != pxCurrentTCB ); + + /* Disinherit the priority, remembering the previous + priority to facilitate determining the subject task's + state. */ + traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); + uxPriorityUsedOnEntry = pxTCB->uxPriority; + pxTCB->uxPriority = uxPriorityToUse; + + /* Only reset the event list item value if the value is not + being used for anything else. */ + if( ( listGET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ) ) & taskEVENT_LIST_ITEM_VALUE_IN_USE ) == 0UL ) + { + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) uxPriorityToUse ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* If the running task is not the task that holds the mutex + then the task that holds the mutex could be in either the + Ready, Blocked or Suspended states. Only remove the task + from its current state list if it is in the Ready state as + the task's priority is going to change and there is one + Ready list per priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxPriorityUsedOnEntry ] ), &( pxTCB->xStateListItem ) ) != pdFALSE ) + { + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + /* It is known that the task is in its ready list so + there is no need to check again and the port level + reset macro can be called directly. */ + portRESET_READY_PRIORITY( pxTCB->uxPriority, uxTopReadyPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + prvAddTaskToReadyList( pxTCB ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskEnterCritical( void ) + { + portDISABLE_INTERRUPTS(); + + if( xSchedulerRunning != pdFALSE ) + { + ( pxCurrentTCB->uxCriticalNesting )++; + + /* This is not the interrupt safe version of the enter critical + function so assert() if it is being called from an interrupt + context. Only API functions that end in "FromISR" can be used in an + interrupt. Only assert if the critical nesting count is 1 to + protect against recursive calls if the assert function also uses a + critical section. */ + if( pxCurrentTCB->uxCriticalNesting == 1 ) + { + portASSERT_IF_IN_ISR(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* portCRITICAL_NESTING_IN_TCB */ +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskExitCritical( void ) + { + if( xSchedulerRunning != pdFALSE ) + { + if( pxCurrentTCB->uxCriticalNesting > 0U ) + { + ( pxCurrentTCB->uxCriticalNesting )--; + + if( pxCurrentTCB->uxCriticalNesting == 0U ) + { + portENABLE_INTERRUPTS(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* portCRITICAL_NESTING_IN_TCB */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) ) + + static char *prvWriteNameToBuffer( char *pcBuffer, const char *pcTaskName ) + { + size_t x; + + /* Start by copying the entire string. */ + strcpy( pcBuffer, pcTaskName ); + + /* Pad the end of the string with spaces to ensure columns line up when + printed out. */ + for( x = strlen( pcBuffer ); x < ( size_t ) ( configMAX_TASK_NAME_LEN - 1 ); x++ ) + { + pcBuffer[ x ] = ' '; + } + + /* Terminate. */ + pcBuffer[ x ] = ( char ) 0x00; + + /* Return the new end of string. */ + return &( pcBuffer[ x ] ); + } + +#endif /* ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + void vTaskList( char * pcWriteBuffer ) + { + TaskStatus_t *pxTaskStatusArray; + UBaseType_t uxArraySize, x; + char cStatus; + + /* + * PLEASE NOTE: + * + * This function is provided for convenience only, and is used by many + * of the demo applications. Do not consider it to be part of the + * scheduler. + * + * vTaskList() calls uxTaskGetSystemState(), then formats part of the + * uxTaskGetSystemState() output into a human readable table that + * displays task names, states and stack usage. + * + * vTaskList() has a dependency on the sprintf() C library function that + * might bloat the code size, use a lot of stack, and provide different + * results on different platforms. An alternative, tiny, third party, + * and limited functionality implementation of sprintf() is provided in + * many of the FreeRTOS/Demo sub-directories in a file called + * printf-stdarg.c (note printf-stdarg.c does not provide a full + * snprintf() implementation!). + * + * It is recommended that production systems call uxTaskGetSystemState() + * directly to get access to raw stats data, rather than indirectly + * through a call to vTaskList(). + */ + + + /* Make sure the write buffer does not contain a string. */ + *pcWriteBuffer = ( char ) 0x00; + + /* Take a snapshot of the number of tasks in case it changes while this + function is executing. */ + uxArraySize = uxCurrentNumberOfTasks; + + /* Allocate an array index for each task. NOTE! if + configSUPPORT_DYNAMIC_ALLOCATION is set to 0 then pvPortMalloc() will + equate to NULL. */ + pxTaskStatusArray = pvPortMalloc( uxCurrentNumberOfTasks * sizeof( TaskStatus_t ) ); /*lint !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack and this allocation allocates a struct that has the alignment requirements of a pointer. */ + + if( pxTaskStatusArray != NULL ) + { + /* Generate the (binary) data. */ + uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, NULL ); + + /* Create a human readable table from the binary data. */ + for( x = 0; x < uxArraySize; x++ ) + { + switch( pxTaskStatusArray[ x ].eCurrentState ) + { + case eRunning: cStatus = tskRUNNING_CHAR; + break; + + case eReady: cStatus = tskREADY_CHAR; + break; + + case eBlocked: cStatus = tskBLOCKED_CHAR; + break; + + case eSuspended: cStatus = tskSUSPENDED_CHAR; + break; + + case eDeleted: cStatus = tskDELETED_CHAR; + break; + + case eInvalid: /* Fall through. */ + default: /* Should not get here, but it is included + to prevent static checking errors. */ + cStatus = ( char ) 0x00; + break; + } + + /* Write the task name to the string, padding with spaces so it + can be printed in tabular form more easily. */ + pcWriteBuffer = prvWriteNameToBuffer( pcWriteBuffer, pxTaskStatusArray[ x ].pcTaskName ); + + /* Write the rest of the string. */ + sprintf( pcWriteBuffer, "\t%c\t%u\t%u\t%u\r\n", cStatus, ( unsigned int ) pxTaskStatusArray[ x ].uxCurrentPriority, ( unsigned int ) pxTaskStatusArray[ x ].usStackHighWaterMark, ( unsigned int ) pxTaskStatusArray[ x ].xTaskNumber ); /*lint !e586 sprintf() allowed as this is compiled with many compilers and this is a utility function only - not part of the core kernel implementation. */ + pcWriteBuffer += strlen( pcWriteBuffer ); /*lint !e9016 Pointer arithmetic ok on char pointers especially as in this case where it best denotes the intent of the code. */ + } + + /* Free the array again. NOTE! If configSUPPORT_DYNAMIC_ALLOCATION + is 0 then vPortFree() will be #defined to nothing. */ + vPortFree( pxTaskStatusArray ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) */ +/*----------------------------------------------------------*/ + +#if ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + void vTaskGetRunTimeStats( char *pcWriteBuffer ) + { + TaskStatus_t *pxTaskStatusArray; + UBaseType_t uxArraySize, x; + uint32_t ulTotalTime, ulStatsAsPercentage; + + #if( configUSE_TRACE_FACILITY != 1 ) + { + #error configUSE_TRACE_FACILITY must also be set to 1 in FreeRTOSConfig.h to use vTaskGetRunTimeStats(). + } + #endif + + /* + * PLEASE NOTE: + * + * This function is provided for convenience only, and is used by many + * of the demo applications. Do not consider it to be part of the + * scheduler. + * + * vTaskGetRunTimeStats() calls uxTaskGetSystemState(), then formats part + * of the uxTaskGetSystemState() output into a human readable table that + * displays the amount of time each task has spent in the Running state + * in both absolute and percentage terms. + * + * vTaskGetRunTimeStats() has a dependency on the sprintf() C library + * function that might bloat the code size, use a lot of stack, and + * provide different results on different platforms. An alternative, + * tiny, third party, and limited functionality implementation of + * sprintf() is provided in many of the FreeRTOS/Demo sub-directories in + * a file called printf-stdarg.c (note printf-stdarg.c does not provide + * a full snprintf() implementation!). + * + * It is recommended that production systems call uxTaskGetSystemState() + * directly to get access to raw stats data, rather than indirectly + * through a call to vTaskGetRunTimeStats(). + */ + + /* Make sure the write buffer does not contain a string. */ + *pcWriteBuffer = ( char ) 0x00; + + /* Take a snapshot of the number of tasks in case it changes while this + function is executing. */ + uxArraySize = uxCurrentNumberOfTasks; + + /* Allocate an array index for each task. NOTE! If + configSUPPORT_DYNAMIC_ALLOCATION is set to 0 then pvPortMalloc() will + equate to NULL. */ + pxTaskStatusArray = pvPortMalloc( uxCurrentNumberOfTasks * sizeof( TaskStatus_t ) ); /*lint !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack and this allocation allocates a struct that has the alignment requirements of a pointer. */ + + if( pxTaskStatusArray != NULL ) + { + /* Generate the (binary) data. */ + uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, &ulTotalTime ); + + /* For percentage calculations. */ + ulTotalTime /= 100UL; + + /* Avoid divide by zero errors. */ + if( ulTotalTime > 0UL ) + { + /* Create a human readable table from the binary data. */ + for( x = 0; x < uxArraySize; x++ ) + { + /* What percentage of the total run time has the task used? + This will always be rounded down to the nearest integer. + ulTotalRunTimeDiv100 has already been divided by 100. */ + ulStatsAsPercentage = pxTaskStatusArray[ x ].ulRunTimeCounter / ulTotalTime; + + /* Write the task name to the string, padding with + spaces so it can be printed in tabular form more + easily. */ + pcWriteBuffer = prvWriteNameToBuffer( pcWriteBuffer, pxTaskStatusArray[ x ].pcTaskName ); + + if( ulStatsAsPercentage > 0UL ) + { + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcWriteBuffer, "\t%lu\t\t%lu%%\r\n", pxTaskStatusArray[ x ].ulRunTimeCounter, ulStatsAsPercentage ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcWriteBuffer, "\t%u\t\t%u%%\r\n", ( unsigned int ) pxTaskStatusArray[ x ].ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); /*lint !e586 sprintf() allowed as this is compiled with many compilers and this is a utility function only - not part of the core kernel implementation. */ + } + #endif + } + else + { + /* If the percentage is zero here then the task has + consumed less than 1% of the total run time. */ + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcWriteBuffer, "\t%lu\t\t<1%%\r\n", pxTaskStatusArray[ x ].ulRunTimeCounter ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcWriteBuffer, "\t%u\t\t<1%%\r\n", ( unsigned int ) pxTaskStatusArray[ x ].ulRunTimeCounter ); /*lint !e586 sprintf() allowed as this is compiled with many compilers and this is a utility function only - not part of the core kernel implementation. */ + } + #endif + } + + pcWriteBuffer += strlen( pcWriteBuffer ); /*lint !e9016 Pointer arithmetic ok on char pointers especially as in this case where it best denotes the intent of the code. */ + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Free the array again. NOTE! If configSUPPORT_DYNAMIC_ALLOCATION + is 0 then vPortFree() will be #defined to nothing. */ + vPortFree( pxTaskStatusArray ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) */ +/*-----------------------------------------------------------*/ + +TickType_t uxTaskResetEventItemValue( void ) +{ +TickType_t uxReturn; + + uxReturn = listGET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ) ); + + /* Reset the event list item to its normal value - so it can be used with + queues and semaphores. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ), ( ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxCurrentTCB->uxPriority ) ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + TaskHandle_t pvTaskIncrementMutexHeldCount( void ) + { + /* If xSemaphoreCreateMutex() is called before any tasks have been created + then pxCurrentTCB will be NULL. */ + if( pxCurrentTCB != NULL ) + { + ( pxCurrentTCB->uxMutexesHeld )++; + } + + return pxCurrentTCB; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait ) + { + uint32_t ulReturn; + + taskENTER_CRITICAL(); + { + /* Only block if the notification count is not already non-zero. */ + if( pxCurrentTCB->ulNotifiedValue == 0UL ) + { + /* Mark this task as waiting for a notification. */ + pxCurrentTCB->ucNotifyState = taskWAITING_NOTIFICATION; + + if( xTicksToWait > ( TickType_t ) 0 ) + { + prvAddCurrentTaskToDelayedList( xTicksToWait, pdTRUE ); + traceTASK_NOTIFY_TAKE_BLOCK(); + + /* All ports are written to allow a yield in a critical + section (some will yield immediately, others wait until the + critical section exits) - but it is not something that + application code should ever do. */ + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + traceTASK_NOTIFY_TAKE(); + ulReturn = pxCurrentTCB->ulNotifiedValue; + + if( ulReturn != 0UL ) + { + if( xClearCountOnExit != pdFALSE ) + { + pxCurrentTCB->ulNotifiedValue = 0UL; + } + else + { + pxCurrentTCB->ulNotifiedValue = ulReturn - ( uint32_t ) 1; + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + pxCurrentTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + } + taskEXIT_CRITICAL(); + + return ulReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait ) + { + BaseType_t xReturn; + + taskENTER_CRITICAL(); + { + /* Only block if a notification is not already pending. */ + if( pxCurrentTCB->ucNotifyState != taskNOTIFICATION_RECEIVED ) + { + /* Clear bits in the task's notification value as bits may get + set by the notifying task or interrupt. This can be used to + clear the value to zero. */ + pxCurrentTCB->ulNotifiedValue &= ~ulBitsToClearOnEntry; + + /* Mark this task as waiting for a notification. */ + pxCurrentTCB->ucNotifyState = taskWAITING_NOTIFICATION; + + if( xTicksToWait > ( TickType_t ) 0 ) + { + prvAddCurrentTaskToDelayedList( xTicksToWait, pdTRUE ); + traceTASK_NOTIFY_WAIT_BLOCK(); + + /* All ports are written to allow a yield in a critical + section (some will yield immediately, others wait until the + critical section exits) - but it is not something that + application code should ever do. */ + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + traceTASK_NOTIFY_WAIT(); + + if( pulNotificationValue != NULL ) + { + /* Output the current notification value, which may or may not + have changed. */ + *pulNotificationValue = pxCurrentTCB->ulNotifiedValue; + } + + /* If ucNotifyValue is set then either the task never entered the + blocked state (because a notification was already pending) or the + task unblocked because of a notification. Otherwise the task + unblocked because of a timeout. */ + if( pxCurrentTCB->ucNotifyState != taskNOTIFICATION_RECEIVED ) + { + /* A notification was not received. */ + xReturn = pdFALSE; + } + else + { + /* A notification was already pending or a notification was + received while the task was waiting. */ + pxCurrentTCB->ulNotifiedValue &= ~ulBitsToClearOnExit; + xReturn = pdTRUE; + } + + pxCurrentTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + BaseType_t xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue ) + { + TCB_t * pxTCB; + BaseType_t xReturn = pdPASS; + uint8_t ucOriginalNotifyState; + + configASSERT( xTaskToNotify ); + pxTCB = xTaskToNotify; + + taskENTER_CRITICAL(); + { + if( pulPreviousNotificationValue != NULL ) + { + *pulPreviousNotificationValue = pxTCB->ulNotifiedValue; + } + + ucOriginalNotifyState = pxTCB->ucNotifyState; + + pxTCB->ucNotifyState = taskNOTIFICATION_RECEIVED; + + switch( eAction ) + { + case eSetBits : + pxTCB->ulNotifiedValue |= ulValue; + break; + + case eIncrement : + ( pxTCB->ulNotifiedValue )++; + break; + + case eSetValueWithOverwrite : + pxTCB->ulNotifiedValue = ulValue; + break; + + case eSetValueWithoutOverwrite : + if( ucOriginalNotifyState != taskNOTIFICATION_RECEIVED ) + { + pxTCB->ulNotifiedValue = ulValue; + } + else + { + /* The value could not be written to the task. */ + xReturn = pdFAIL; + } + break; + + case eNoAction: + /* The task is being notified without its notify value being + updated. */ + break; + + default: + /* Should not get here if all enums are handled. + Artificially force an assert by testing a value the + compiler can't assume is const. */ + configASSERT( pxTCB->ulNotifiedValue == ~0UL ); + + break; + } + + traceTASK_NOTIFY(); + + /* If the task is in the blocked state specifically to wait for a + notification then unblock it now. */ + if( ucOriginalNotifyState == taskWAITING_NOTIFICATION ) + { + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + + /* The task should not have been on an event list. */ + configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL ); + + #if( configUSE_TICKLESS_IDLE != 0 ) + { + /* If a task is blocked waiting for a notification then + xNextTaskUnblockTime might be set to the blocked task's time + out time. If the task is unblocked for a reason other than + a timeout xNextTaskUnblockTime is normally left unchanged, + because it will automatically get reset to a new value when + the tick count equals xNextTaskUnblockTime. However if + tickless idling is used it might be more important to enter + sleep mode at the earliest possible time - so reset + xNextTaskUnblockTime here to ensure it is updated at the + earliest possible time. */ + prvResetNextTaskUnblockTime(); + } + #endif + + if( pxTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* The notified task has a priority above the currently + executing task so a yield is required. */ + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + BaseType_t xTaskGenericNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue, BaseType_t *pxHigherPriorityTaskWoken ) + { + TCB_t * pxTCB; + uint8_t ucOriginalNotifyState; + BaseType_t xReturn = pdPASS; + UBaseType_t uxSavedInterruptStatus; + + configASSERT( xTaskToNotify ); + + /* RTOS ports that support interrupt nesting have the concept of a + maximum system call (or maximum API call) interrupt priority. + Interrupts that are above the maximum system call priority are keep + permanently enabled, even when the RTOS kernel is in a critical section, + but cannot make any calls to FreeRTOS API functions. If configASSERT() + is defined in FreeRTOSConfig.h then + portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has + been assigned a priority above the configured maximum system call + priority. Only FreeRTOS functions that end in FromISR can be called + from interrupts that have been assigned a priority at or (logically) + below the maximum system call interrupt priority. FreeRTOS maintains a + separate interrupt safe API to ensure interrupt entry is as fast and as + simple as possible. More information (albeit Cortex-M specific) is + provided on the following link: + http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + pxTCB = xTaskToNotify; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( pulPreviousNotificationValue != NULL ) + { + *pulPreviousNotificationValue = pxTCB->ulNotifiedValue; + } + + ucOriginalNotifyState = pxTCB->ucNotifyState; + pxTCB->ucNotifyState = taskNOTIFICATION_RECEIVED; + + switch( eAction ) + { + case eSetBits : + pxTCB->ulNotifiedValue |= ulValue; + break; + + case eIncrement : + ( pxTCB->ulNotifiedValue )++; + break; + + case eSetValueWithOverwrite : + pxTCB->ulNotifiedValue = ulValue; + break; + + case eSetValueWithoutOverwrite : + if( ucOriginalNotifyState != taskNOTIFICATION_RECEIVED ) + { + pxTCB->ulNotifiedValue = ulValue; + } + else + { + /* The value could not be written to the task. */ + xReturn = pdFAIL; + } + break; + + case eNoAction : + /* The task is being notified without its notify value being + updated. */ + break; + + default: + /* Should not get here if all enums are handled. + Artificially force an assert by testing a value the + compiler can't assume is const. */ + configASSERT( pxTCB->ulNotifiedValue == ~0UL ); + break; + } + + traceTASK_NOTIFY_FROM_ISR(); + + /* If the task is in the blocked state specifically to wait for a + notification then unblock it now. */ + if( ucOriginalNotifyState == taskWAITING_NOTIFICATION ) + { + /* The task should not have been on an event list. */ + configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL ); + + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + } + else + { + /* The delayed and ready lists cannot be accessed, so hold + this task pending until the scheduler is resumed. */ + vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + + if( pxTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* The notified task has a priority above the currently + executing task so a yield is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + + /* Mark that a yield is pending in case the user is not + using the "xHigherPriorityTaskWoken" parameter to an ISR + safe FreeRTOS function. */ + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + void vTaskNotifyGiveFromISR( TaskHandle_t xTaskToNotify, BaseType_t *pxHigherPriorityTaskWoken ) + { + TCB_t * pxTCB; + uint8_t ucOriginalNotifyState; + UBaseType_t uxSavedInterruptStatus; + + configASSERT( xTaskToNotify ); + + /* RTOS ports that support interrupt nesting have the concept of a + maximum system call (or maximum API call) interrupt priority. + Interrupts that are above the maximum system call priority are keep + permanently enabled, even when the RTOS kernel is in a critical section, + but cannot make any calls to FreeRTOS API functions. If configASSERT() + is defined in FreeRTOSConfig.h then + portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has + been assigned a priority above the configured maximum system call + priority. Only FreeRTOS functions that end in FromISR can be called + from interrupts that have been assigned a priority at or (logically) + below the maximum system call interrupt priority. FreeRTOS maintains a + separate interrupt safe API to ensure interrupt entry is as fast and as + simple as possible. More information (albeit Cortex-M specific) is + provided on the following link: + http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + pxTCB = xTaskToNotify; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + ucOriginalNotifyState = pxTCB->ucNotifyState; + pxTCB->ucNotifyState = taskNOTIFICATION_RECEIVED; + + /* 'Giving' is equivalent to incrementing a count in a counting + semaphore. */ + ( pxTCB->ulNotifiedValue )++; + + traceTASK_NOTIFY_GIVE_FROM_ISR(); + + /* If the task is in the blocked state specifically to wait for a + notification then unblock it now. */ + if( ucOriginalNotifyState == taskWAITING_NOTIFICATION ) + { + /* The task should not have been on an event list. */ + configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL ); + + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + } + else + { + /* The delayed and ready lists cannot be accessed, so hold + this task pending until the scheduler is resumed. */ + vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + + if( pxTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* The notified task has a priority above the currently + executing task so a yield is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + + /* Mark that a yield is pending in case the user is not + using the "xHigherPriorityTaskWoken" parameter in an ISR + safe FreeRTOS function. */ + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + BaseType_t xReturn; + + /* If null is passed in here then it is the calling task that is having + its notification state cleared. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + taskENTER_CRITICAL(); + { + if( pxTCB->ucNotifyState == taskNOTIFICATION_RECEIVED ) + { + pxTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + uint32_t ulTaskNotifyValueClear( TaskHandle_t xTask, uint32_t ulBitsToClear ) + { + TCB_t *pxTCB; + uint32_t ulReturn; + + /* If null is passed in here then it is the calling task that is having + its notification state cleared. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + taskENTER_CRITICAL(); + { + /* Return the notification as it was before the bits were cleared, + then clear the bit mask. */ + ulReturn = pxCurrentTCB->ulNotifiedValue; + pxTCB->ulNotifiedValue &= ~ulBitsToClear; + } + taskEXIT_CRITICAL(); + + return ulReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) ) + + uint32_t ulTaskGetIdleRunTimeCounter( void ) + { + return xIdleTaskHandle->ulRunTimeCounter; + } + +#endif +/*-----------------------------------------------------------*/ + +static void prvAddCurrentTaskToDelayedList( TickType_t xTicksToWait, const BaseType_t xCanBlockIndefinitely ) +{ +TickType_t xTimeToWake; +const TickType_t xConstTickCount = xTickCount; + + #if( INCLUDE_xTaskAbortDelay == 1 ) + { + /* About to enter a delayed list, so ensure the ucDelayAborted flag is + reset to pdFALSE so it can be detected as having been set to pdTRUE + when the task leaves the Blocked state. */ + pxCurrentTCB->ucDelayAborted = pdFALSE; + } + #endif + + /* Remove the task from the ready list before adding it to the blocked list + as the same list item is used for both lists. */ + if( uxListRemove( &( pxCurrentTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + /* The current task must be in a ready list, so there is no need to + check, and the port reset macro can be called directly. */ + portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority ); /*lint !e931 pxCurrentTCB cannot change as it is the calling task. pxCurrentTCB->uxPriority and uxTopReadyPriority cannot change as called with scheduler suspended or in a critical section. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( ( xTicksToWait == portMAX_DELAY ) && ( xCanBlockIndefinitely != pdFALSE ) ) + { + /* Add the task to the suspended task list instead of a delayed task + list to ensure it is not woken by a timing event. It will block + indefinitely. */ + vListInsertEnd( &xSuspendedTaskList, &( pxCurrentTCB->xStateListItem ) ); + } + else + { + /* Calculate the time at which the task should be woken if the event + does not occur. This may overflow but this doesn't matter, the + kernel will manage it correctly. */ + xTimeToWake = xConstTickCount + xTicksToWait; + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xStateListItem ), xTimeToWake ); + + if( xTimeToWake < xConstTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow + list. */ + vListInsert( pxOverflowDelayedTaskList, &( pxCurrentTCB->xStateListItem ) ); + } + else + { + /* The wake time has not overflowed, so the current block list + is used. */ + vListInsert( pxDelayedTaskList, &( pxCurrentTCB->xStateListItem ) ); + + /* If the task entering the blocked state was placed at the + head of the list of blocked tasks then xNextTaskUnblockTime + needs to be updated too. */ + if( xTimeToWake < xNextTaskUnblockTime ) + { + xNextTaskUnblockTime = xTimeToWake; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + } + #else /* INCLUDE_vTaskSuspend */ + { + /* Calculate the time at which the task should be woken if the event + does not occur. This may overflow but this doesn't matter, the kernel + will manage it correctly. */ + xTimeToWake = xConstTickCount + xTicksToWait; + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xStateListItem ), xTimeToWake ); + + if( xTimeToWake < xConstTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow list. */ + vListInsert( pxOverflowDelayedTaskList, &( pxCurrentTCB->xStateListItem ) ); + } + else + { + /* The wake time has not overflowed, so the current block list is used. */ + vListInsert( pxDelayedTaskList, &( pxCurrentTCB->xStateListItem ) ); + + /* If the task entering the blocked state was placed at the head of the + list of blocked tasks then xNextTaskUnblockTime needs to be updated + too. */ + if( xTimeToWake < xNextTaskUnblockTime ) + { + xNextTaskUnblockTime = xTimeToWake; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + /* Avoid compiler warning when INCLUDE_vTaskSuspend is not 1. */ + ( void ) xCanBlockIndefinitely; + } + #endif /* INCLUDE_vTaskSuspend */ +} + +/* Code below here allows additional code to be inserted into this source file, +especially where access to file scope functions and data is needed (for example +when performing module tests). */ + +#ifdef FREERTOS_MODULE_TEST + #include "tasks_test_access_functions.h" +#endif + + +#if( configINCLUDE_FREERTOS_TASK_C_ADDITIONS_H == 1 ) + + #include "freertos_tasks_c_additions.h" + + #ifdef FREERTOS_TASKS_C_ADDITIONS_INIT + static void freertos_tasks_c_additions_init( void ) + { + FREERTOS_TASKS_C_ADDITIONS_INIT(); + } + #endif + +#endif + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/timers.c b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/timers.c new file mode 100644 index 0000000..6d1a28f --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/middlewares/FreeRTOS-10.3.1/timers.c @@ -0,0 +1,1127 @@ +/* + * FreeRTOS Kernel V10.3.1 + * Copyright (c) 2020 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! + */ + +/* Standard includes. */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "timers.h" + +#if ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 0 ) + #error configUSE_TIMERS must be set to 1 to make the xTimerPendFunctionCall() function available. +#endif + +/* Lint e9021, e961 and e750 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e9021 !e961 !e750. */ + + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. This #if is closed at the very bottom +of this file. If you want to include software timer functionality then ensure +configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#if ( configUSE_TIMERS == 1 ) + +/* Misc definitions. */ +#define tmrNO_DELAY ( TickType_t ) 0U + +/* The name assigned to the timer service task. This can be overridden by +defining trmTIMER_SERVICE_TASK_NAME in FreeRTOSConfig.h. */ +#ifndef configTIMER_SERVICE_TASK_NAME + #define configTIMER_SERVICE_TASK_NAME "Tmr Svc" +#endif + +/* Bit definitions used in the ucStatus member of a timer structure. */ +#define tmrSTATUS_IS_ACTIVE ( ( uint8_t ) 0x01 ) +#define tmrSTATUS_IS_STATICALLY_ALLOCATED ( ( uint8_t ) 0x02 ) +#define tmrSTATUS_IS_AUTORELOAD ( ( uint8_t ) 0x04 ) + +/* The definition of the timers themselves. */ +typedef struct tmrTimerControl /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +{ + const char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + ListItem_t xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ + TickType_t xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ + void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ + TimerCallbackFunction_t pxCallbackFunction; /*<< The function that will be called when the timer expires. */ + #if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxTimerNumber; /*<< An ID assigned by trace tools such as FreeRTOS+Trace */ + #endif + uint8_t ucStatus; /*<< Holds bits to say if the timer was statically allocated or not, and if it is active or not. */ +} xTIMER; + +/* The old xTIMER name is maintained above then typedefed to the new Timer_t +name below to enable the use of older kernel aware debuggers. */ +typedef xTIMER Timer_t; + +/* The definition of messages that can be sent and received on the timer queue. +Two types of message can be queued - messages that manipulate a software timer, +and messages that request the execution of a non-timer related callback. The +two message types are defined in two separate structures, xTimerParametersType +and xCallbackParametersType respectively. */ +typedef struct tmrTimerParameters +{ + TickType_t xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ + Timer_t * pxTimer; /*<< The timer to which the command will be applied. */ +} TimerParameter_t; + + +typedef struct tmrCallbackParameters +{ + PendedFunction_t pxCallbackFunction; /* << The callback function to execute. */ + void *pvParameter1; /* << The value that will be used as the callback functions first parameter. */ + uint32_t ulParameter2; /* << The value that will be used as the callback functions second parameter. */ +} CallbackParameters_t; + +/* The structure that contains the two message types, along with an identifier +that is used to determine which message type is valid. */ +typedef struct tmrTimerQueueMessage +{ + BaseType_t xMessageID; /*<< The command being sent to the timer service task. */ + union + { + TimerParameter_t xTimerParameters; + + /* Don't include xCallbackParameters if it is not going to be used as + it makes the structure (and therefore the timer queue) larger. */ + #if ( INCLUDE_xTimerPendFunctionCall == 1 ) + CallbackParameters_t xCallbackParameters; + #endif /* INCLUDE_xTimerPendFunctionCall */ + } u; +} DaemonTaskMessage_t; + +/*lint -save -e956 A manual analysis and inspection has been used to determine +which static variables must be declared volatile. */ + +/* The list in which active timers are stored. Timers are referenced in expire +time order, with the nearest expiry time at the front of the list. Only the +timer service task is allowed to access these lists. +xActiveTimerList1 and xActiveTimerList2 could be at function scope but that +breaks some kernel aware debuggers, and debuggers that reply on removing the +static qualifier. */ +PRIVILEGED_DATA static List_t xActiveTimerList1; +PRIVILEGED_DATA static List_t xActiveTimerList2; +PRIVILEGED_DATA static List_t *pxCurrentTimerList; +PRIVILEGED_DATA static List_t *pxOverflowTimerList; + +/* A queue that is used to send commands to the timer service task. */ +PRIVILEGED_DATA static QueueHandle_t xTimerQueue = NULL; +PRIVILEGED_DATA static TaskHandle_t xTimerTaskHandle = NULL; + +/*lint -restore */ + +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + /* If static allocation is supported then the application must provide the + following callback function - which enables the application to optionally + provide the memory that will be used by the timer task as the task's stack + and TCB. */ + extern void vApplicationGetTimerTaskMemory( StaticTask_t **ppxTimerTaskTCBBuffer, StackType_t **ppxTimerTaskStackBuffer, uint32_t *pulTimerTaskStackSize ); + +#endif + +/* + * Initialise the infrastructure used by the timer service task if it has not + * been initialised already. + */ +static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; + +/* + * The timer service task (daemon). Timer functionality is controlled by this + * task. Other tasks communicate with the timer service task using the + * xTimerQueue queue. + */ +static portTASK_FUNCTION_PROTO( prvTimerTask, pvParameters ) PRIVILEGED_FUNCTION; + +/* + * Called by the timer service task to interpret and process a command it + * received on the timer queue. + */ +static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; + +/* + * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, + * depending on if the expire time causes a timer counter overflow. + */ +static BaseType_t prvInsertTimerInActiveList( Timer_t * const pxTimer, const TickType_t xNextExpiryTime, const TickType_t xTimeNow, const TickType_t xCommandTime ) PRIVILEGED_FUNCTION; + +/* + * An active timer has reached its expire time. Reload the timer if it is an + * auto-reload timer, then call its callback. + */ +static void prvProcessExpiredTimer( const TickType_t xNextExpireTime, const TickType_t xTimeNow ) PRIVILEGED_FUNCTION; + +/* + * The tick count has overflowed. Switch the timer lists after ensuring the + * current timer list does not still reference some timers. + */ +static void prvSwitchTimerLists( void ) PRIVILEGED_FUNCTION; + +/* + * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE + * if a tick count overflow occurred since prvSampleTimeNow() was last called. + */ +static TickType_t prvSampleTimeNow( BaseType_t * const pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; + +/* + * If the timer list contains any active timers then return the expire time of + * the timer that will expire first and set *pxListWasEmpty to false. If the + * timer list does not contain any timers then return 0 and set *pxListWasEmpty + * to pdTRUE. + */ +static TickType_t prvGetNextExpireTime( BaseType_t * const pxListWasEmpty ) PRIVILEGED_FUNCTION; + +/* + * If a timer has expired, process it. Otherwise, block the timer service task + * until either a timer does expire or a command is received. + */ +static void prvProcessTimerOrBlockTask( const TickType_t xNextExpireTime, BaseType_t xListWasEmpty ) PRIVILEGED_FUNCTION; + +/* + * Called after a Timer_t structure has been allocated either statically or + * dynamically to fill in the structure's members. + */ +static void prvInitialiseNewTimer( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction, + Timer_t *pxNewTimer ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +BaseType_t xTimerCreateTimerTask( void ) +{ +BaseType_t xReturn = pdFAIL; + + /* This function is called when the scheduler is started if + configUSE_TIMERS is set to 1. Check that the infrastructure used by the + timer service task has been created/initialised. If timers have already + been created then the initialisation will already have been performed. */ + prvCheckForValidListAndQueue(); + + if( xTimerQueue != NULL ) + { + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + StaticTask_t *pxTimerTaskTCBBuffer = NULL; + StackType_t *pxTimerTaskStackBuffer = NULL; + uint32_t ulTimerTaskStackSize; + + vApplicationGetTimerTaskMemory( &pxTimerTaskTCBBuffer, &pxTimerTaskStackBuffer, &ulTimerTaskStackSize ); + xTimerTaskHandle = xTaskCreateStatic( prvTimerTask, + configTIMER_SERVICE_TASK_NAME, + ulTimerTaskStackSize, + NULL, + ( ( UBaseType_t ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, + pxTimerTaskStackBuffer, + pxTimerTaskTCBBuffer ); + + if( xTimerTaskHandle != NULL ) + { + xReturn = pdPASS; + } + } + #else + { + xReturn = xTaskCreate( prvTimerTask, + configTIMER_SERVICE_TASK_NAME, + configTIMER_TASK_STACK_DEPTH, + NULL, + ( ( UBaseType_t ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, + &xTimerTaskHandle ); + } + #endif /* configSUPPORT_STATIC_ALLOCATION */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + configASSERT( xReturn ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + TimerHandle_t xTimerCreate( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction ) + { + Timer_t *pxNewTimer; + + pxNewTimer = ( Timer_t * ) pvPortMalloc( sizeof( Timer_t ) ); /*lint !e9087 !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack, and the first member of Timer_t is always a pointer to the timer's mame. */ + + if( pxNewTimer != NULL ) + { + /* Status is thus far zero as the timer is not created statically + and has not been started. The auto-reload bit may get set in + prvInitialiseNewTimer. */ + pxNewTimer->ucStatus = 0x00; + prvInitialiseNewTimer( pcTimerName, xTimerPeriodInTicks, uxAutoReload, pvTimerID, pxCallbackFunction, pxNewTimer ); + } + + return pxNewTimer; + } + +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + TimerHandle_t xTimerCreateStatic( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction, + StaticTimer_t *pxTimerBuffer ) + { + Timer_t *pxNewTimer; + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticTimer_t equals the size of the real timer + structure. */ + volatile size_t xSize = sizeof( StaticTimer_t ); + configASSERT( xSize == sizeof( Timer_t ) ); + ( void ) xSize; /* Keeps lint quiet when configASSERT() is not defined. */ + } + #endif /* configASSERT_DEFINED */ + + /* A pointer to a StaticTimer_t structure MUST be provided, use it. */ + configASSERT( pxTimerBuffer ); + pxNewTimer = ( Timer_t * ) pxTimerBuffer; /*lint !e740 !e9087 StaticTimer_t is a pointer to a Timer_t, so guaranteed to be aligned and sized correctly (checked by an assert()), so this is safe. */ + + if( pxNewTimer != NULL ) + { + /* Timers can be created statically or dynamically so note this + timer was created statically in case it is later deleted. The + auto-reload bit may get set in prvInitialiseNewTimer(). */ + pxNewTimer->ucStatus = tmrSTATUS_IS_STATICALLY_ALLOCATED; + + prvInitialiseNewTimer( pcTimerName, xTimerPeriodInTicks, uxAutoReload, pvTimerID, pxCallbackFunction, pxNewTimer ); + } + + return pxNewTimer; + } + +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +static void prvInitialiseNewTimer( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction, + Timer_t *pxNewTimer ) +{ + /* 0 is not a valid value for xTimerPeriodInTicks. */ + configASSERT( ( xTimerPeriodInTicks > 0 ) ); + + if( pxNewTimer != NULL ) + { + /* Ensure the infrastructure used by the timer service task has been + created/initialised. */ + prvCheckForValidListAndQueue(); + + /* Initialise the timer structure members using the function + parameters. */ + pxNewTimer->pcTimerName = pcTimerName; + pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; + pxNewTimer->pvTimerID = pvTimerID; + pxNewTimer->pxCallbackFunction = pxCallbackFunction; + vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); + if( uxAutoReload != pdFALSE ) + { + pxNewTimer->ucStatus |= tmrSTATUS_IS_AUTORELOAD; + } + traceTIMER_CREATE( pxNewTimer ); + } +} +/*-----------------------------------------------------------*/ + +BaseType_t xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait ) +{ +BaseType_t xReturn = pdFAIL; +DaemonTaskMessage_t xMessage; + + configASSERT( xTimer ); + + /* Send a message to the timer service task to perform a particular action + on a particular timer definition. */ + if( xTimerQueue != NULL ) + { + /* Send a command to the timer service task to start the xTimer timer. */ + xMessage.xMessageID = xCommandID; + xMessage.u.xTimerParameters.xMessageValue = xOptionalValue; + xMessage.u.xTimerParameters.pxTimer = xTimer; + + if( xCommandID < tmrFIRST_FROM_ISR_COMMAND ) + { + if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xTicksToWait ); + } + else + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); + } + } + else + { + xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); + } + + traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +TaskHandle_t xTimerGetTimerDaemonTaskHandle( void ) +{ + /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been + started, then xTimerTaskHandle will be NULL. */ + configASSERT( ( xTimerTaskHandle != NULL ) ); + return xTimerTaskHandle; +} +/*-----------------------------------------------------------*/ + +TickType_t xTimerGetPeriod( TimerHandle_t xTimer ) +{ +Timer_t *pxTimer = xTimer; + + configASSERT( xTimer ); + return pxTimer->xTimerPeriodInTicks; +} +/*-----------------------------------------------------------*/ + +void vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ) +{ +Timer_t * pxTimer = xTimer; + + configASSERT( xTimer ); + taskENTER_CRITICAL(); + { + if( uxAutoReload != pdFALSE ) + { + pxTimer->ucStatus |= tmrSTATUS_IS_AUTORELOAD; + } + else + { + pxTimer->ucStatus &= ~tmrSTATUS_IS_AUTORELOAD; + } + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +UBaseType_t uxTimerGetReloadMode( TimerHandle_t xTimer ) +{ +Timer_t * pxTimer = xTimer; +UBaseType_t uxReturn; + + configASSERT( xTimer ); + taskENTER_CRITICAL(); + { + if( ( pxTimer->ucStatus & tmrSTATUS_IS_AUTORELOAD ) == 0 ) + { + /* Not an auto-reload timer. */ + uxReturn = ( UBaseType_t ) pdFALSE; + } + else + { + /* Is an auto-reload timer. */ + uxReturn = ( UBaseType_t ) pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +TickType_t xTimerGetExpiryTime( TimerHandle_t xTimer ) +{ +Timer_t * pxTimer = xTimer; +TickType_t xReturn; + + configASSERT( xTimer ); + xReturn = listGET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ) ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +const char * pcTimerGetName( TimerHandle_t xTimer ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ +{ +Timer_t *pxTimer = xTimer; + + configASSERT( xTimer ); + return pxTimer->pcTimerName; +} +/*-----------------------------------------------------------*/ + +static void prvProcessExpiredTimer( const TickType_t xNextExpireTime, const TickType_t xTimeNow ) +{ +BaseType_t xResult; +Timer_t * const pxTimer = ( Timer_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); /*lint !e9087 !e9079 void * is used as this macro is used with tasks and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + + /* Remove the timer from the list of active timers. A check has already + been performed to ensure the list is not empty. */ + ( void ) uxListRemove( &( pxTimer->xTimerListItem ) ); + traceTIMER_EXPIRED( pxTimer ); + + /* If the timer is an auto-reload timer then calculate the next + expiry time and re-insert the timer in the list of active timers. */ + if( ( pxTimer->ucStatus & tmrSTATUS_IS_AUTORELOAD ) != 0 ) + { + /* The timer is inserted into a list using a time relative to anything + other than the current time. It will therefore be inserted into the + correct list relative to the time this task thinks it is now. */ + if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) != pdFALSE ) + { + /* The timer expired before it was added to the active timer + list. Reload it now. */ + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + pxTimer->ucStatus &= ~tmrSTATUS_IS_ACTIVE; + mtCOVERAGE_TEST_MARKER(); + } + + /* Call the timer callback. */ + pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer ); +} +/*-----------------------------------------------------------*/ + +static portTASK_FUNCTION( prvTimerTask, pvParameters ) +{ +TickType_t xNextExpireTime; +BaseType_t xListWasEmpty; + + /* Just to avoid compiler warnings. */ + ( void ) pvParameters; + + #if( configUSE_DAEMON_TASK_STARTUP_HOOK == 1 ) + { + extern void vApplicationDaemonTaskStartupHook( void ); + + /* Allow the application writer to execute some code in the context of + this task at the point the task starts executing. This is useful if the + application includes initialisation code that would benefit from + executing after the scheduler has been started. */ + vApplicationDaemonTaskStartupHook(); + } + #endif /* configUSE_DAEMON_TASK_STARTUP_HOOK */ + + for( ;; ) + { + /* Query the timers list to see if it contains any timers, and if so, + obtain the time at which the next timer will expire. */ + xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); + + /* If a timer has expired, process it. Otherwise, block this task + until either a timer does expire, or a command is received. */ + prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); + + /* Empty the command queue. */ + prvProcessReceivedCommands(); + } +} +/*-----------------------------------------------------------*/ + +static void prvProcessTimerOrBlockTask( const TickType_t xNextExpireTime, BaseType_t xListWasEmpty ) +{ +TickType_t xTimeNow; +BaseType_t xTimerListsWereSwitched; + + vTaskSuspendAll(); + { + /* Obtain the time now to make an assessment as to whether the timer + has expired or not. If obtaining the time causes the lists to switch + then don't process this timer as any timers that remained in the list + when the lists were switched will have been processed within the + prvSampleTimeNow() function. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + if( xTimerListsWereSwitched == pdFALSE ) + { + /* The tick count has not overflowed, has the timer expired? */ + if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) + { + ( void ) xTaskResumeAll(); + prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); + } + else + { + /* The tick count has not overflowed, and the next expire + time has not been reached yet. This task should therefore + block to wait for the next expire time or a command to be + received - whichever comes first. The following line cannot + be reached unless xNextExpireTime > xTimeNow, except in the + case when the current timer list is empty. */ + if( xListWasEmpty != pdFALSE ) + { + /* The current timer list is empty - is the overflow list + also empty? */ + xListWasEmpty = listLIST_IS_EMPTY( pxOverflowTimerList ); + } + + vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ), xListWasEmpty ); + + if( xTaskResumeAll() == pdFALSE ) + { + /* Yield to wait for either a command to arrive, or the + block time to expire. If a command arrived between the + critical section being exited and this yield then the yield + will not cause the task to block. */ + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + else + { + ( void ) xTaskResumeAll(); + } + } +} +/*-----------------------------------------------------------*/ + +static TickType_t prvGetNextExpireTime( BaseType_t * const pxListWasEmpty ) +{ +TickType_t xNextExpireTime; + + /* Timers are listed in expiry time order, with the head of the list + referencing the task that will expire first. Obtain the time at which + the timer with the nearest expiry time will expire. If there are no + active timers then just set the next expire time to 0. That will cause + this task to unblock when the tick count overflows, at which point the + timer lists will be switched and the next expiry time can be + re-assessed. */ + *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); + if( *pxListWasEmpty == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + } + else + { + /* Ensure the task unblocks when the tick count rolls over. */ + xNextExpireTime = ( TickType_t ) 0U; + } + + return xNextExpireTime; +} +/*-----------------------------------------------------------*/ + +static TickType_t prvSampleTimeNow( BaseType_t * const pxTimerListsWereSwitched ) +{ +TickType_t xTimeNow; +PRIVILEGED_DATA static TickType_t xLastTime = ( TickType_t ) 0U; /*lint !e956 Variable is only accessible to one task. */ + + xTimeNow = xTaskGetTickCount(); + + if( xTimeNow < xLastTime ) + { + prvSwitchTimerLists(); + *pxTimerListsWereSwitched = pdTRUE; + } + else + { + *pxTimerListsWereSwitched = pdFALSE; + } + + xLastTime = xTimeNow; + + return xTimeNow; +} +/*-----------------------------------------------------------*/ + +static BaseType_t prvInsertTimerInActiveList( Timer_t * const pxTimer, const TickType_t xNextExpiryTime, const TickType_t xTimeNow, const TickType_t xCommandTime ) +{ +BaseType_t xProcessTimerNow = pdFALSE; + + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + + if( xNextExpiryTime <= xTimeNow ) + { + /* Has the expiry time elapsed between the command to start/reset a + timer was issued, and the time the command was processed? */ + if( ( ( TickType_t ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + { + /* The time between a command being issued and the command being + processed actually exceeds the timers period. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); + } + } + else + { + if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) + { + /* If, since the command was issued, the tick count has overflowed + but the expiry time has not, then the timer must have already passed + its expiry time and should be processed immediately. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + } + + return xProcessTimerNow; +} +/*-----------------------------------------------------------*/ + +static void prvProcessReceivedCommands( void ) +{ +DaemonTaskMessage_t xMessage; +Timer_t *pxTimer; +BaseType_t xTimerListsWereSwitched, xResult; +TickType_t xTimeNow; + + while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) /*lint !e603 xMessage does not have to be initialised as it is passed out, not in, and it is not used unless xQueueReceive() returns pdTRUE. */ + { + #if ( INCLUDE_xTimerPendFunctionCall == 1 ) + { + /* Negative commands are pended function calls rather than timer + commands. */ + if( xMessage.xMessageID < ( BaseType_t ) 0 ) + { + const CallbackParameters_t * const pxCallback = &( xMessage.u.xCallbackParameters ); + + /* The timer uses the xCallbackParameters member to request a + callback be executed. Check the callback is not NULL. */ + configASSERT( pxCallback ); + + /* Call the function. */ + pxCallback->pxCallbackFunction( pxCallback->pvParameter1, pxCallback->ulParameter2 ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* INCLUDE_xTimerPendFunctionCall */ + + /* Commands that are positive are timer commands rather than pended + function calls. */ + if( xMessage.xMessageID >= ( BaseType_t ) 0 ) + { + /* The messages uses the xTimerParameters member to work on a + software timer. */ + pxTimer = xMessage.u.xTimerParameters.pxTimer; + + if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) /*lint !e961. The cast is only redundant when NULL is passed into the macro. */ + { + /* The timer is in a list, remove it. */ + ( void ) uxListRemove( &( pxTimer->xTimerListItem ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.u.xTimerParameters.xMessageValue ); + + /* In this case the xTimerListsWereSwitched parameter is not used, but + it must be present in the function call. prvSampleTimeNow() must be + called after the message is received from xTimerQueue so there is no + possibility of a higher priority task adding a message to the message + queue with a time that is ahead of the timer daemon task (because it + pre-empted the timer daemon task after the xTimeNow value was set). */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + + switch( xMessage.xMessageID ) + { + case tmrCOMMAND_START : + case tmrCOMMAND_START_FROM_ISR : + case tmrCOMMAND_RESET : + case tmrCOMMAND_RESET_FROM_ISR : + case tmrCOMMAND_START_DONT_TRACE : + /* Start or restart a timer. */ + pxTimer->ucStatus |= tmrSTATUS_IS_ACTIVE; + if( prvInsertTimerInActiveList( pxTimer, xMessage.u.xTimerParameters.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.u.xTimerParameters.xMessageValue ) != pdFALSE ) + { + /* The timer expired before it was added to the active + timer list. Process it now. */ + pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer ); + traceTIMER_EXPIRED( pxTimer ); + + if( ( pxTimer->ucStatus & tmrSTATUS_IS_AUTORELOAD ) != 0 ) + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xMessage.u.xTimerParameters.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + break; + + case tmrCOMMAND_STOP : + case tmrCOMMAND_STOP_FROM_ISR : + /* The timer has already been removed from the active list. */ + pxTimer->ucStatus &= ~tmrSTATUS_IS_ACTIVE; + break; + + case tmrCOMMAND_CHANGE_PERIOD : + case tmrCOMMAND_CHANGE_PERIOD_FROM_ISR : + pxTimer->ucStatus |= tmrSTATUS_IS_ACTIVE; + pxTimer->xTimerPeriodInTicks = xMessage.u.xTimerParameters.xMessageValue; + configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); + + /* The new period does not really have a reference, and can + be longer or shorter than the old one. The command time is + therefore set to the current time, and as the period cannot + be zero the next expiry time can only be in the future, + meaning (unlike for the xTimerStart() case above) there is + no fail case that needs to be handled here. */ + ( void ) prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); + break; + + case tmrCOMMAND_DELETE : + #if ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + { + /* The timer has already been removed from the active list, + just free up the memory if the memory was dynamically + allocated. */ + if( ( pxTimer->ucStatus & tmrSTATUS_IS_STATICALLY_ALLOCATED ) == ( uint8_t ) 0 ) + { + vPortFree( pxTimer ); + } + else + { + pxTimer->ucStatus &= ~tmrSTATUS_IS_ACTIVE; + } + } + #else + { + /* If dynamic allocation is not enabled, the memory + could not have been dynamically allocated. So there is + no need to free the memory - just mark the timer as + "not active". */ + pxTimer->ucStatus &= ~tmrSTATUS_IS_ACTIVE; + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + break; + + default : + /* Don't expect to get here. */ + break; + } + } + } +} +/*-----------------------------------------------------------*/ + +static void prvSwitchTimerLists( void ) +{ +TickType_t xNextExpireTime, xReloadTime; +List_t *pxTemp; +Timer_t *pxTimer; +BaseType_t xResult; + + /* The tick count has overflowed. The timer lists must be switched. + If there are any timers still referenced from the current timer list + then they must have expired and should be processed before the lists + are switched. */ + while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + + /* Remove the timer from the list. */ + pxTimer = ( Timer_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); /*lint !e9087 !e9079 void * is used as this macro is used with tasks and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + ( void ) uxListRemove( &( pxTimer->xTimerListItem ) ); + traceTIMER_EXPIRED( pxTimer ); + + /* Execute its callback, then send a command to restart the timer if + it is an auto-reload timer. It cannot be restarted here as the lists + have not yet been switched. */ + pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer ); + + if( ( pxTimer->ucStatus & tmrSTATUS_IS_AUTORELOAD ) != 0 ) + { + /* Calculate the reload value, and if the reload value results in + the timer going into the same timer list then it has already expired + and the timer should be re-inserted into the current list so it is + processed again within this loop. Otherwise a command should be sent + to restart the timer to ensure it is only inserted into a list after + the lists have been swapped. */ + xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); + if( xReloadTime > xNextExpireTime ) + { + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + else + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + pxTemp = pxCurrentTimerList; + pxCurrentTimerList = pxOverflowTimerList; + pxOverflowTimerList = pxTemp; +} +/*-----------------------------------------------------------*/ + +static void prvCheckForValidListAndQueue( void ) +{ + /* Check that the list from which active timers are referenced, and the + queue used to communicate with the timer service, have been + initialised. */ + taskENTER_CRITICAL(); + { + if( xTimerQueue == NULL ) + { + vListInitialise( &xActiveTimerList1 ); + vListInitialise( &xActiveTimerList2 ); + pxCurrentTimerList = &xActiveTimerList1; + pxOverflowTimerList = &xActiveTimerList2; + + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + /* The timer queue is allocated statically in case + configSUPPORT_DYNAMIC_ALLOCATION is 0. */ + static StaticQueue_t xStaticTimerQueue; /*lint !e956 Ok to declare in this manner to prevent additional conditional compilation guards in other locations. */ + static uint8_t ucStaticTimerQueueStorage[ ( size_t ) configTIMER_QUEUE_LENGTH * sizeof( DaemonTaskMessage_t ) ]; /*lint !e956 Ok to declare in this manner to prevent additional conditional compilation guards in other locations. */ + + xTimerQueue = xQueueCreateStatic( ( UBaseType_t ) configTIMER_QUEUE_LENGTH, ( UBaseType_t ) sizeof( DaemonTaskMessage_t ), &( ucStaticTimerQueueStorage[ 0 ] ), &xStaticTimerQueue ); + } + #else + { + xTimerQueue = xQueueCreate( ( UBaseType_t ) configTIMER_QUEUE_LENGTH, sizeof( DaemonTaskMessage_t ) ); + } + #endif + + #if ( configQUEUE_REGISTRY_SIZE > 0 ) + { + if( xTimerQueue != NULL ) + { + vQueueAddToRegistry( xTimerQueue, "TmrQ" ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configQUEUE_REGISTRY_SIZE */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer ) +{ +BaseType_t xReturn; +Timer_t *pxTimer = xTimer; + + configASSERT( xTimer ); + + /* Is the timer in the list of active timers? */ + taskENTER_CRITICAL(); + { + if( ( pxTimer->ucStatus & tmrSTATUS_IS_ACTIVE ) == 0 ) + { + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} /*lint !e818 Can't be pointer to const due to the typedef. */ +/*-----------------------------------------------------------*/ + +void *pvTimerGetTimerID( const TimerHandle_t xTimer ) +{ +Timer_t * const pxTimer = xTimer; +void *pvReturn; + + configASSERT( xTimer ); + + taskENTER_CRITICAL(); + { + pvReturn = pxTimer->pvTimerID; + } + taskEXIT_CRITICAL(); + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ) +{ +Timer_t * const pxTimer = xTimer; + + configASSERT( xTimer ); + + taskENTER_CRITICAL(); + { + pxTimer->pvTimerID = pvNewID; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +#if( INCLUDE_xTimerPendFunctionCall == 1 ) + + BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, BaseType_t *pxHigherPriorityTaskWoken ) + { + DaemonTaskMessage_t xMessage; + BaseType_t xReturn; + + /* Complete the message with the function parameters and post it to the + daemon task. */ + xMessage.xMessageID = tmrCOMMAND_EXECUTE_CALLBACK_FROM_ISR; + xMessage.u.xCallbackParameters.pxCallbackFunction = xFunctionToPend; + xMessage.u.xCallbackParameters.pvParameter1 = pvParameter1; + xMessage.u.xCallbackParameters.ulParameter2 = ulParameter2; + + xReturn = xQueueSendFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); + + tracePEND_FUNC_CALL_FROM_ISR( xFunctionToPend, pvParameter1, ulParameter2, xReturn ); + + return xReturn; + } + +#endif /* INCLUDE_xTimerPendFunctionCall */ +/*-----------------------------------------------------------*/ + +#if( INCLUDE_xTimerPendFunctionCall == 1 ) + + BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait ) + { + DaemonTaskMessage_t xMessage; + BaseType_t xReturn; + + /* This function can only be called after a timer has been created or + after the scheduler has been started because, until then, the timer + queue does not exist. */ + configASSERT( xTimerQueue ); + + /* Complete the message with the function parameters and post it to the + daemon task. */ + xMessage.xMessageID = tmrCOMMAND_EXECUTE_CALLBACK; + xMessage.u.xCallbackParameters.pxCallbackFunction = xFunctionToPend; + xMessage.u.xCallbackParameters.pvParameter1 = pvParameter1; + xMessage.u.xCallbackParameters.ulParameter2 = ulParameter2; + + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xTicksToWait ); + + tracePEND_FUNC_CALL( xFunctionToPend, pvParameter1, ulParameter2, xReturn ); + + return xReturn; + } + +#endif /* INCLUDE_xTimerPendFunctionCall */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxTimerGetTimerNumber( TimerHandle_t xTimer ) + { + return ( ( Timer_t * ) xTimer )->uxTimerNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTimerSetTimerNumber( TimerHandle_t xTimer, UBaseType_t uxTimerNumber ) + { + ( ( Timer_t * ) xTimer )->uxTimerNumber = uxTimerNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. If you want to include software timer +functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#endif /* configUSE_TIMERS == 1 */ + + + diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/JLinkSettings.ini b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/JLinkSettings.ini new file mode 100644 index 0000000..d36f31d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/JLinkSettings.ini @@ -0,0 +1,39 @@ +[BREAKPOINTS] +ForceImpTypeAny = 0 +ShowInfoWin = 1 +EnableFlashBP = 2 +BPDuringExecution = 0 +[CFI] +CFISize = 0x00 +CFIAddr = 0x00 +[CPU] +MonModeVTableAddr = 0xFFFFFFFF +MonModeDebug = 0 +MaxNumAPs = 0 +LowPowerHandlingMode = 0 +OverrideMemMap = 0 +AllowSimulation = 1 +ScriptFile="" +[FLASH] +CacheExcludeSize = 0x00 +CacheExcludeAddr = 0x00 +MinNumBytesFlashDL = 0 +SkipProgOnCRCMatch = 1 +VerifyDownload = 1 +AllowCaching = 1 +EnableFlashDL = 2 +Override = 1 +Device="Cortex-M33" +[GENERAL] +WorkRAMSize = 0x00 +WorkRAMAddr = 0x00 +RAMUsageLimit = 0x00 +[SWO] +SWOLogFile="" +[MEM] +RdOverrideOrMask = 0x00 +RdOverrideAndMask = 0xFFFFFFFF +RdOverrideAddr = 0xFFFFFFFF +WrOverrideOrMask = 0x00 +WrOverrideAndMask = 0xFFFFFFFF +WrOverrideAddr = 0xFFFFFFFF diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/Project.uvoptx b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/Project.uvoptx new file mode 100644 index 0000000..dee4fce --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/Project.uvoptx @@ -0,0 +1,1501 @@ + + + + 1.0 + +
### uVision Project, (C) Keil Software
+ + + *.c + *.s*; *.src; *.a* + *.obj; *.o + *.lib + *.txt; *.h; *.inc + *.plm + *.cpp + 0 + + + + 0 + 0 + + + + mdk_app + 0x4 + ARM-ADS + + 12000000 + + 1 + 1 + 0 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\Lists\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 1 + + 0 + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 1 + 1 + 0 + 0 + 1 + 0 + 0 + 4 + + + + + + + + + + + Segger\JL2CM3.dll + + + + 0 + JL2CM3 + -U69615359 -O78 -S2 -ZTIFSpeedSel5000 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(0BE12477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC1000 -FN1 -FF0GD32F5xx_4M -FS08000000 -FL0480000 -FP0($$Device:GD32F527ZM$Flash\GD32F5xx_4M.FLM) + + + 0 + UL2V8M + UL2V8M(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0GD32F5xx_4M -FS08000000 -FL0480000 -FP0($$Device:GD32F527ZM$Flash\GD32F5xx_4M.FLM)) + + + + + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + 0 + 0 + 0 + + + + + + + + + + + + + application + 1 + 0 + 0 + 0 + + 1 + 1 + 1 + 0 + 0 + 0 + ..\..\application\main.c + main.c + 0 + 0 + + + 1 + 2 + 1 + 0 + 0 + 0 + ..\..\application\application.c + application.c + 0 + 0 + + + 1 + 3 + 1 + 0 + 0 + 0 + ..\..\..\common\osal\osal.c + osal.c + 0 + 0 + + + 1 + 4 + 1 + 0 + 0 + 0 + ..\..\hal\hal_uart.c + hal_uart.c + 0 + 0 + + + + + api_sample + 1 + 0 + 0 + 0 + + 2 + 5 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\power_management\test_power_management.c + test_power_management.c + 0 + 0 + + + 2 + 6 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\upgrade\test_upgrade.c + test_upgrade.c + 0 + 0 + + + 2 + 7 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\upgrade\test_upgrade_common_file_transfer.c + test_upgrade_common_file_transfer.c + 0 + 0 + + + 2 + 8 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\upgrade\test_upgrade_platform_opt.c + test_upgrade_platform_opt.c + 0 + 0 + + + 2 + 9 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\utils\util_md5.c + util_md5.c + 0 + 0 + + + 2 + 10 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\time_sync\test_time_sync.c + test_time_sync.c + 0 + 0 + + + 2 + 11 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\camera_manager\test_camera_manager.c + test_camera_manager.c + 0 + 0 + + + 2 + 12 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\data_transmission\test_data_transmission.c + test_data_transmission.c + 0 + 0 + + + 2 + 13 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\fc_subscription\test_fc_subscription.c + test_fc_subscription.c + 0 + 0 + + + 2 + 14 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\flight_control\test_flight_control.c + test_flight_control.c + 0 + 0 + + + 2 + 15 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\gimbal_emu\test_payload_gimbal_emu.c + test_payload_gimbal_emu.c + 0 + 0 + + + 2 + 16 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\gimbal_manager\test_gimbal_manager.c + test_gimbal_manager.c + 0 + 0 + + + 2 + 17 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\hms\test_hms.c + test_hms.c + 0 + 0 + + + 2 + 18 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\payload_collaboration\test_payload_collaboration.c + test_payload_collaboration.c + 0 + 0 + + + 2 + 19 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\perception\test_perception.c + test_perception.c + 0 + 0 + + + 2 + 20 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\positioning\test_positioning.c + test_positioning.c + 0 + 0 + + + 2 + 21 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\utils\dji_config_manager.c + dji_config_manager.c + 0 + 0 + + + 2 + 22 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\utils\util_buffer.c + util_buffer.c + 0 + 0 + + + 2 + 23 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\utils\util_file.c + util_file.c + 0 + 0 + + + 2 + 24 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\utils\util_link_list.c + util_link_list.c + 0 + 0 + + + 2 + 25 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\utils\util_misc.c + util_misc.c + 0 + 0 + + + 2 + 26 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\utils\util_time.c + util_time.c + 0 + 0 + + + 2 + 27 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\waypoint_v2\test_waypoint_v2.c + test_waypoint_v2.c + 0 + 0 + + + 2 + 28 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\waypoint_v3\test_waypoint_v3.c + test_waypoint_v3.c + 0 + 0 + + + 2 + 29 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\widget\file_binary_array_list_en.c + file_binary_array_list_en.c + 0 + 0 + + + 2 + 30 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\widget\test_widget.c + test_widget.c + 0 + 0 + + + 2 + 31 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\widget\test_widget_speaker.c + test_widget_speaker.c + 0 + 0 + + + 2 + 32 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\camera_emu\test_payload_cam_emu_base.c + test_payload_cam_emu_base.c + 0 + 0 + + + 2 + 33 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\xport\test_payload_xport.c + test_payload_xport.c + 0 + 0 + + + 2 + 34 + 1 + 0 + 0 + 0 + ..\..\..\..\..\module_sample\tethered_battery\test_tethered_battery.c + test_tethered_battery.c + 0 + 0 + + + + + bsp + 0 + 0 + 0 + 0 + + 3 + 35 + 1 + 0 + 0 + 0 + ..\..\drivers\CMSIS\GD\GD32F5xx\Source\system_gd32f5xx.c + system_gd32f5xx.c + 0 + 0 + + + 3 + 36 + 2 + 0 + 0 + 0 + ..\..\drivers\BSP\startup_gd32f5xx.s + startup_gd32f5xx.s + 0 + 0 + + + 3 + 37 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\gd32f5xx_it.c + gd32f5xx_it.c + 0 + 0 + + + 3 + 38 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\button.c + button.c + 0 + 0 + + + 3 + 39 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\dji_ringbuffer.c + dji_ringbuffer.c + 0 + 0 + + + 3 + 40 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\flash_if.c + flash_if.c + 0 + 0 + + + 3 + 41 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\pps.c + pps.c + 0 + 0 + + + 3 + 42 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\uart.c + uart.c + 0 + 0 + + + 3 + 43 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\upgrade_platform_opt_gd32.c + upgrade_platform_opt_gd32.c + 0 + 0 + + + 3 + 44 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\led.c + led.c + 0 + 0 + + + 3 + 45 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\apply_high_power.c + apply_high_power.c + 0 + 0 + + + 3 + 46 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\pwm.c + pwm.c + 0 + 0 + + + 3 + 47 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\can.c + can.c + 0 + 0 + + + 3 + 48 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\gd32f5xx_hw.c + gd32f5xx_hw.c + 0 + 0 + + + 3 + 49 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\usb_device.c + usb_device.c + 0 + 0 + + + + + drv/gd32f5xx_drivers + 0 + 0 + 0 + 0 + + 4 + 50 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_adc.c + gd32f5xx_adc.c + 0 + 0 + + + 4 + 51 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_can.c + gd32f5xx_can.c + 0 + 0 + + + 4 + 52 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau.c + gd32f5xx_cau.c + 0 + 0 + + + 4 + 53 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_aes.c + gd32f5xx_cau_aes.c + 0 + 0 + + + 4 + 54 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_des.c + gd32f5xx_cau_des.c + 0 + 0 + + + 4 + 55 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_tdes.c + gd32f5xx_cau_tdes.c + 0 + 0 + + + 4 + 56 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_crc.c + gd32f5xx_crc.c + 0 + 0 + + + 4 + 57 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_ctc.c + gd32f5xx_ctc.c + 0 + 0 + + + 4 + 58 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dac.c + gd32f5xx_dac.c + 0 + 0 + + + 4 + 59 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dbg.c + gd32f5xx_dbg.c + 0 + 0 + + + 4 + 60 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dci.c + gd32f5xx_dci.c + 0 + 0 + + + 4 + 61 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dma.c + gd32f5xx_dma.c + 0 + 0 + + + 4 + 62 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_enet.c + gd32f5xx_enet.c + 0 + 0 + + + 4 + 63 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_exmc.c + gd32f5xx_exmc.c + 0 + 0 + + + 4 + 64 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_exti.c + gd32f5xx_exti.c + 0 + 0 + + + 4 + 65 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_fmc.c + gd32f5xx_fmc.c + 0 + 0 + + + 4 + 66 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_fwdgt.c + gd32f5xx_fwdgt.c + 0 + 0 + + + 4 + 67 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_gpio.c + gd32f5xx_gpio.c + 0 + 0 + + + 4 + 68 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_hau.c + gd32f5xx_hau.c + 0 + 0 + + + 4 + 69 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_hau_sha_md5.c + gd32f5xx_hau_sha_md5.c + 0 + 0 + + + 4 + 70 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_i2c.c + gd32f5xx_i2c.c + 0 + 0 + + + 4 + 71 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_i2c_add.c + gd32f5xx_i2c_add.c + 0 + 0 + + + 4 + 72 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_ipa.c + gd32f5xx_ipa.c + 0 + 0 + + + 4 + 73 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_iref.c + gd32f5xx_iref.c + 0 + 0 + + + 4 + 74 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_misc.c + gd32f5xx_misc.c + 0 + 0 + + + 4 + 75 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_pkcau.c + gd32f5xx_pkcau.c + 0 + 0 + + + 4 + 76 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_pmu.c + gd32f5xx_pmu.c + 0 + 0 + + + 4 + 77 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_rcu.c + gd32f5xx_rcu.c + 0 + 0 + + + 4 + 78 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_rtc.c + gd32f5xx_rtc.c + 0 + 0 + + + 4 + 79 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_sai.c + gd32f5xx_sai.c + 0 + 0 + + + 4 + 80 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_sdio.c + gd32f5xx_sdio.c + 0 + 0 + + + 4 + 81 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_spi.c + gd32f5xx_spi.c + 0 + 0 + + + 4 + 82 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_syscfg.c + gd32f5xx_syscfg.c + 0 + 0 + + + 4 + 83 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_timer.c + gd32f5xx_timer.c + 0 + 0 + + + 4 + 84 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_tli.c + gd32f5xx_tli.c + 0 + 0 + + + 4 + 85 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_trng.c + gd32f5xx_trng.c + 0 + 0 + + + 4 + 86 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_usart.c + gd32f5xx_usart.c + 0 + 0 + + + 4 + 87 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_wwdgt.c + gd32f5xx_wwdgt.c + 0 + 0 + + + + + freertos + 0 + 0 + 0 + 0 + + 5 + 88 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\croutine.c + croutine.c + 0 + 0 + + + 5 + 89 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\event_groups.c + event_groups.c + 0 + 0 + + + 5 + 90 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\list.c + list.c + 0 + 0 + + + 5 + 91 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\queue.c + queue.c + 0 + 0 + + + 5 + 92 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\stream_buffer.c + stream_buffer.c + 0 + 0 + + + 5 + 93 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\tasks.c + tasks.c + 0 + 0 + + + 5 + 94 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\timers.c + timers.c + 0 + 0 + + + 5 + 95 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\portable\MemMang\heap_4.c + heap_4.c + 0 + 0 + + + 5 + 96 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure\port.c + port.c + 0 + 0 + + + 5 + 97 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure\portasm.c + portasm.c + 0 + 0 + + + + + usb_drivers + 0 + 0 + 0 + 0 + + 6 + 98 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_usb_library\driver\Source\drv_usb_core.c + drv_usb_core.c + 0 + 0 + + + 6 + 99 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_usb_library\driver\Source\drv_usb_dev.c + drv_usb_dev.c + 0 + 0 + + + 6 + 100 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_usb_library\driver\Source\drv_usbd_int.c + drv_usbd_int.c + 0 + 0 + + + 6 + 101 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_usb_library\device\core\Source\usbd_core.c + usbd_core.c + 0 + 0 + + + 6 + 102 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_usb_library\device\core\Source\usbd_enum.c + usbd_enum.c + 0 + 0 + + + 6 + 103 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_usb_library\device\core\Source\usbd_transc.c + usbd_transc.c + 0 + 0 + + + 6 + 104 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_usb_library\device\class\cdc\Source\cdc_acm_core.c + cdc_acm_core.c + 0 + 0 + + + + + psdk_lib + 0 + 0 + 0 + 0 + + 7 + 105 + 4 + 0 + 0 + 0 + ..\..\..\..\..\..\..\psdk_lib\lib\armcc_cortex-m33\libpayload.lib + libpayload.lib + 0 + 0 + + + + + ::CMSIS + 0 + 0 + 0 + 1 + + +
diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/Project.uvprojx b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/Project.uvprojx new file mode 100644 index 0000000..b7dcfab --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_app/Project.uvprojx @@ -0,0 +1,962 @@ + + + + 2.1 + +
### uVision Project, (C) Keil Software
+ + + + mdk_app + 0x4 + ARM-ADS + 6100001::V6.10.1::.\ARMCLANG + 1 + + + GD32F527ZM + GigaDevice + GigaDevice.GD32F5xx_DFP.1.0.0 + https://gd32mcu.com/data/documents/pack/ + IRAM(0x20000000,0x110000) IROM(0x08000000,0x480000) CPUTYPE("Cortex-M33") FPU3(SFPU) DSP CLOCK(12000000) ELITTLE + + + UL2V8M(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0GD32F5xx_4M -FS08000000 -FL0480000 -FP0($$Device:GD32F527ZM$Flash\GD32F5xx_4M.FLM)) + 0 + + + + + + + + + + + $$Device:GD32F527ZM$SVD\GD32F5xx.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\Objects\ + mdk_app + 1 + 0 + 1 + 1 + 1 + .\Lists\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 1 + 0 + C:\Keil_v5\ARM\ARMCC\Bin\fromelf.exe .\Objects\mdk_app.axf --bin --output .\PSDK_APPALIAS_V01.00.00.99.bin + + 0 + 0 + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + 1 + + + + + + + SARMV8M.DLL + -MPU + TCM.DLL + -pCM33 + + + + 1 + 0 + 0 + 0 + 16 + + + + + 1 + 0 + 0 + 1 + 1 + 4100 + + 1 + BIN\UL2V8M.DLL + + + + + + 0 + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M33" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 2 + 0 + 0 + 0 + 8 + 1 + 0 + 0 + 0 + 3 + 3 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x110000 + + + 1 + 0x8000000 + 0x480000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8020000 + 0x480000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x110000 + + + 0 + 0x0 + 0x0 + + + + + + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 1 + 0 + 0 + 4 + 3 + 0 + 0 + 0 + 0 + 0 + + + GD32F527,SYSTEM_ARCH_RTOS=1,USE_USB_FS, USE_BOOTLOADER + + ..\..\application;..\..\drivers\GD32F5xx_standard_peripheral\Include;..\..\middlewares\FreeRTOS-10.3.1\include;..\..\drivers\CMSIS;..\..\drivers\CMSIS\GD\GD32F5xx\Include;..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ;..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure;..\..\drivers\BSP;..\..\..\..\..\module_sample;..\..\hal;..\..\drivers\GD32F5xx_usb_library\device\core\Include;..\..\drivers\GD32F5xx_usb_library\driver\Include;..\..\drivers\GD32F5xx_usb_library\device\class\cdc\Include;..\..\drivers\GD32F5xx_usb_library\ustd\common;..\..\drivers\GD32F5xx_usb_library\ustd\class\cdc;..\..\..\common\osal;..\..\..\..\..\..\..\psdk_lib\include + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + + + + 1 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + + + + + + + + + + + + application + + + main.c + 1 + ..\..\application\main.c + + + application.c + 1 + ..\..\application\application.c + + + osal.c + 1 + ..\..\..\common\osal\osal.c + + + hal_uart.c + 1 + ..\..\hal\hal_uart.c + + + + + api_sample + + + test_power_management.c + 1 + ..\..\..\..\..\module_sample\power_management\test_power_management.c + + + test_upgrade.c + 1 + ..\..\..\..\..\module_sample\upgrade\test_upgrade.c + + + test_upgrade_common_file_transfer.c + 1 + ..\..\..\..\..\module_sample\upgrade\test_upgrade_common_file_transfer.c + + + test_upgrade_platform_opt.c + 1 + ..\..\..\..\..\module_sample\upgrade\test_upgrade_platform_opt.c + + + util_md5.c + 1 + ..\..\..\..\..\module_sample\utils\util_md5.c + + + test_time_sync.c + 1 + ..\..\..\..\..\module_sample\time_sync\test_time_sync.c + + + test_camera_manager.c + 1 + ..\..\..\..\..\module_sample\camera_manager\test_camera_manager.c + + + test_data_transmission.c + 1 + ..\..\..\..\..\module_sample\data_transmission\test_data_transmission.c + + + test_fc_subscription.c + 1 + ..\..\..\..\..\module_sample\fc_subscription\test_fc_subscription.c + + + test_flight_control.c + 1 + ..\..\..\..\..\module_sample\flight_control\test_flight_control.c + + + test_payload_gimbal_emu.c + 1 + ..\..\..\..\..\module_sample\gimbal_emu\test_payload_gimbal_emu.c + + + test_gimbal_manager.c + 1 + ..\..\..\..\..\module_sample\gimbal_manager\test_gimbal_manager.c + + + test_hms.c + 1 + ..\..\..\..\..\module_sample\hms\test_hms.c + + + test_payload_collaboration.c + 1 + ..\..\..\..\..\module_sample\payload_collaboration\test_payload_collaboration.c + + + test_perception.c + 1 + ..\..\..\..\..\module_sample\perception\test_perception.c + + + test_positioning.c + 1 + ..\..\..\..\..\module_sample\positioning\test_positioning.c + + + dji_config_manager.c + 1 + ..\..\..\..\..\module_sample\utils\dji_config_manager.c + + + util_buffer.c + 1 + ..\..\..\..\..\module_sample\utils\util_buffer.c + + + util_file.c + 1 + ..\..\..\..\..\module_sample\utils\util_file.c + + + util_link_list.c + 1 + ..\..\..\..\..\module_sample\utils\util_link_list.c + + + util_misc.c + 1 + ..\..\..\..\..\module_sample\utils\util_misc.c + + + util_time.c + 1 + ..\..\..\..\..\module_sample\utils\util_time.c + + + test_waypoint_v2.c + 1 + ..\..\..\..\..\module_sample\waypoint_v2\test_waypoint_v2.c + + + test_waypoint_v3.c + 1 + ..\..\..\..\..\module_sample\waypoint_v3\test_waypoint_v3.c + + + file_binary_array_list_en.c + 1 + ..\..\..\..\..\module_sample\widget\file_binary_array_list_en.c + + + test_widget.c + 1 + ..\..\..\..\..\module_sample\widget\test_widget.c + + + test_widget_speaker.c + 1 + ..\..\..\..\..\module_sample\widget\test_widget_speaker.c + + + test_payload_cam_emu_base.c + 1 + ..\..\..\..\..\module_sample\camera_emu\test_payload_cam_emu_base.c + + + test_payload_xport.c + 1 + ..\..\..\..\..\module_sample\xport\test_payload_xport.c + + + test_tethered_battery.c + 1 + ..\..\..\..\..\module_sample\tethered_battery\test_tethered_battery.c + + + + + bsp + + + system_gd32f5xx.c + 1 + ..\..\drivers\CMSIS\GD\GD32F5xx\Source\system_gd32f5xx.c + + + startup_gd32f5xx.s + 2 + ..\..\drivers\BSP\startup_gd32f5xx.s + + + gd32f5xx_it.c + 1 + ..\..\drivers\BSP\gd32f5xx_it.c + + + button.c + 1 + ..\..\drivers\BSP\button.c + + + dji_ringbuffer.c + 1 + ..\..\drivers\BSP\dji_ringbuffer.c + + + flash_if.c + 1 + ..\..\drivers\BSP\flash_if.c + + + pps.c + 1 + ..\..\drivers\BSP\pps.c + + + uart.c + 1 + ..\..\drivers\BSP\uart.c + + + upgrade_platform_opt_gd32.c + 1 + ..\..\drivers\BSP\upgrade_platform_opt_gd32.c + + + led.c + 1 + ..\..\drivers\BSP\led.c + + + apply_high_power.c + 1 + ..\..\drivers\BSP\apply_high_power.c + + + pwm.c + 1 + ..\..\drivers\BSP\pwm.c + + + can.c + 1 + ..\..\drivers\BSP\can.c + + + gd32f5xx_hw.c + 1 + ..\..\drivers\BSP\gd32f5xx_hw.c + + + usb_device.c + 1 + ..\..\drivers\BSP\usb_device.c + + + + + drv/gd32f5xx_drivers + + + gd32f5xx_adc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_adc.c + + + gd32f5xx_can.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_can.c + + + gd32f5xx_cau.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau.c + + + gd32f5xx_cau_aes.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_aes.c + + + gd32f5xx_cau_des.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_des.c + + + gd32f5xx_cau_tdes.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_tdes.c + + + gd32f5xx_crc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_crc.c + + + gd32f5xx_ctc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_ctc.c + + + gd32f5xx_dac.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dac.c + + + gd32f5xx_dbg.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dbg.c + + + gd32f5xx_dci.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dci.c + + + gd32f5xx_dma.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dma.c + + + gd32f5xx_enet.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_enet.c + + + gd32f5xx_exmc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_exmc.c + + + gd32f5xx_exti.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_exti.c + + + gd32f5xx_fmc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_fmc.c + + + gd32f5xx_fwdgt.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_fwdgt.c + + + gd32f5xx_gpio.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_gpio.c + + + gd32f5xx_hau.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_hau.c + + + gd32f5xx_hau_sha_md5.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_hau_sha_md5.c + + + gd32f5xx_i2c.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_i2c.c + + + gd32f5xx_i2c_add.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_i2c_add.c + + + gd32f5xx_ipa.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_ipa.c + + + gd32f5xx_iref.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_iref.c + + + gd32f5xx_misc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_misc.c + + + gd32f5xx_pkcau.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_pkcau.c + + + gd32f5xx_pmu.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_pmu.c + + + gd32f5xx_rcu.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_rcu.c + + + gd32f5xx_rtc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_rtc.c + + + gd32f5xx_sai.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_sai.c + + + gd32f5xx_sdio.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_sdio.c + + + gd32f5xx_spi.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_spi.c + + + gd32f5xx_syscfg.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_syscfg.c + + + gd32f5xx_timer.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_timer.c + + + gd32f5xx_tli.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_tli.c + + + gd32f5xx_trng.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_trng.c + + + gd32f5xx_usart.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_usart.c + + + gd32f5xx_wwdgt.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_wwdgt.c + + + + + freertos + + + croutine.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\croutine.c + + + event_groups.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\event_groups.c + + + list.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\list.c + + + queue.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\queue.c + + + stream_buffer.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\stream_buffer.c + + + tasks.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\tasks.c + + + timers.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\timers.c + + + heap_4.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\portable\MemMang\heap_4.c + + + port.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure\port.c + + + portasm.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure\portasm.c + + + + + usb_drivers + + + drv_usb_core.c + 1 + ..\..\drivers\GD32F5xx_usb_library\driver\Source\drv_usb_core.c + + + drv_usb_dev.c + 1 + ..\..\drivers\GD32F5xx_usb_library\driver\Source\drv_usb_dev.c + + + drv_usbd_int.c + 1 + ..\..\drivers\GD32F5xx_usb_library\driver\Source\drv_usbd_int.c + + + usbd_core.c + 1 + ..\..\drivers\GD32F5xx_usb_library\device\core\Source\usbd_core.c + + + usbd_enum.c + 1 + ..\..\drivers\GD32F5xx_usb_library\device\core\Source\usbd_enum.c + + + usbd_transc.c + 1 + ..\..\drivers\GD32F5xx_usb_library\device\core\Source\usbd_transc.c + + + cdc_acm_core.c + 1 + ..\..\drivers\GD32F5xx_usb_library\device\class\cdc\Source\cdc_acm_core.c + + + + + psdk_lib + + + libpayload.lib + 4 + ..\..\..\..\..\..\..\psdk_lib\lib\armcc_cortex-m33\libpayload.lib + + + + + ::CMSIS + + + + + + + + + + + + + + + + + + +
diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/JLinkSettings.ini b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/JLinkSettings.ini new file mode 100644 index 0000000..d36f31d --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/JLinkSettings.ini @@ -0,0 +1,39 @@ +[BREAKPOINTS] +ForceImpTypeAny = 0 +ShowInfoWin = 1 +EnableFlashBP = 2 +BPDuringExecution = 0 +[CFI] +CFISize = 0x00 +CFIAddr = 0x00 +[CPU] +MonModeVTableAddr = 0xFFFFFFFF +MonModeDebug = 0 +MaxNumAPs = 0 +LowPowerHandlingMode = 0 +OverrideMemMap = 0 +AllowSimulation = 1 +ScriptFile="" +[FLASH] +CacheExcludeSize = 0x00 +CacheExcludeAddr = 0x00 +MinNumBytesFlashDL = 0 +SkipProgOnCRCMatch = 1 +VerifyDownload = 1 +AllowCaching = 1 +EnableFlashDL = 2 +Override = 1 +Device="Cortex-M33" +[GENERAL] +WorkRAMSize = 0x00 +WorkRAMAddr = 0x00 +RAMUsageLimit = 0x00 +[SWO] +SWOLogFile="" +[MEM] +RdOverrideOrMask = 0x00 +RdOverrideAndMask = 0xFFFFFFFF +RdOverrideAddr = 0xFFFFFFFF +WrOverrideOrMask = 0x00 +WrOverrideAndMask = 0xFFFFFFFF +WrOverrideAddr = 0xFFFFFFFF diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/Project.uvoptx b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/Project.uvoptx new file mode 100644 index 0000000..a7d1667 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/Project.uvoptx @@ -0,0 +1,973 @@ + + + + 1.0 + +
### uVision Project, (C) Keil Software
+ + + *.c + *.s*; *.src; *.a* + *.obj; *.o + *.lib + *.txt; *.h; *.inc + *.plm + *.cpp + 0 + + + + 0 + 0 + + + + mdk_bootloader + 0x4 + ARM-ADS + + 12000000 + + 1 + 1 + 0 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\Lists\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 1 + + 255 + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 1 + 1 + 0 + 0 + 1 + 0 + 0 + 4 + + + + + + + + + + + Segger\JL2CM3.dll + + + + 0 + JL2CM3 + -U69615359 -O78 -S2 -ZTIFSpeedSel5000 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(0BE12477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO14 -FD20000000 -FC1000 -FN1 -FF0GD32F5xx_4M.FLM -FS08000000 -FL0480000 -FP0($$Device:GD32F527ZM$Flash\GD32F5xx_4M.FLM) + + + 0 + UL2V8M + UL2V8M(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0GD32F5xx_4M -FS08000000 -FL0480000 -FP0($$Device:GD32F527ZM$Flash\GD32F5xx_4M.FLM)) + + + + + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + 0 + 0 + 0 + + + + + + + + + + + + + bootloader + 1 + 0 + 0 + 0 + + 1 + 1 + 1 + 0 + 0 + 0 + ..\..\bootloader\common.c + common.c + 0 + 0 + + + 1 + 2 + 1 + 0 + 0 + 0 + ..\..\bootloader\main.c + main.c + 0 + 0 + + + 1 + 3 + 1 + 0 + 0 + 0 + ..\..\bootloader\menu.c + menu.c + 0 + 0 + + + 1 + 4 + 1 + 0 + 0 + 0 + ..\..\bootloader\ymodem.c + ymodem.c + 0 + 0 + + + 1 + 5 + 1 + 0 + 0 + 0 + ..\..\..\common\osal\osal.c + osal.c + 0 + 0 + + + + + bsp + 1 + 0 + 0 + 0 + + 2 + 6 + 1 + 0 + 0 + 0 + ..\..\drivers\CMSIS\GD\GD32F5xx\Source\system_gd32f5xx.c + system_gd32f5xx.c + 0 + 0 + + + 2 + 7 + 2 + 0 + 0 + 0 + ..\..\drivers\BSP\startup_gd32f5xx.s + startup_gd32f5xx.s + 0 + 0 + + + 2 + 8 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\gd32f5xx_it.c + gd32f5xx_it.c + 0 + 0 + + + 2 + 9 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\button.c + button.c + 0 + 0 + + + 2 + 10 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\dji_ringbuffer.c + dji_ringbuffer.c + 0 + 0 + + + 2 + 11 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\flash_if.c + flash_if.c + 0 + 0 + + + 2 + 12 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\uart.c + uart.c + 0 + 0 + + + 2 + 13 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\upgrade_platform_opt_gd32.c + upgrade_platform_opt_gd32.c + 0 + 0 + + + 2 + 14 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\led.c + led.c + 0 + 0 + + + 2 + 15 + 1 + 0 + 0 + 0 + ..\..\drivers\BSP\gd32f5xx_hw.c + gd32f5xx_hw.c + 0 + 0 + + + + + drv/gd32f5xx_drivers + 0 + 0 + 0 + 0 + + 3 + 16 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_adc.c + gd32f5xx_adc.c + 0 + 0 + + + 3 + 17 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_can.c + gd32f5xx_can.c + 0 + 0 + + + 3 + 18 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau.c + gd32f5xx_cau.c + 0 + 0 + + + 3 + 19 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_aes.c + gd32f5xx_cau_aes.c + 0 + 0 + + + 3 + 20 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_des.c + gd32f5xx_cau_des.c + 0 + 0 + + + 3 + 21 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_tdes.c + gd32f5xx_cau_tdes.c + 0 + 0 + + + 3 + 22 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_crc.c + gd32f5xx_crc.c + 0 + 0 + + + 3 + 23 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_ctc.c + gd32f5xx_ctc.c + 0 + 0 + + + 3 + 24 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dac.c + gd32f5xx_dac.c + 0 + 0 + + + 3 + 25 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dbg.c + gd32f5xx_dbg.c + 0 + 0 + + + 3 + 26 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dci.c + gd32f5xx_dci.c + 0 + 0 + + + 3 + 27 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dma.c + gd32f5xx_dma.c + 0 + 0 + + + 3 + 28 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_enet.c + gd32f5xx_enet.c + 0 + 0 + + + 3 + 29 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_exmc.c + gd32f5xx_exmc.c + 0 + 0 + + + 3 + 30 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_exti.c + gd32f5xx_exti.c + 0 + 0 + + + 3 + 31 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_fmc.c + gd32f5xx_fmc.c + 0 + 0 + + + 3 + 32 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_fwdgt.c + gd32f5xx_fwdgt.c + 0 + 0 + + + 3 + 33 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_gpio.c + gd32f5xx_gpio.c + 0 + 0 + + + 3 + 34 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_hau.c + gd32f5xx_hau.c + 0 + 0 + + + 3 + 35 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_hau_sha_md5.c + gd32f5xx_hau_sha_md5.c + 0 + 0 + + + 3 + 36 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_i2c.c + gd32f5xx_i2c.c + 0 + 0 + + + 3 + 37 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_i2c_add.c + gd32f5xx_i2c_add.c + 0 + 0 + + + 3 + 38 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_ipa.c + gd32f5xx_ipa.c + 0 + 0 + + + 3 + 39 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_iref.c + gd32f5xx_iref.c + 0 + 0 + + + 3 + 40 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_misc.c + gd32f5xx_misc.c + 0 + 0 + + + 3 + 41 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_pkcau.c + gd32f5xx_pkcau.c + 0 + 0 + + + 3 + 42 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_pmu.c + gd32f5xx_pmu.c + 0 + 0 + + + 3 + 43 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_rcu.c + gd32f5xx_rcu.c + 0 + 0 + + + 3 + 44 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_rtc.c + gd32f5xx_rtc.c + 0 + 0 + + + 3 + 45 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_sai.c + gd32f5xx_sai.c + 0 + 0 + + + 3 + 46 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_sdio.c + gd32f5xx_sdio.c + 0 + 0 + + + 3 + 47 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_spi.c + gd32f5xx_spi.c + 0 + 0 + + + 3 + 48 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_syscfg.c + gd32f5xx_syscfg.c + 0 + 0 + + + 3 + 49 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_timer.c + gd32f5xx_timer.c + 0 + 0 + + + 3 + 50 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_tli.c + gd32f5xx_tli.c + 0 + 0 + + + 3 + 51 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_trng.c + gd32f5xx_trng.c + 0 + 0 + + + 3 + 52 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_usart.c + gd32f5xx_usart.c + 0 + 0 + + + 3 + 53 + 1 + 0 + 0 + 0 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_wwdgt.c + gd32f5xx_wwdgt.c + 0 + 0 + + + + + freertos + 0 + 0 + 0 + 0 + + 4 + 54 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\croutine.c + croutine.c + 0 + 0 + + + 4 + 55 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\event_groups.c + event_groups.c + 0 + 0 + + + 4 + 56 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\list.c + list.c + 0 + 0 + + + 4 + 57 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\queue.c + queue.c + 0 + 0 + + + 4 + 58 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\stream_buffer.c + stream_buffer.c + 0 + 0 + + + 4 + 59 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\tasks.c + tasks.c + 0 + 0 + + + 4 + 60 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\timers.c + timers.c + 0 + 0 + + + 4 + 61 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\portable\MemMang\heap_4.c + heap_4.c + 0 + 0 + + + 4 + 62 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure\port.c + port.c + 0 + 0 + + + 4 + 63 + 1 + 0 + 0 + 0 + ..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure\portasm.c + portasm.c + 0 + 0 + + + + + ::CMSIS + 0 + 0 + 0 + 1 + + +
diff --git a/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/Project.uvprojx b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/Project.uvprojx new file mode 100644 index 0000000..87ec512 --- /dev/null +++ b/samples/sample_c/platform/rtos_freertos/gd32f527_development_board/project/mdk_bootloader/Project.uvprojx @@ -0,0 +1,738 @@ + + + + 2.1 + +
### uVision Project, (C) Keil Software
+ + + + mdk_bootloader + 0x4 + ARM-ADS + 6100001::V6.10.1::.\ARMCLANG + 6100001::V6.10.1::.\ARMCLANG + 1 + + + GD32F527ZM + GigaDevice + GigaDevice.GD32F5xx_DFP.1.0.0 + https://gd32mcu.com/data/documents/pack/ + IRAM(0x20000000,0x110000) IROM(0x08000000,0x480000) CPUTYPE("Cortex-M33") FPU3(SFPU) DSP CLOCK(12000000) ELITTLE + + + UL2V8M(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0GD32F5xx_4M -FS08000000 -FL0480000 -FP0($$Device:GD32F527ZM$Flash\GD32F5xx_4M.FLM)) + 0 + + + + + + + + + + + $$Device:GD32F527ZM$SVD\GD32F5xx.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\Objects\ + mdk_app + 1 + 0 + 1 + 1 + 1 + .\Lists\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 1 + 0 + C:\Keil_v5\ARM\ARMCC\Bin\fromelf.exe .\Objects\mdk_app.axf --bin --output .\dji_sdk_demo_rtos.bin + + 0 + 0 + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + 1 + + + + + + + SARMV8M.DLL + -MPU + TCM.DLL + -pCM33 + + + + 1 + 0 + 0 + 0 + 16 + + + + + 1 + 0 + 0 + 1 + 1 + 4100 + + 1 + BIN\UL2V8M.DLL + "" () + + + + + 0 + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M33" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 2 + 0 + 0 + 0 + 8 + 1 + 0 + 0 + 0 + 3 + 3 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x110000 + + + 1 + 0x8000000 + 0x480000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x480000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x110000 + + + 0 + 0x0 + 0x0 + + + + + + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 1 + 0 + 0 + 4 + 3 + 0 + 0 + 0 + 0 + 0 + + + GD32F527,SYSTEM_ARCH_RTOS=1, + + ..\..\drivers\GD32F5xx_standard_peripheral\Include;..\..\middlewares\FreeRTOS-10.3.1\include;..\..\drivers\CMSIS;..\..\drivers\CMSIS\GD\GD32F5xx\Include;..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ;..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure;..\..\drivers\BSP;..\..\..\..\..\..\..\modules;..\..\..\..\..\..\..\modules\aircraft_info\include;..\..\..\..\..\..\..\modules\error\include;..\..\..\..\..\..\..\modules\camera_manager\include;..\..\..\..\..\..\..\modules\core\include;..\..\..\..\..\..\..\modules\xxx_template\include;..\..\..\..\..\..\..\modules\widget\include;..\..\..\..\..\..\..\modules\waypoint_v3\include;..\..\..\..\..\..\..\modules\waypoint_v2\include;..\..\..\..\..\..\..\modules\upgrade\include;..\..\..\..\..\..\..\modules\time_sync\include;..\..\..\..\..\..\..\modules\power_management\include;..\..\..\..\..\..\..\modules\positioning\include;..\..\..\..\..\..\..\modules\platform\include;..\..\..\..\..\..\..\modules\perception\include;..\..\..\..\..\..\..\modules\payload_xport\include;..\..\..\..\..\..\..\modules\payload_gimbal\include;..\..\..\..\..\..\..\modules\payload_camera\include;..\..\..\..\..\..\..\modules\payload_camera\payload_collaboration;..\..\..\..\..\..\..\modules\fc_subscription\include;..\..\..\..\..\..\..\modules\logger\include;..\..\..\..\..\..\..\modules\data_channel\include;..\..\..\..\..\..\..\modules\data_channel\high_speed_data_channel;..\..\..\..\..\..\..\modules\data_channel\low_speed_data_channel;..\..\..\..\..\..\..\modules\data_channel\stream_channel;..\..\..\..\..\..\..\modules\data_channel\mop_channel\mop;..\..\..\..\..\..\..\modules\flight_controller\include;..\..\..\..\..\..\..\modules\liveview\include;..\..\..\..\..\..\..\modules\gimbal_manager\include;..\..\..\..\..\..\..\modules\hms\include;..\..\..\..\..\..\..\modules\data_channel\mop_channel\mop\inc;..\..\..\common\osal;..\..\..\hal;..\..\application;..\..\drivers\GD32F5xx_usb_library\driver\Include;..\..\drivers\GD32F5xx_usb_library\device\core\Include;..\..\drivers\GD32F5xx_usb_library\device\class\cdc\Include;..\..\drivers\GD32F5xx_usb_library\ustd\class\cdc;..\..\drivers\GD32F5xx_usb_library\ustd\common;..\..\..\..\..\..\..\psdk_lib\include + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + + + + 1 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + + + + + + + + + + + + bootloader + + + common.c + 1 + ..\..\bootloader\common.c + + + main.c + 1 + ..\..\bootloader\main.c + + + menu.c + 1 + ..\..\bootloader\menu.c + + + ymodem.c + 1 + ..\..\bootloader\ymodem.c + + + osal.c + 1 + ..\..\..\common\osal\osal.c + + + + + bsp + + + system_gd32f5xx.c + 1 + ..\..\drivers\CMSIS\GD\GD32F5xx\Source\system_gd32f5xx.c + + + startup_gd32f5xx.s + 2 + ..\..\drivers\BSP\startup_gd32f5xx.s + + + gd32f5xx_it.c + 1 + ..\..\drivers\BSP\gd32f5xx_it.c + + + button.c + 1 + ..\..\drivers\BSP\button.c + + + dji_ringbuffer.c + 1 + ..\..\drivers\BSP\dji_ringbuffer.c + + + flash_if.c + 1 + ..\..\drivers\BSP\flash_if.c + + + uart.c + 1 + ..\..\drivers\BSP\uart.c + + + upgrade_platform_opt_gd32.c + 1 + ..\..\drivers\BSP\upgrade_platform_opt_gd32.c + + + led.c + 1 + ..\..\drivers\BSP\led.c + + + gd32f5xx_hw.c + 1 + ..\..\drivers\BSP\gd32f5xx_hw.c + + + + + drv/gd32f5xx_drivers + + + gd32f5xx_adc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_adc.c + + + gd32f5xx_can.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_can.c + + + gd32f5xx_cau.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau.c + + + gd32f5xx_cau_aes.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_aes.c + + + gd32f5xx_cau_des.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_des.c + + + gd32f5xx_cau_tdes.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_cau_tdes.c + + + gd32f5xx_crc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_crc.c + + + gd32f5xx_ctc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_ctc.c + + + gd32f5xx_dac.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dac.c + + + gd32f5xx_dbg.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dbg.c + + + gd32f5xx_dci.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dci.c + + + gd32f5xx_dma.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_dma.c + + + gd32f5xx_enet.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_enet.c + + + gd32f5xx_exmc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_exmc.c + + + gd32f5xx_exti.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_exti.c + + + gd32f5xx_fmc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_fmc.c + + + gd32f5xx_fwdgt.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_fwdgt.c + + + gd32f5xx_gpio.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_gpio.c + + + gd32f5xx_hau.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_hau.c + + + gd32f5xx_hau_sha_md5.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_hau_sha_md5.c + + + gd32f5xx_i2c.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_i2c.c + + + gd32f5xx_i2c_add.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_i2c_add.c + + + gd32f5xx_ipa.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_ipa.c + + + gd32f5xx_iref.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_iref.c + + + gd32f5xx_misc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_misc.c + + + gd32f5xx_pkcau.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_pkcau.c + + + gd32f5xx_pmu.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_pmu.c + + + gd32f5xx_rcu.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_rcu.c + + + gd32f5xx_rtc.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_rtc.c + + + gd32f5xx_sai.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_sai.c + + + gd32f5xx_sdio.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_sdio.c + + + gd32f5xx_spi.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_spi.c + + + gd32f5xx_syscfg.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_syscfg.c + + + gd32f5xx_timer.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_timer.c + + + gd32f5xx_tli.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_tli.c + + + gd32f5xx_trng.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_trng.c + + + gd32f5xx_usart.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_usart.c + + + gd32f5xx_wwdgt.c + 1 + ..\..\drivers\GD32F5xx_standard_peripheral\Source\gd32f5xx_wwdgt.c + + + + + freertos + + + croutine.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\croutine.c + + + event_groups.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\event_groups.c + + + list.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\list.c + + + queue.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\queue.c + + + stream_buffer.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\stream_buffer.c + + + tasks.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\tasks.c + + + timers.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\timers.c + + + heap_4.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\portable\MemMang\heap_4.c + + + port.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure\port.c + + + portasm.c + 1 + ..\..\middlewares\FreeRTOS-10.3.1\portable\GCC\ARM_CM33_NTZ\non_secure\portasm.c + + + + + ::CMSIS + + + + + + + + + + + + + + + + + + +
diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/application.c b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/application.c index 2785404..170a726 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/application.c +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/application.c @@ -111,6 +111,7 @@ void DjiUser_StartTask(void const *argument) .UartWriteData = HalUart_WriteData, .UartReadData = HalUart_ReadData, .UartGetStatus = HalUart_GetStatus, + .UartGetDeviceInfo = HalUart_GetDeviceInfo, }; T_DjiHalI2cHandler i2CHandler = { .I2cInit = HalI2c_Init, @@ -311,7 +312,8 @@ void DjiUser_StartTask(void const *argument) aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) && aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT) || DJI_AIRCRAFT_TYPE_M4T == aircraftInfoBaseInfo.aircraftType - || DJI_AIRCRAFT_TYPE_M4E == aircraftInfoBaseInfo.aircraftType + || DJI_AIRCRAFT_TYPE_M4TD == aircraftInfoBaseInfo.aircraftType + || DJI_AIRCRAFT_TYPE_M4D == aircraftInfoBaseInfo.aircraftType ) { if (DjiTest_PositioningStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("psdk positioning init error"); diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/hal/hal_uart.c b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/hal/hal_uart.c index c913187..d292ec1 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/hal/hal_uart.c +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/hal/hal_uart.c @@ -38,6 +38,18 @@ /* Private constants ---------------------------------------------------------*/ #define COMMUNICATION_UART_NUM UART_NUM_3 +#define HAL_UART_USB_UART_FT232_VID (0x0403) +#define HAL_UART_USB_UART_FT232_PID (0x6001) + +#define HAL_UART_USB_UART_CP2102_VID (0x10C4) +#define HAL_UART_USB_UART_CP2102_PID (0xEA60) + +#define HAL_UART_USB_UART_VCOM_VID (0x2CA3) +#define HAL_UART_USB_UART_VCOM_PID (0xF002) + +#define HAL_UART_USB_UART_VID HAL_UART_USB_UART_FT232_VID +#define HAL_UART_USB_UART_PID HAL_UART_USB_UART_FT232_PID + /* Private types -------------------------------------------------------------*/ typedef enum { USER_UART_NUM0 = 0, @@ -120,6 +132,20 @@ T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *stat return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; } +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo) +{ + + if (deviceInfo == NULL) { + return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; + } + + deviceInfo->vid = HAL_UART_USB_UART_VID; + deviceInfo->pid = HAL_UART_USB_UART_PID; + + return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS; +} + + /* Private functions definition-----------------------------------------------*/ /****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/hal/hal_uart.h b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/hal/hal_uart.h index df46cdd..ee84476 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/hal/hal_uart.h +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/hal/hal_uart.h @@ -47,6 +47,7 @@ T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle); T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen); T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status); +T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo); #ifdef __cplusplus } diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/mdk/mdk_app.uvprojx b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/mdk/mdk_app.uvprojx index 6a59c8f..41c8bd6 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/mdk/mdk_app.uvprojx +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/mdk/mdk_app.uvprojx @@ -935,6 +935,11 @@ 5 +dji_cloud_api_by_websockt.h +..\..\..\..\..\..\..\psdk_lib\include\dji_cloud_api_by_websockt.h + + +5 dji_core.h ..\..\..\..\..\..\..\psdk_lib\include\dji_core.h @@ -1010,6 +1015,11 @@ 5 +dji_open_ar.h +..\..\..\..\..\..\..\psdk_lib\include\dji_open_ar.h + + +5 dji_payload_camera.h ..\..\..\..\..\..\..\psdk_lib\include\dji_payload_camera.h diff --git a/tools/build_dpk/README.md b/tools/build_dpk/README.md new file mode 100644 index 0000000..aad288c --- /dev/null +++ b/tools/build_dpk/README.md @@ -0,0 +1,25 @@ +# build_dpk.sh 1.1 + +# Description +build_dpk.sh is an application packaging tool. It requires an input application configuration json file(app.json), and generates a .dpk application installation package. + +the sample app.json: samples/sample_c/platform/linux/manifold3/app_json/app.json +app.json filling specification: +please refer to samples/sample_c/platform/linux/manifold3/app_json/README.md + +# Environment Dependencies +Python 3 environment is required; +dpkg tool is required. + +# Usage + build_dpk.sh -i input app.json file + [-o output dpk file path] + [-h help]" + Options: + " -h Show this help message and exit" + " -i Specify input app.json file" + " -o Specify build dpk file path" + + Examples: + build_dpk.sh -i ../../samples/sample_c/platform/linux/manifold3/app_json/app.json Generate .dpk application installation package under the current path + build_dpk.sh -i ../../samples/sample_c/platform/linux/manifold3/app_json/app.json -o dpk Generate .dpk application installation package under the specified path(dpk) diff --git a/tools/build_dpk/build_dpk.sh b/tools/build_dpk/build_dpk.sh new file mode 100755 index 0000000..b0db817 --- /dev/null +++ b/tools/build_dpk/build_dpk.sh @@ -0,0 +1,524 @@ +#!/bin/bash + +is_ai_rendering="false" +input_json_file="" +output_dpk_path="./" + +# help +show_help() +{ + echo "Usage: build_dpk.sh -i input app.json file + [-o output dpk file path] + [-h help]" + echo "" + echo "Options:" + echo " -h Show this help message and exit" + echo " -i Specify input app.json file" + echo " -o Specify build dpk file path" + echo "" +} + +# prase parameters +while getopts ":i:o:h" opt; do + case ${opt} in + h) + show_help + exit 0 + ;; + i) + input_json_file=$OPTARG + ;; + o) + output_dpk_path=$OPTARG + ;; + \?) + echo "Invalid option: -$OPTARG" >&1 + show_help + exit 1 + ;; + :) + echo "Option -$OPTARG requires an argument." >&1 + show_help + exit 1 + ;; + esac +done + +# check input json file +if [ -n "$input_json_file" ]; then + echo "-i option is set with value: $input_json_file" +else + show_help + exit 1 +fi + +if [ ! -f "$input_json_file" ]; then + echo "Input file $input_json_file does not exist." + exit 1 +fi + +if [[ "$input_json_file" != *.json ]]; then + echo "Input file $input_json_file is not a .json file." + exit 1 +fi + +echo "Input json file: $input_json_file" + +input_json_dir=$(dirname "$input_json_file") + +# check output path +if [ -n "$output_dpk_path" ]; then + echo "Output dpk file path: $output_dpk_path" +else + echo "Use Default Output dpk path" +fi + +# prase and check id field +id=$(python3 -c "import json; print(json.load(open('$input_json_file'))['user_app_id'])") +if [ "$id" == "" ]; then + echo "Error, user_app_id field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +if [ $(printf "%s" "$id" | wc -c) -gt 16 ]; then + echo "Error, user_app_id field byte count:$(printf "%s" "$id" | wc -c) over 16" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check version field +version_regex='^[0-9]+\.[0-9]+\.[0-9]+\.[0-9]+$' +version=$(python3 -c "import json; print(json.load(open('$input_json_file'))['firmware_version'])") +if [ "$version" == "" ]; then + echo "Error, firmware_version field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [[ ! $version =~ $version_regex ]]; then + echo "Error, firmware_version field not comply with the xx.xx.xx.xx specification" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check platform field +platform=$(python3 -c "import json; print(json.load(open('$input_json_file'))['platform'])") +if [ "$platform" == "" ]; then + echo "Error, platform field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [[ "$platform" != "manifold3" ]]; then + echo "Error, platform field is not manifold3" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check name_cn field +name_cn=$(python3 -c "import json; print(json.load(open('$input_json_file'))['name']['name_cn'])") +if [ "$name_cn" == "" ]; then + echo "Error, name_cn field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$name_cn" | wc -c) -gt 47 ]; then + echo "Error, name_cn field byte count:$(printf "%s" "$name_cn" | wc -c) over 47" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check name_en field +regex='^[a-zA-Z0-9.-]+$' +name_en=$(python3 -c "import json; print(json.load(open('$input_json_file'))['name']['name_en'])") +if [ "$name_en" == "" ]; then + echo "Error, name_en field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$name_en" | wc -c) -gt 32 ]; then + echo "Error, name_en field byte count:$(printf "%s" "$name_en" | wc -c) over 32" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [[ ! $name_en =~ $regex ]]; then + echo "Error, name_en field not comply with the specification" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check name_jp field +name_jp=$(python3 -c "import json; print(json.load(open('$input_json_file'))['name']['name_jp'])") +if [ "$name_jp" == "" ]; then + echo "Error, name_jp field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$name_jp" | wc -c) -gt 47 ]; then + echo "Error, name_jp field byte count:$(printf "%s" "$name_jp" | wc -c) over 47" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check name_fr field +name_fr=$(python3 -c "import json; print(json.load(open('$input_json_file'))['name']['name_fr'])") +if [ "$name_fr" == "" ]; then + echo "Error, name_fr field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$name_fr" | wc -c) -gt 47 ]; then + echo "Error, name_fr field byte count:$(printf "%s" "$name_fr" | wc -c) over 47" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check description_cn field +desc_cn=$(python3 -c " +import json +import sys + +with open('$input_json_file', 'r') as file: + data = json.load(file) +print('\n '.join(data['description']['description_cn'])) +") +if [ "$desc_cn" == "" ]; then + echo "Error, description_cn field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$desc_cn" | wc -c) -gt 367 ]; then + echo "Error, desc_cn field byte count:$(printf "%s" "$desc_cn" | wc -c) over 367" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check description_en field +desc_en=$(python3 -c " +import json +import sys + +with open('$input_json_file', 'r') as file: + data = json.load(file) +print('\n '.join(data['description']['description_en'])) +") +if [ "$desc_en" == "" ]; then + echo "Error, description_en field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$desc_en" | wc -c) -gt 367 ]; then + echo "Error, desc_en field byte count:$(printf "%s" "$desc_en" | wc -c) over 367" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check description_jp field +desc_jp=$(python3 -c " +import json +import sys + +with open('$input_json_file', 'r') as file: + data = json.load(file) +print('\n '.join(data['description']['description_jp'])) +") +if [ "$desc_jp" == "" ]; then + echo "Error, description_jp field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$desc_jp" | wc -c) -gt 367 ]; then + echo "Error, desc_jp field byte count:$(printf "%s" "$desc_jp" | wc -c) over 367" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check description_fr field +desc_fr=$(python3 -c " +import json +import sys + +with open('$input_json_file', 'r') as file: + data = json.load(file) +print('\n '.join(data['description']['description_fr'])) +") +if [ "$desc_fr" == "" ]; then + echo "Error, description_fr field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$desc_fr" | wc -c) -gt 367 ]; then + echo "Error, desc_fr field byte count:$(printf "%s" "$desc_fr" | wc -c) over 367" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check maintainer_cn field +maintainer_cn=$(python3 -c "import json; print(json.load(open('$input_json_file'))['maintainer']['maintainer_cn'])") +if [ "$maintainer_cn" == "" ]; then + echo "Error, maintainer_cn field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$maintainer_cn" | wc -c) -gt 127 ]; then + echo "Error, maintainer_cn field byte count:$(printf "%s" "$maintainer_cn" | wc -c) over 127" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check maintainer_en field +maintainer_en=$(python3 -c "import json; print(json.load(open('$input_json_file'))['maintainer']['maintainer_en'])") +if [ "$maintainer_en" == "" ]; then + echo "Error, maintainer_en field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$maintainer_en" | wc -c) -gt 127 ]; then + echo "Error, maintainer_en field byte count:$(printf "%s" "$maintainer_en" | wc -c) over 127" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check maintainer_jp field +maintainer_jp=$(python3 -c "import json; print(json.load(open('$input_json_file'))['maintainer']['maintainer_jp'])") +if [ "$maintainer_jp" == "" ]; then + echo "Error, maintainer_jp field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$maintainer_jp" | wc -c) -gt 127 ]; then + echo "Error, maintainer_jp field byte count:$(printf "%s" "$maintainer_jp" | wc -c) over 127" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check maintainer_fr field +maintainer_fr=$(python3 -c "import json; print(json.load(open('$input_json_file'))['maintainer']['maintainer_fr'])") +if [ "$maintainer_fr" == "" ]; then + echo "Error, maintainer_fr field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [ $(printf "%s" "$maintainer_fr" | wc -c) -gt 127 ]; then + echo "Error, maintainer_fr field byte count:$(printf "%s" "$maintainer_fr" | wc -c) over 127" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check ver_min field +ver_min=$(python3 -c "import json; print(json.load(open('$input_json_file'))['ver_min'])") +if [ "$ver_min" == "" ]; then + echo "Error, ver_min field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [[ ! $ver_min =~ $version_regex ]]; then + echo "Error, ver_min field not comply with the xx.xx.xx.xx specification" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check ver_maxfield +ver_max=$(python3 -c "import json; print(json.load(open('$input_json_file'))['ver_max'])") +if [ "$ver_max" == "" ]; then + echo "Error, ver_max field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +elif [[ ! $ver_max =~ $version_regex ]]; then + echo "Error, ver_max field not comply with the xx.xx.xx.xx specification" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +fi + +# prase and check bin field +bin_file=$(python3 -c "import json; print(json.load(open('$input_json_file'))['bin'])") +if [ "$bin_file" == "" ]; then + echo "Error, bin field not exist or null" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 +else + bin_source_file="$input_json_dir/$bin_file" + if [ ! -f "$bin_source_file" ]; then + echo "Error, bin field $bin_file not exist" + echo "Please check app.json" + echo "Document Specification: samples/sample_c/platform/linux/manifold3/app_json/README.md" + exit 1 + fi +fi + +# prase and check userconfig field +mapfile -t userconfig_files < <(python3 - < "$package_path"/DEBIAN/control +Id: $id +Package: $name_en +Format_Version: 3 +Is_Ai_Rendering: $is_ai_rendering +Name_CN: $name_cn +Name_EN: $name_en +Name_JP: $name_jp +Name_FR: $name_fr +Description: $desc_en +Description_CN: $desc_cn +Description_EN: $desc_en +Description_JP: $desc_jp +Description_FR: $desc_fr +Version: $version +Platform: $platform +Maintainer: $maintainer_en +Maintainer_CN: $maintainer_cn +Maintainer_EN: $maintainer_en +Maintainer_JP: $maintainer_jp +Maintainer_FR: $maintainer_fr +Architecture: all +Binary: bin/$bin_name +Ver_Min: $ver_min +Ver_Max: $ver_max +EOF + +bin_dest_path="$package_path/bin" +userconfig_dest_path="$package_path" +if ! mkdir "$bin_dest_path"; then + echo "Failed to create $bin_dest_path dir" + rm -rf "$package_path" + exit 1 +fi + +if ! cp "$bin_source_file" "$bin_dest_path"; then + echo "Failed to copy $bin_source_file to $bin_dest_path" + rm -rf "$package_path" + exit 1 +fi + +chmod a+x $bin_dest_path/$bin_name +if [[ $? -ne 0 ]]; then + echo "Failed to add $bin_dest_path/$bin_name excutable permission" + rm -rf "$package_path" + exit 1 +fi + +for userconfig_file in "${userconfig_files[@]}"; do + userconfig_source_file="$input_json_dir/$userconfig_file" + cp -r "$userconfig_source_file" "$userconfig_dest_path" + if [[ $? -ne 0 ]]; then + echo "Failed to copy $userconfig_file to $userconfig_dest_path" + rm -rf "$package_path" + exit 1 + fi +done + +data_path="$package_path/data" +log_path="$package_path/data/logs" +media_path="$package_path/data/media" +if ! mkdir "$data_path"; then + echo "Failed to create $data_path dir" + rm -rf "$package_path" + exit 1 +fi +if ! mkdir "$log_path"; then + echo "Failed to create $log_path dir" + rm -rf "$package_path" + exit 1 +fi +if ! mkdir "$media_path"; then + echo "Failed to create $media_path dir" + rm -rf "$package_path" + exit 1 +fi + +# generate .dpk +old_deb_file="$package_path.deb" +new_dpk_file="$package_path.dpk" +dpkg-deb --build "$package_path" > /dev/null 2>&1 +if [ $? -ne 0 ]; then + echo "Failed to create $old_deb_file" + rm -rf "$package_path" + rm "$old_deb_file" + exit 1 +fi +if ! mv "$old_deb_file" "$new_dpk_file"; then + echo "Failed to create $new_dpk_file" + rm -rf "$package_path" + rm "$old_deb_file" + rm "$new_dpk_file" + exit 1 +fi + +if ! rm -rf "$package_path"; then + echo "Failed to delete $package_path" + exit 1 +fi + +echo "----------------------------" +echo "Successed to create $new_dpk_file!!!" + +exit 0 diff --git a/tools/file2c/file2c.exe b/tools/file2c/file2c.exe old mode 100755 new mode 100644