diff --git a/README.md b/README.md index b027ce3..bc5703a 100644 --- a/README.md +++ b/README.md @@ -44,16 +44,25 @@ This project implements a real-time speed sensor and CAN communication system on - FDCAN1_RX -> PB_8 (CAN_RX) - FDCAN1_TX -> PB_9 (CAN_TX) - TIM1_CH1 -> PA_8 (Sensor speed) - - I2C3 -> PA_7 (SCL) - - I2C3 -> PC_1 (SDA) + - I2C3 SCL -> PA_7 + - I2C3 SDA -> PC_1 # How to Extend The Project - Implement a mechanism to process incoming data and perform the appropriate actions. - - Integrate new thread to communicate via I2C to motors/servo. - Create a Heartbeat mechanism. - Integrate Watchdog timer that resets if the system "breaks". - Integration tests for CAN. - Latency tests + - Redefine diferent prioritys for threads. + +### Creating new Threads + - In app_threadx.h, increase THREAD_COUNT by one, and remember to update the comments above that definition. + + - Don’t forget to add the function prototype in app_threadx.h and to include the new source file in the CMakeLists.txt file. + + - Next, open init_threads.c and initialize your new thread. Follow the existing threads for consistency and simplicity. + + - Finally, implement the functionality of your thread. That’s it, simple as that, you’re now ready to start! Good luck. # Instructions to Build and Flash to STM32 Microcontroller diff --git a/ThreadX_Os/CMakeLists.txt b/ThreadX_Os/CMakeLists.txt index e78e27f..7dbb070 100644 --- a/ThreadX_Os/CMakeLists.txt +++ b/ThreadX_Os/CMakeLists.txt @@ -12,7 +12,6 @@ set(CMAKE_C_STANDARD 11) set(CMAKE_C_STANDARD_REQUIRED ON) set(CMAKE_C_EXTENSIONS ON) - # Define the build type if(NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "Debug") @@ -47,10 +46,18 @@ target_sources(${CMAKE_PROJECT_NAME} PRIVATE # Add user sources here Core/Src/init/init_can.c Core/Src/init/init_threads.c - Core/Src/threads/speedSensor.c - Core/Src/threads/tx_can.c - Core/Src/threads/rx_can.c - Core/Src/utils/speed_rpm.c + Core/Src/threads/can/rx_can.c + Core/Src/threads/can/tx_can.c + Core/Src/threads/motors/dc_motors.c + Core/Src/threads/motors/emergency_brake.c + Core/Src/threads/motors/servo.c + Core/Src/threads/battery.c + Core/Src/threads/speed_sensor.c + Core/Src/utils/debug_utils.c + Core/Src/utils/i2c_utils.c + Core/Src/utils/speed_rpm_utils.c + Core/Src/i2c_ina219.c + Core/Src/i2c_pca9685.c ) # Add include paths diff --git a/ThreadX_Os/Core/Inc/app_threadx.h b/ThreadX_Os/Core/Inc/app_threadx.h index 54a6a5f..f89862b 100644 --- a/ThreadX_Os/Core/Inc/app_threadx.h +++ b/ThreadX_Os/Core/Inc/app_threadx.h @@ -35,15 +35,43 @@ extern "C" { #include #include #include + /* USER CODE END Includes */ /* Exported types ------------------------------------------------------------*/ /* USER CODE BEGIN ET */ +// Thread with max priority +#define MAX_PRIO 0 + +// Thread with medium priority +#define MEDIUM_PRIO 5 + +// Thread with low priority +#define LOW_PRIO 10 + +// Thread with no priority (lowest) +#define NONE_PRIO 15 + +//Queue size (number of messages) +#define QUEUE_SIZE 8 + +/* +Number of threads +1 -> Speed sensor thread +2 -> CAN TX thread +3 -> CAN RX thread +4 -> dc_motors thread +5 -> servo thread +6 -> battery thread +7 -> emergency brake thread +*/ +#define THREAD_COUNT 7 + // Thread structure typedef struct s_threads { TX_THREAD thread; - uint8_t stack[1024]; + UINT stack[1024]; } t_threads; // CAN frames structure @@ -60,10 +88,14 @@ typedef struct s_canFrames { extern FDCAN_HandleTypeDef hfdcan1; extern UART_HandleTypeDef huart1; extern TIM_HandleTypeDef htim1; +extern I2C_HandleTypeDef hi2c3; extern TX_QUEUE can_tx_queue; -extern TX_QUEUE can_rx_queue; -extern t_threads threads[3]; +extern TX_QUEUE can_emergency_brake_queue; +extern TX_QUEUE i2c_dc_motors_queue; +extern TX_QUEUE i2c_servo_queue; +extern TX_MUTEX i2c_mutex; +extern t_threads threads[THREAD_COUNT]; /* USER CODE END EC */ /* Private defines -----------------------------------------------------------*/ @@ -75,12 +107,6 @@ extern t_threads threads[3]; /* Main thread defines -------------------------------------------------------*/ /* USER CODE BEGIN MTD */ -//Thread 0 (Speed Sensor) max priority -#define THREAD_0_PRIO 1 - -//Queue size (number of messages) -#define QUEUE_SIZE 8 - /* USER CODE END MTD */ /* Exported macro ------------------------------------------------------------*/ @@ -98,7 +124,10 @@ void MX_ThreadX_Init(void); VOID thread_SensorSpeed(ULONG thread_input); VOID thread_tx_can(ULONG thread_input); VOID thread_rx_can(ULONG thread_input); -uint8_t rx_receive(t_rx_can_msg *msg); +VOID thread_dc_motors(ULONG thread_input); +VOID thread_servo(ULONG thread_input); +VOID thread_battery(ULONG thread_input); +VOID thread_emergency_brake(ULONG thread_input); //init void initCanFrames(t_canFrames *canFrames); @@ -106,7 +135,11 @@ UINT init_threads(VOID); UINT init_queue(VOID); //utils -VOID uart_send(const char *msg); +VOID uart_send(const char *msg); +VOID uart_send_int(int32_t value); +VOID rpm_debug_print(ULONG rpm, + ULONG cr1_reg, ULONG cnt_reg); +HAL_StatusTypeDef i2c_scan_bus(VOID); /* USER CODE END EFP */ diff --git a/ThreadX_Os/Core/Inc/can_protocol.h b/ThreadX_Os/Core/Inc/can_protocol.h new file mode 100644 index 0000000..4c2f55f --- /dev/null +++ b/ThreadX_Os/Core/Inc/can_protocol.h @@ -0,0 +1,31 @@ +#ifndef CAN_PROTOCOL_H + #define CAN_PROTOCOL_H + +#include "app_threadx.h" + +// CAN message types +typedef enum { + CAN_MSG_SPEED, + CAN_MSG_BATTERY, +} e_can_msg_type; + +// TX CAN message structure (sending) +typedef struct s_tx_can_message { + e_can_msg_type type; + uint8_t data[8]; +} t_tx_can_msg; + +// RX CAN message structure (receiving) +typedef struct s_rx_can_message { + uint32_t type; + uint8_t data[8]; + uint8_t len; +} t_rx_can_msg; + +/* // Steering/throttle CAN message instructions +typedef struct s_i2c_message { + int8_t steering; + int8_t throttle; +} t_i2c_msg; */ + +#endif \ No newline at end of file diff --git a/ThreadX_Os/Core/Inc/i2c_ina219.h b/ThreadX_Os/Core/Inc/i2c_ina219.h new file mode 100644 index 0000000..c13ebbe --- /dev/null +++ b/ThreadX_Os/Core/Inc/i2c_ina219.h @@ -0,0 +1,22 @@ +#ifndef I2C_INA219_H +# define I2C_INA219_H + +#include "app_threadx.h" + +#define INA219_ADDR 0x41 + +#define INA219_REG_CONFIG 0x00 +#define INA219_REG_SHUNT_VOLT 0x01 +#define INA219_REG_BUS_VOLT 0x02 +#define INA219_REG_POWER 0x03 +#define INA219_REG_CURRENT 0x04 +#define INA219_REG_CALIBRATION 0x05 + +#define INA219_CALIBRATION 4096 + +HAL_StatusTypeDef ina219_init(UINT addr); +HAL_StatusTypeDef ina219_read_voltage(float* voltage); +HAL_StatusTypeDef ina219_read_current(float* current); +HAL_StatusTypeDef ina219_read_power(float* power); + +#endif \ No newline at end of file diff --git a/ThreadX_Os/Core/Inc/i2c_pca9685.h b/ThreadX_Os/Core/Inc/i2c_pca9685.h new file mode 100644 index 0000000..7c08ec0 --- /dev/null +++ b/ThreadX_Os/Core/Inc/i2c_pca9685.h @@ -0,0 +1,64 @@ +#ifndef I2C_PCA9685_H +# define I2C_PCA9685_H + +#include "app_threadx.h" + +#define PCA9685_ADDR_SERVO 0x40 +#define PCA9685_ADDR_MOTOR 0x60 + +// PWM resolution and channel range +#define PCA9685_PWM_MAX 4095 + +// PCA9685 channel limits +#define PCA9685_CHANNEL_MIN 0 +#define PCA9685_CHANNEL_MAX 15 + +// PCA9685 register addresses +#define MODE1 0x00 +#define MODE2 0x01 +#define PRE_SCALE 0xFE + +// LED0 registers +#define LED0_ON_L 0x06 +#define LED0_ON_H 0x07 +#define LED0_OFF_L 0x08 +#define LED0_OFF_H 0x09 + +// PCA9685 mode settings +#define PCA9685_SLEEP_MODE 0x10 +#define PCA9685_50HZ_PRESCALE 0x79 +#define PCA9685_1KHZ_PRESCALE 0x05 +#define PCA9685_WAKE_AUTOINC 0x20 + +// Servo pulse limits +#define SERVO_MIN_PULSE 205 +#define SERVO_MAX_PULSE 410 +#define SERVO_MAX_ANGLE 180 + +// Motor speed limits +#define MOTOR_MAX_SPEED 100 + +#define MOTOR_PWM_MIN 0 + +typedef struct s_motor_channel { + UINT pwm_ch; // PWM motor channel + UINT in1_ch; // IN1 channel + UINT in2_ch; // IN2 channel +} t_motor_channel; + +// Predefined motor channels +static const t_motor_channel MOTOR_LEFT = { 0, 1, 2 }; +static const t_motor_channel MOTOR_RIGHT = { 7, 5, 6 }; + +HAL_StatusTypeDef pca9685_init(UINT addr); + +HAL_StatusTypeDef pca9685_set_pwm(UINT channel, + uint16_t on, uint16_t off, UINT addr); + +HAL_StatusTypeDef pca9685_set_servo_angle(UINT channel, UINT angle); + +HAL_StatusTypeDef motor_set(t_motor_channel motor, int8_t speed, uint8_t brake); + +HAL_StatusTypeDef stopMotors(VOID); + +#endif diff --git a/ThreadX_Os/Core/Inc/stm32u5xx_hal_conf.h b/ThreadX_Os/Core/Inc/stm32u5xx_hal_conf.h index dfb402e..d4866aa 100644 --- a/ThreadX_Os/Core/Inc/stm32u5xx_hal_conf.h +++ b/ThreadX_Os/Core/Inc/stm32u5xx_hal_conf.h @@ -51,7 +51,7 @@ extern "C" { /*#define HAL_GTZC_MODULE_ENABLED */ /*#define HAL_HASH_MODULE_ENABLED */ /*#define HAL_HCD_MODULE_ENABLED */ -/*#define HAL_I2C_MODULE_ENABLED */ +#define HAL_I2C_MODULE_ENABLED #define HAL_ICACHE_MODULE_ENABLED /*#define HAL_IRDA_MODULE_ENABLED */ /*#define HAL_IWDG_MODULE_ENABLED */ diff --git a/ThreadX_Os/Core/Inc/tx_user.h b/ThreadX_Os/Core/Inc/tx_user.h index 929444d..df092e5 100644 --- a/ThreadX_Os/Core/Inc/tx_user.h +++ b/ThreadX_Os/Core/Inc/tx_user.h @@ -246,7 +246,7 @@ /* Define the common timer tick reference for use by other middleware components. */ -/*#define TX_TIMER_TICKS_PER_SECOND 100*/ +#define TX_TIMER_TICKS_PER_SECOND 1000 /* Determine if there is a FileX pointer in the thread control block. By default, the pointer is there for legacy/backwards compatibility. diff --git a/ThreadX_Os/Core/Inc/utils.h b/ThreadX_Os/Core/Inc/utils.h index 9f16a9f..0a7cb15 100644 --- a/ThreadX_Os/Core/Inc/utils.h +++ b/ThreadX_Os/Core/Inc/utils.h @@ -8,8 +8,6 @@ typedef uint32_t UINT; typedef uint32_t ULONG; typedef void VOID; - #define TX_SUCCESS 0 - #define TX_QUEUE_ERROR 1 #endif // Timer ticks per second definition @@ -17,31 +15,11 @@ #define TX_TIMER_TICKS_PER_SECOND 1000 #endif -// CAN message types -typedef enum { - CAN_MSG_SPEED, - CAN_MSG_BATTERY, - CAN_MSG_HEARTBEAT, -} e_can_msg_type; - -// TX CAN message structure -typedef struct s_tx_can_message { - e_can_msg_type type; - uint8_t data[8]; -} t_tx_can_msg; - -// RX CAN message structure -typedef struct s_rx_can_message { - uint32_t type; - uint8_t data[8]; - uint8_t len; -} t_rx_can_msg; - //Maximum RPM value to prevent overflow -#define MAX_RPM 5000 +#define MAX_RPM 10000 //Pulses Per Revolution -#define PPR 20 +#define PPR 40 // RPM calculation state, created for hardware abstraction and testability typedef struct s_rpm_state { @@ -50,10 +28,7 @@ typedef struct s_rpm_state { UINT first_run; } t_rpm_state; -UINT convertValuesRPM( - ULONG count, - ULONG ticks, - ULONG period, - t_rpm_state *state); +UINT convertValuesRPM(ULONG count, ULONG ticks, + ULONG period, t_rpm_state *state); #endif \ No newline at end of file diff --git a/ThreadX_Os/Core/Src/app_threadx.c b/ThreadX_Os/Core/Src/app_threadx.c index c421de5..a9924e2 100644 --- a/ThreadX_Os/Core/Src/app_threadx.c +++ b/ThreadX_Os/Core/Src/app_threadx.c @@ -23,7 +23,7 @@ /* Private includes ----------------------------------------------------------*/ /* USER CODE BEGIN Includes */ -#include "main.h" +#include "can_protocol.h" /* USER CODE END Includes */ /* Private typedef -----------------------------------------------------------*/ @@ -46,8 +46,11 @@ /* Private variables ---------------------------------------------------------*/ /* USER CODE BEGIN PV */ TX_QUEUE can_tx_queue; -TX_QUEUE can_rx_queue; -t_threads threads[3]; +TX_QUEUE can_emergency_brake_queue; +TX_QUEUE i2c_dc_motors_queue; +TX_QUEUE i2c_servo_queue; +TX_MUTEX i2c_mutex; +t_threads threads[THREAD_COUNT]; /* USER CODE BEGIN PD */ @@ -68,6 +71,7 @@ UINT App_ThreadX_Init(VOID *memory_ptr) UINT ret = TX_SUCCESS; /* USER CODE BEGIN App_ThreadX_MEM_POOL */ + // Create TX queue ret = tx_queue_create(&can_tx_queue, "CAN TX Queue", sizeof(t_tx_can_msg) / sizeof(ULONG), @@ -75,20 +79,38 @@ UINT App_ThreadX_Init(VOID *memory_ptr) if (ret != TX_SUCCESS) uart_send("ERROR! Failed TX queue creation.\r\n"); - // Create RX queue - UCHAR *rx_queue_memory = (UCHAR *)memory_ptr + QUEUE_SIZE * sizeof(t_tx_can_msg); - ret = tx_queue_create(&can_rx_queue, "CAN RX Queue", + // Create Emergency Brake queue + UCHAR *can_emergency_brake_queue_memory = (UCHAR *)memory_ptr + QUEUE_SIZE * sizeof(t_tx_can_msg); + ret = tx_queue_create(&can_emergency_brake_queue, "CAN RX Queue", + sizeof(t_rx_can_msg) / sizeof(ULONG), + can_emergency_brake_queue_memory, QUEUE_SIZE * sizeof(t_rx_can_msg)); + if (ret != TX_SUCCESS) + uart_send("ERROR! Failed Emergency Brake queue creation.\r\n"); + + // Create I2C DC Motors queue + UCHAR *i2c_motors_queue_memory = can_emergency_brake_queue_memory + QUEUE_SIZE * sizeof(t_rx_can_msg); + ret = tx_queue_create(&i2c_dc_motors_queue, "I2C DC Motors Queue", sizeof(t_rx_can_msg) / sizeof(ULONG), - rx_queue_memory, QUEUE_SIZE * sizeof(t_rx_can_msg)); + i2c_motors_queue_memory, QUEUE_SIZE * sizeof(t_rx_can_msg)); if (ret != TX_SUCCESS) - uart_send("ERROR! Failed RX queue creation.\r\n"); + uart_send("ERROR! Failed I2C DC Motors queue creation.\r\n"); + + // Create I2C Servo queue + UCHAR *i2c_servo_queue_memory = i2c_motors_queue_memory + QUEUE_SIZE * sizeof(t_rx_can_msg); + ret = tx_queue_create(&i2c_servo_queue, "I2C Servo Queue", + sizeof(t_rx_can_msg) / sizeof(ULONG), + i2c_servo_queue_memory, QUEUE_SIZE * sizeof(t_rx_can_msg)); + if (ret != TX_SUCCESS) + uart_send("ERROR! Failed I2C Servo queue creation.\r\n"); if (init_threads() != TX_SUCCESS) exit(EXIT_FAILURE); + else + uart_send("\r\n=== ThreadX Initialized ===\r\n"); /* USER CODE END App_ThreadX_MEM_POOL */ /* USER CODE BEGIN App_ThreadX_Init */ - uart_send("\r\n=== ThreadX Initialized ===\r\n"); + /* USER CODE END App_ThreadX_Init */ return ret; @@ -113,10 +135,4 @@ void MX_ThreadX_Init(void) /* USER CODE BEGIN 1 */ -// Function to send a string over UART -void uart_send(const char *msg) -{ - HAL_UART_Transmit(&huart1, (uint8_t*)msg, strlen(msg), 100); -} - /* USER CODE END 1 */ diff --git a/ThreadX_Os/Core/Src/i2c_ina219.c b/ThreadX_Os/Core/Src/i2c_ina219.c new file mode 100644 index 0000000..ec97064 --- /dev/null +++ b/ThreadX_Os/Core/Src/i2c_ina219.c @@ -0,0 +1,115 @@ +#include "i2c_ina219.h" + +HAL_StatusTypeDef ina219_init(UINT addr) { + + HAL_StatusTypeDef status; + uint8_t data[2]; + + // Config: + // Bus voltage range = 32V + // Gain = /8 (320mV shunt) + // Bus ADC = 12bit + // Shunt ADC = 12bit + // Mode = Shunt + Bus continuous + uint16_t config = 0x019F; + + data[0] = (config >> 8) & 0xFF; + data[1] = config & 0xFF; + + tx_mutex_get(&i2c_mutex, TX_WAIT_FOREVER); + + status = HAL_I2C_Mem_Write(&hi2c3, + addr << 1, + INA219_REG_CONFIG, + I2C_MEMADD_SIZE_8BIT, + data, 2, 100); + + if (status != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return status; + } + + // Calibration + data[0] = (INA219_CALIBRATION >> 8) & 0xFF; + data[1] = INA219_CALIBRATION & 0xFF; + + status = HAL_I2C_Mem_Write(&hi2c3, + addr << 1, + INA219_REG_CALIBRATION, + I2C_MEMADD_SIZE_8BIT, + data, 2, 100); + + tx_mutex_put(&i2c_mutex); + return status; +} + +HAL_StatusTypeDef ina219_read_voltage(float *voltage) +{ + uint8_t buf[2]; + uint16_t raw; + + tx_mutex_get(&i2c_mutex, TX_WAIT_FOREVER); + + if (HAL_I2C_Mem_Read(&hi2c3, + INA219_ADDR << 1, + INA219_REG_BUS_VOLT, + I2C_MEMADD_SIZE_8BIT, + buf, 2, 100) != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return HAL_ERROR; + } + + raw = (buf[0] << 8) | buf[1]; + raw >>= 3; // remove flags + + *voltage = raw * 0.004f; // 4mV per bit + + return HAL_OK; +} + +HAL_StatusTypeDef ina219_read_current(float *current) +{ + uint8_t buf[2]; + int16_t raw; + + tx_mutex_get(&i2c_mutex, TX_WAIT_FOREVER); + + if (HAL_I2C_Mem_Read(&hi2c3, + INA219_ADDR << 1, + INA219_REG_CURRENT, + I2C_MEMADD_SIZE_8BIT, + buf, 2, 100) != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return HAL_ERROR; + } + tx_mutex_put(&i2c_mutex); + + raw = (buf[0] << 8) | buf[1]; + + *current = raw * 0.1f; // 0.1mA per bit + + return HAL_OK; +} + +HAL_StatusTypeDef ina219_read_power(float *power) +{ + uint8_t buf[2]; + uint16_t raw; + + tx_mutex_get(&i2c_mutex, TX_WAIT_FOREVER); + + if (HAL_I2C_Mem_Read(&hi2c3, + INA219_ADDR << 1, + INA219_REG_POWER, + I2C_MEMADD_SIZE_8BIT, + buf, 2, 100) != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return HAL_ERROR; + } + tx_mutex_put(&i2c_mutex); + raw = (buf[0] << 8) | buf[1]; + + *power = raw * 2.0f; // 2mW per bit + + return HAL_OK; +} diff --git a/ThreadX_Os/Core/Src/i2c_pca9685.c b/ThreadX_Os/Core/Src/i2c_pca9685.c new file mode 100644 index 0000000..801c633 --- /dev/null +++ b/ThreadX_Os/Core/Src/i2c_pca9685.c @@ -0,0 +1,191 @@ +#include "i2c_pca9685.h" + +static HAL_StatusTypeDef error_return(const char *msg) { + if (!msg) + uart_send("PCA9685: I2C communication error\r\n"); + else + uart_send(msg); + return (HAL_ERROR); +} + +HAL_StatusTypeDef pca9685_init(UINT addr) { + + HAL_StatusTypeDef status; + uint8_t data; + + tx_mutex_get(&i2c_mutex, TX_WAIT_FOREVER); + + i2c_scan_bus(); + // Set to sleep mode to configure prescaler + data = PCA9685_SLEEP_MODE; + status = HAL_I2C_Mem_Write(&hi2c3, addr << 1, + MODE1, I2C_MEMADD_SIZE_8BIT, + &data, 1, 100); + if (status != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return (error_return("PCA9685: Failed to enter sleep mode\r\n")); + } + + if (addr == PCA9685_ADDR_SERVO) + { + // 50Hz for servos + data = PCA9685_50HZ_PRESCALE; + status = HAL_I2C_Mem_Write(&hi2c3, addr << 1, + PRE_SCALE, I2C_MEMADD_SIZE_8BIT, + &data, 1, 100); + if (status != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return (error_return("PCA9685: Failed to set prescaler\r\n")); + } + } + else if (addr == PCA9685_ADDR_MOTOR) + { + // 1KHz for DC motors + data = PCA9685_1KHZ_PRESCALE; + status = HAL_I2C_Mem_Write(&hi2c3, addr << 1, + PRE_SCALE, I2C_MEMADD_SIZE_8BIT, + &data, 1, 100); + if (status != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return (error_return("PCA9685: Failed to set prescaler\r\n")); + } + } + + // Wake up & auto increment + data = PCA9685_WAKE_AUTOINC; + status = HAL_I2C_Mem_Write(&hi2c3, addr << 1, + MODE1, I2C_MEMADD_SIZE_8BIT, + &data, 1, 100); + if (status != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return (error_return("PCA9685: Failed to exit sleep mode\r\n")); + } + + tx_mutex_put(&i2c_mutex); + return (status); +} + +HAL_StatusTypeDef pca9685_set_servo_angle(UINT channel, UINT angle) +{ + uint16_t pulse; + + if (angle > SERVO_MAX_ANGLE) + angle = SERVO_MAX_ANGLE; + + pulse = SERVO_MIN_PULSE + + ((SERVO_MAX_PULSE - SERVO_MIN_PULSE) * angle) + / SERVO_MAX_ANGLE; + + return (pca9685_set_pwm(channel, 0, pulse, PCA9685_ADDR_SERVO)); +} + +HAL_StatusTypeDef pca9685_set_pwm(UINT channel, + uint16_t on, uint16_t off, UINT addr) +{ + HAL_StatusTypeDef status; + uint8_t buf[4]; + uint8_t reg; + + // Buffer preparation with LSB / MSB + buf[0] = on & 0xFF; // ON_L + buf[1] = (on >> 8) & 0x0F; // ON_H + buf[2] = off & 0xFF; // OFF_L + buf[3] = (off >> 8) & 0x0F; // OFF_H + + reg = LED0_ON_L + 4 * channel; + + tx_mutex_get(&i2c_mutex, TX_WAIT_FOREVER); + + status = HAL_I2C_Mem_Write(&hi2c3, addr << 1, + reg, I2C_MEMADD_SIZE_8BIT, + buf, 4, 500); + + if (status != HAL_OK) { + tx_mutex_put(&i2c_mutex); + return (error_return("PCA9685: Failed to set PWM\r\n")); + } + + tx_mutex_put(&i2c_mutex); + return (HAL_OK); +} + +HAL_StatusTypeDef motor_set(t_motor_channel motor, int8_t speed, uint8_t brake) +{ + uint16_t pwm; + + // Fast stop (active brake) + if (brake) { + // Both IN1 and IN2 high, PWM 0 + if (pca9685_set_pwm(motor.in1_ch, 0, PCA9685_PWM_MAX, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to brake motor (in1)\r\n")); + } + if (pca9685_set_pwm(motor.in2_ch, 0, PCA9685_PWM_MAX, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to brake motor (in2)\r\n")); + } + if (pca9685_set_pwm(motor.pwm_ch, 0, 0, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to brake motor (pwm)\r\n")); + } + return (HAL_OK); + } + + // Speed limits + if (speed > MOTOR_MAX_SPEED) speed = MOTOR_MAX_SPEED; + if (speed < -MOTOR_MAX_SPEED) speed = -MOTOR_MAX_SPEED; + + // Stop motor (coast) + if (speed == 0) { + if (pca9685_set_pwm(motor.in1_ch, 0, 0, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to stop motor (in1)\r\n")); + } + if (pca9685_set_pwm(motor.in2_ch, 0, 0, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to stop motor (in2)\r\n")); + } + if (pca9685_set_pwm(motor.pwm_ch, 0, 0, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to stop motor (pwm)\r\n")); + } + return (HAL_OK); + } + + // Determine direction + if (speed > 0) { + // Forward + if (pca9685_set_pwm(motor.in1_ch, 0, PCA9685_PWM_MAX, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to set motor direction (in1)\r\n")); + } + if (pca9685_set_pwm(motor.in2_ch, 0, MOTOR_PWM_MIN, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to set motor direction (in2)\r\n")); + } + } else { + // Reverse + speed = -speed; + if (pca9685_set_pwm(motor.in1_ch, 0, MOTOR_PWM_MIN, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to set motor direction (in1)\r\n")); + } + if (pca9685_set_pwm(motor.in2_ch, 0, PCA9685_PWM_MAX, PCA9685_ADDR_MOTOR) != HAL_OK) { + return (error_return("PCA9685: Failed to set motor direction (in2)\r\n")); + } + } + + // PWM proportional to speed + pwm = (PCA9685_PWM_MAX * speed) / MOTOR_MAX_SPEED; + + if (pca9685_set_pwm(motor.pwm_ch, 0, pwm, PCA9685_ADDR_MOTOR) != HAL_OK) + return (error_return("PCA9685: Failed to set motor PWM\r\n")); + + return (HAL_OK); +} + +HAL_StatusTypeDef stopMotors(VOID) +{ + HAL_StatusTypeDef status; + + status = motor_set(MOTOR_LEFT, 0, 1); + if (status != HAL_OK) + return (status); + + status = motor_set(MOTOR_RIGHT, 0, 1); + if (status != HAL_OK) + return (status); + + return (HAL_OK); +} diff --git a/ThreadX_Os/Core/Src/init/init_can.c b/ThreadX_Os/Core/Src/init/init_can.c index a9f7cc3..7ab1165 100644 --- a/ThreadX_Os/Core/Src/init/init_can.c +++ b/ThreadX_Os/Core/Src/init/init_can.c @@ -1,33 +1,18 @@ #include "app_threadx.h" -static void TxHeartBeatConf(FDCAN_TxHeaderTypeDef *TxHeader); static void TxSpeedConf(FDCAN_TxHeaderTypeDef *TxHeader); static void TxBatteryConf(FDCAN_TxHeaderTypeDef *TxHeader); // Configuration of CAN frame for speed data void initCanFrames(t_canFrames *canFrames) { - TxHeartBeatConf(&canFrames->tx_header_heart_beat); TxSpeedConf(&canFrames->tx_header_speed); TxBatteryConf(&canFrames->tx_header_battery); } -static void TxHeartBeatConf(FDCAN_TxHeaderTypeDef *TxHeader) -{ - TxHeader->Identifier = 0x200; - TxHeader->IdType = FDCAN_STANDARD_ID; - TxHeader->TxFrameType = FDCAN_DATA_FRAME; - TxHeader->DataLength = FDCAN_DLC_BYTES_8; - TxHeader->ErrorStateIndicator = FDCAN_ESI_ACTIVE; - TxHeader->BitRateSwitch = FDCAN_BRS_OFF; - TxHeader->FDFormat = FDCAN_CLASSIC_CAN; - TxHeader->TxEventFifoControl = FDCAN_NO_TX_EVENTS; - TxHeader->MessageMarker = 0x0; -} - static void TxSpeedConf(FDCAN_TxHeaderTypeDef *TxHeader) { - TxHeader->Identifier = 0x201; + TxHeader->Identifier = 0x200; TxHeader->IdType = FDCAN_STANDARD_ID; TxHeader->TxFrameType = FDCAN_DATA_FRAME; TxHeader->DataLength = FDCAN_DLC_BYTES_8; @@ -40,7 +25,7 @@ static void TxSpeedConf(FDCAN_TxHeaderTypeDef *TxHeader) static void TxBatteryConf(FDCAN_TxHeaderTypeDef *TxHeader) { - TxHeader->Identifier = 0x202; + TxHeader->Identifier = 0x201; TxHeader->IdType = FDCAN_STANDARD_ID; TxHeader->TxFrameType = FDCAN_DATA_FRAME; TxHeader->DataLength = FDCAN_DLC_BYTES_8; diff --git a/ThreadX_Os/Core/Src/init/init_threads.c b/ThreadX_Os/Core/Src/init/init_threads.c index b196ad1..4b831f8 100644 --- a/ThreadX_Os/Core/Src/init/init_threads.c +++ b/ThreadX_Os/Core/Src/init/init_threads.c @@ -1,37 +1,87 @@ #include "app_threadx.h" // Function to initialize and create threads -UINT init_threads(VOID) +UINT init_threads(VOID) { - UINT ret = TX_SUCCESS; + UINT ret = TX_SUCCESS; // Sensor speed thread ret = tx_thread_create(&threads[0].thread, "CANThread", thread_SensorSpeed, 0, threads[0].stack, 1024, - THREAD_0_PRIO, THREAD_0_PRIO, + NONE_PRIO, NONE_PRIO, TX_NO_TIME_SLICE, TX_AUTO_START); if (ret != TX_SUCCESS) uart_send("ERROR! Speed sensor thread creation failed!\r\n"); + else + uart_send("Speed Sensor Thread created successfully.\r\n"); // CAN TX thread ret = tx_thread_create(&threads[1].thread, "TxCanThread", thread_tx_can, 0, threads[1].stack, 1024, - THREAD_0_PRIO, THREAD_0_PRIO, + LOW_PRIO, LOW_PRIO, TX_NO_TIME_SLICE, TX_AUTO_START); if (ret != TX_SUCCESS) uart_send("ERROR! CAN TX thread creation failed!\r\n"); + else + uart_send("CAN TX Thread created successfully.\r\n"); // CAN RX thread ret = tx_thread_create(&threads[2].thread, "RxCanThread", thread_rx_can, 0, threads[2].stack, 1024, - THREAD_0_PRIO, THREAD_0_PRIO, + MEDIUM_PRIO, MEDIUM_PRIO, TX_NO_TIME_SLICE, TX_AUTO_START); - uart_send("Creating RX CAN thread...\r\n"); + if (ret != TX_SUCCESS) uart_send("ERROR! CAN RX thread creation failed!\r\n"); + else + uart_send("CAN RX Thread created successfully.\r\n"); + + // DC Motors thread + ret = tx_thread_create(&threads[3].thread, "DCMotorsThread", thread_dc_motors, 0, + threads[3].stack, 1024, + MAX_PRIO, MAX_PRIO, + TX_NO_TIME_SLICE, + TX_AUTO_START); + if (ret != TX_SUCCESS) + uart_send("ERROR! DC Motors thread creation failed!\r\n"); + else + uart_send("DC Motors Thread created successfully.\r\n"); + + // Servo thread + ret = tx_thread_create(&threads[4].thread, "ServoThread", thread_servo, 0, + threads[4].stack, 1024, + MEDIUM_PRIO, MEDIUM_PRIO, + TX_NO_TIME_SLICE, + TX_AUTO_START); + if (ret != TX_SUCCESS) + uart_send("ERROR! Servo thread creation failed!\r\n"); + else + uart_send("Servo Thread created successfully.\r\n"); + + // Emergency brake thread + ret = tx_thread_create(&threads[5].thread, "EmergencyBrakeThread", thread_emergency_brake, 0, + threads[5].stack, 1024, + MAX_PRIO, MAX_PRIO, + TX_NO_TIME_SLICE, + TX_AUTO_START); + if (ret != TX_SUCCESS) + uart_send("ERROR! Emergency Brake thread creation failed!\r\n"); + else + uart_send("Emergency Brake Thread created successfully.\r\n"); + +/* // Battery thread + ret = tx_thread_create(&threads[6].thread, "BatteryThread", thread_battery, 0, + threads[6].stack, 1024, + NONE_PRIO, NONE_PRIO, + TX_NO_TIME_SLICE, + TX_AUTO_START); + if (ret != TX_SUCCESS) + uart_send("ERROR! Battery thread creation failed!\r\n"); + else + uart_send("Battery Thread created successfully.\r\n"); */ return (ret); } diff --git a/ThreadX_Os/Core/Src/main.c b/ThreadX_Os/Core/Src/main.c index ffbf7ab..3aa14ec 100644 --- a/ThreadX_Os/Core/Src/main.c +++ b/ThreadX_Os/Core/Src/main.c @@ -44,6 +44,8 @@ FDCAN_HandleTypeDef hfdcan1; +I2C_HandleTypeDef hi2c3; + TIM_HandleTypeDef htim1; UART_HandleTypeDef huart1; @@ -58,8 +60,9 @@ static void SystemPower_Config(void); static void MX_GPIO_Init(void); static void MX_ICACHE_Init(void); static void MX_USART1_UART_Init(void); -static void MX_FDCAN1_Init(void); static void MX_TIM1_Init(void); +static void MX_FDCAN1_Init(void); +static void MX_I2C3_Init(void); /* USER CODE BEGIN PFP */ /* USER CODE END PFP */ @@ -103,8 +106,9 @@ int main(void) MX_GPIO_Init(); MX_ICACHE_Init(); MX_USART1_UART_Init(); - MX_FDCAN1_Init(); MX_TIM1_Init(); + MX_FDCAN1_Init(); + MX_I2C3_Init(); /* USER CODE BEGIN 2 */ /* USER CODE END 2 */ @@ -135,7 +139,7 @@ void SystemClock_Config(void) /** Configure the main internal regulator output voltage */ - if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1) != HAL_OK) + if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE2) != HAL_OK) { Error_Handler(); } @@ -145,16 +149,16 @@ void SystemClock_Config(void) RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_MSI; RCC_OscInitStruct.MSIState = RCC_MSI_ON; RCC_OscInitStruct.MSICalibrationValue = RCC_MSICALIBRATION_DEFAULT; - RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_4; + RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_0; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_MSI; - RCC_OscInitStruct.PLL.PLLMBOOST = RCC_PLLMBOOST_DIV1; - RCC_OscInitStruct.PLL.PLLM = 1; - RCC_OscInitStruct.PLL.PLLN = 80; + RCC_OscInitStruct.PLL.PLLMBOOST = RCC_PLLMBOOST_DIV4; + RCC_OscInitStruct.PLL.PLLM = 3; + RCC_OscInitStruct.PLL.PLLN = 9; RCC_OscInitStruct.PLL.PLLP = 2; - RCC_OscInitStruct.PLL.PLLQ = 2; + RCC_OscInitStruct.PLL.PLLQ = 4; RCC_OscInitStruct.PLL.PLLR = 2; - RCC_OscInitStruct.PLL.PLLRGE = RCC_PLLVCIRANGE_0; + RCC_OscInitStruct.PLL.PLLRGE = RCC_PLLVCIRANGE_1; RCC_OscInitStruct.PLL.PLLFRACN = 0; if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { @@ -172,7 +176,7 @@ void SystemClock_Config(void) RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; RCC_ClkInitStruct.APB3CLKDivider = RCC_HCLK_DIV1; - if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK) + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { Error_Handler(); } @@ -224,15 +228,15 @@ static void MX_FDCAN1_Init(void) hfdcan1.Init.AutoRetransmission = ENABLE; hfdcan1.Init.TransmitPause = DISABLE; hfdcan1.Init.ProtocolException = DISABLE; - hfdcan1.Init.NominalPrescaler = 16; + hfdcan1.Init.NominalPrescaler = 4; hfdcan1.Init.NominalSyncJumpWidth = 1; - hfdcan1.Init.NominalTimeSeg1 = 13; - hfdcan1.Init.NominalTimeSeg2 = 6; + hfdcan1.Init.NominalTimeSeg1 = 15; + hfdcan1.Init.NominalTimeSeg2 = 2; hfdcan1.Init.DataPrescaler = 1; hfdcan1.Init.DataSyncJumpWidth = 1; hfdcan1.Init.DataTimeSeg1 = 1; hfdcan1.Init.DataTimeSeg2 = 1; - hfdcan1.Init.StdFiltersNbr = 1; + hfdcan1.Init.StdFiltersNbr = 0; hfdcan1.Init.ExtFiltersNbr = 0; hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_QUEUE_OPERATION; if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) @@ -240,33 +244,59 @@ static void MX_FDCAN1_Init(void) Error_Handler(); } /* USER CODE BEGIN FDCAN1_Init 2 */ + if (HAL_FDCAN_Start(&hfdcan1) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE END FDCAN1_Init 2 */ + +} + +/** + * @brief I2C3 Initialization Function + * @param None + * @retval None + */ +static void MX_I2C3_Init(void) +{ + + /* USER CODE BEGIN I2C3_Init 0 */ + + /* USER CODE END I2C3_Init 0 */ + + /* USER CODE BEGIN I2C3_Init 1 */ - FDCAN_FilterTypeDef filterConfig; - filterConfig.IdType = FDCAN_STANDARD_ID; - filterConfig.FilterIndex = 0; - filterConfig.FilterType = FDCAN_FILTER_RANGE; - filterConfig.FilterConfig = FDCAN_FILTER_TO_RXFIFO0; - filterConfig.FilterID1 = 0x100; - filterConfig.FilterID2 = 0x250; - - if (HAL_FDCAN_ConfigFilter(&hfdcan1, &filterConfig) != HAL_OK) + /* USER CODE END I2C3_Init 1 */ + hi2c3.Instance = I2C3; + hi2c3.Init.Timing = 0x10808DD3; + hi2c3.Init.OwnAddress1 = 0; + hi2c3.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; + hi2c3.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; + hi2c3.Init.OwnAddress2 = 0; + hi2c3.Init.OwnAddress2Masks = I2C_OA2_NOMASK; + hi2c3.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; + hi2c3.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE; + if (HAL_I2C_Init(&hi2c3) != HAL_OK) { - Error_Handler(); + Error_Handler(); } - - // Enable RX FIFO 0 new message notification - if (HAL_FDCAN_ActivateNotification(&hfdcan1, FDCAN_IT_RX_FIFO0_NEW_MESSAGE, 0) != HAL_OK) + + /** Configure Analogue filter + */ + if (HAL_I2CEx_ConfigAnalogFilter(&hi2c3, I2C_ANALOGFILTER_ENABLE) != HAL_OK) { - Error_Handler(); + Error_Handler(); } - // Start FDCAN peripheral - if (HAL_FDCAN_Start(&hfdcan1) != HAL_OK) + /** Configure Digital filter + */ + if (HAL_I2CEx_ConfigDigitalFilter(&hi2c3, 0) != HAL_OK) { - Error_Handler(); + Error_Handler(); } + /* USER CODE BEGIN I2C3_Init 2 */ - /* USER CODE END FDCAN1_Init 2 */ + /* USER CODE END I2C3_Init 2 */ } @@ -333,7 +363,7 @@ static void MX_TIM1_Init(void) } sSlaveConfig.SlaveMode = TIM_SLAVEMODE_EXTERNAL1; sSlaveConfig.InputTrigger = TIM_TS_TI1FP1; - sSlaveConfig.TriggerPolarity = TIM_TRIGGERPOLARITY_FALLING; + sSlaveConfig.TriggerPolarity = TIM_TRIGGERPOLARITY_RISING; sSlaveConfig.TriggerFilter = 15; if (HAL_TIM_SlaveConfigSynchro(&htim1, &sSlaveConfig) != HAL_OK) { @@ -524,14 +554,6 @@ static void MX_GPIO_Init(void) GPIO_InitStruct.Pull = GPIO_NOPULL; HAL_GPIO_Init(USER_Button_GPIO_Port, &GPIO_InitStruct); - /*Configure GPIO pins : PH4 PH5 */ - GPIO_InitStruct.Pin = GPIO_PIN_4|GPIO_PIN_5; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStruct.Alternate = GPIO_AF4_I2C2; - HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); - /*Configure GPIO pins : LED_RED_Pin LED_GREEN_Pin Mems_VL53_xshut_Pin */ GPIO_InitStruct.Pin = LED_RED_Pin|LED_GREEN_Pin|Mems_VL53_xshut_Pin; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; @@ -586,22 +608,6 @@ static void MX_GPIO_Init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; HAL_GPIO_Init(WRLS_WKUP_B_GPIO_Port, &GPIO_InitStruct); - /*Configure GPIO pin : PC1 */ - GPIO_InitStruct.Pin = GPIO_PIN_1; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStruct.Alternate = GPIO_AF4_I2C3; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - - /*Configure GPIO pin : PA7 */ - GPIO_InitStruct.Pin = GPIO_PIN_7; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - GPIO_InitStruct.Alternate = GPIO_AF4_I2C3; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - /*Configure GPIO pins : WRLS_NOTIFY_Pin Mems_INT_IIS2MDC_Pin USB_IANA_Pin */ GPIO_InitStruct.Pin = WRLS_NOTIFY_Pin|Mems_INT_IIS2MDC_Pin|USB_IANA_Pin; GPIO_InitStruct.Mode = GPIO_MODE_INPUT; diff --git a/ThreadX_Os/Core/Src/stm32u5xx_hal_msp.c b/ThreadX_Os/Core/Src/stm32u5xx_hal_msp.c index a15dd6a..cf0c008 100644 --- a/ThreadX_Os/Core/Src/stm32u5xx_hal_msp.c +++ b/ThreadX_Os/Core/Src/stm32u5xx_hal_msp.c @@ -154,6 +154,92 @@ void HAL_FDCAN_MspDeInit(FDCAN_HandleTypeDef* hfdcan) } +/** + * @brief I2C MSP Initialization + * This function configures the hardware resources used in this example + * @param hi2c: I2C handle pointer + * @retval None + */ +void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c) +{ + GPIO_InitTypeDef GPIO_InitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + if(hi2c->Instance==I2C3) + { + /* USER CODE BEGIN I2C3_MspInit 0 */ + + /* USER CODE END I2C3_MspInit 0 */ + + /** Initializes the peripherals clock + */ + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C3; + PeriphClkInit.I2c3ClockSelection = RCC_I2C3CLKSOURCE_PCLK3; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOA_CLK_ENABLE(); + /**I2C3 GPIO Configuration + PC1 ------> I2C3_SDA + PA7 ------> I2C3_SCL + */ + GPIO_InitStruct.Pin = GPIO_PIN_1; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF4_I2C3; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + GPIO_InitStruct.Pin = GPIO_PIN_7; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF4_I2C3; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Peripheral clock enable */ + __HAL_RCC_I2C3_CLK_ENABLE(); + /* USER CODE BEGIN I2C3_MspInit 1 */ + + /* USER CODE END I2C3_MspInit 1 */ + + } + +} + +/** + * @brief I2C MSP De-Initialization + * This function freeze the hardware resources used in this example + * @param hi2c: I2C handle pointer + * @retval None + */ +void HAL_I2C_MspDeInit(I2C_HandleTypeDef* hi2c) +{ + if(hi2c->Instance==I2C3) + { + /* USER CODE BEGIN I2C3_MspDeInit 0 */ + + /* USER CODE END I2C3_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_I2C3_CLK_DISABLE(); + + /**I2C3 GPIO Configuration + PC1 ------> I2C3_SDA + PA7 ------> I2C3_SCL + */ + HAL_GPIO_DeInit(GPIOC, GPIO_PIN_1); + + HAL_GPIO_DeInit(GPIOA, GPIO_PIN_7); + + /* USER CODE BEGIN I2C3_MspDeInit 1 */ + + /* USER CODE END I2C3_MspDeInit 1 */ + } + +} + /** * @brief TIM_Base MSP Initialization * This function configures the hardware resources used in this example diff --git a/ThreadX_Os/Core/Src/threads/battery.c b/ThreadX_Os/Core/Src/threads/battery.c new file mode 100644 index 0000000..d43603c --- /dev/null +++ b/ThreadX_Os/Core/Src/threads/battery.c @@ -0,0 +1,26 @@ +#include "i2c_ina219.h" +#include "can_protocol.h" + +VOID thread_battery(ULONG thread_input) +{ + float vbat; + + uart_send("Battery Thread started\r\n"); + + if (ina219_init(INA219_ADDR) != HAL_OK) { + uart_send("Battery Thread: INA219 init failed\r\n"); + return; + } + + while (1) { + if (ina219_read_voltage(&vbat) == HAL_OK) { + uart_send("Battery Voltage: "); + uart_send_int((int32_t)(vbat * 1000)); // in mV + uart_send(" mV\r\n"); + } else { + uart_send("Battery Thread: INA219 read voltage failed\r\n"); + } + + tx_thread_sleep(100); // Sleep for 100 ticks + } +} diff --git a/ThreadX_Os/Core/Src/threads/can/rx_can.c b/ThreadX_Os/Core/Src/threads/can/rx_can.c new file mode 100644 index 0000000..dfa0b02 --- /dev/null +++ b/ThreadX_Os/Core/Src/threads/can/rx_can.c @@ -0,0 +1,53 @@ +#include "can_protocol.h" + +// CAN RX callback function +static HAL_StatusTypeDef rx_receive(t_rx_can_msg *msg) +{ + FDCAN_RxHeaderTypeDef rxHeader; + uint8_t rx_data[8]; + + if (HAL_FDCAN_GetRxFifoFillLevel(&hfdcan1, FDCAN_RX_FIFO0) > 0) + { + if (HAL_FDCAN_GetRxMessage(&hfdcan1, FDCAN_RX_FIFO0, &rxHeader, rx_data) == HAL_OK) + { + msg->type = rxHeader.Identifier; + msg->len = (rxHeader.DataLength < 8) ? rxHeader.DataLength : 8; + memcpy(&msg->data, rx_data, msg->len); + return (HAL_OK); + } + } + return (HAL_ERROR); +} + +// THREAD - responsible to receive CAN messages +VOID thread_rx_can(ULONG thread_input) +{ + t_rx_can_msg msg; + memset(&msg, 0, sizeof(t_rx_can_msg)); + + while (1) + { + if (rx_receive(&msg) == HAL_OK) + { + switch(msg.type) + { + case 0x100: // Emergency brake + if (tx_queue_send(&can_emergency_brake_queue, &msg, TX_NO_WAIT) != TX_SUCCESS) + uart_send("ERROR: Emergency brake queue FULL!\r\n"); + break ; + case 0x101: // throttle + if (tx_queue_send(&i2c_dc_motors_queue, &msg, TX_NO_WAIT) != TX_SUCCESS) + uart_send("ERROR: DC motors queue FULL!\r\n"); + break ; + case 0x102: // Steering + if (tx_queue_send(&i2c_servo_queue, &msg, TX_NO_WAIT) != TX_SUCCESS) + uart_send("ERROR: Servo queue FULL!\r\n"); + break ; + default: + uart_send("Received UNKNOWN CAN MSG\r\n"); + break ; + } + } + tx_thread_sleep(1); // Sleep for 1 tick to avoid busy waiting + } +} diff --git a/ThreadX_Os/Core/Src/threads/tx_can.c b/ThreadX_Os/Core/Src/threads/can/tx_can.c similarity index 66% rename from ThreadX_Os/Core/Src/threads/tx_can.c rename to ThreadX_Os/Core/Src/threads/can/tx_can.c index 274b00f..94c56bc 100644 --- a/ThreadX_Os/Core/Src/threads/tx_can.c +++ b/ThreadX_Os/Core/Src/threads/can/tx_can.c @@ -1,18 +1,17 @@ -#include "app_threadx.h" +#include "can_protocol.h" // Function responsible to transmit CAN messages. VOID thread_tx_can(ULONG thread_input) { //can message to send - t_tx_can_msg msg; + t_tx_can_msg msg; //can frames configuration - t_canFrames canFrames; + t_canFrames canFrames; memset(&msg, 0, sizeof(t_tx_can_msg)); memset(&canFrames, 0, sizeof(t_canFrames)); initCanFrames(&canFrames); if (!canFrames.tx_header_speed.Identifier || - !canFrames.tx_header_heart_beat.Identifier || !canFrames.tx_header_battery.Identifier) { uart_send("CAN frames not initialized!\r\n"); return ; @@ -28,31 +27,23 @@ VOID thread_tx_can(ULONG thread_input) HAL_FDCAN_AddMessageToTxFifoQ( &hfdcan1, &canFrames.tx_header_speed, - msg.data - ); + msg.data); uart_send("Speed CAN message sent\r\n"); - break; - case CAN_MSG_HEARTBEAT: - HAL_FDCAN_AddMessageToTxFifoQ( - &hfdcan1, - &canFrames.tx_header_heart_beat, - msg.data - ); - uart_send("Heart Beat CAN message sent\r\n"); - break; + break ; + case CAN_MSG_BATTERY: HAL_FDCAN_AddMessageToTxFifoQ( &hfdcan1, &canFrames.tx_header_battery, - msg.data - ); + msg.data); uart_send("Battery CAN message sent\r\n"); - break; + break ; + default: uart_send("Unknown CAN message type\r\n"); break; } } - tx_thread_sleep(100); + tx_thread_sleep(1); } } diff --git a/ThreadX_Os/Core/Src/threads/motors/dc_motors.c b/ThreadX_Os/Core/Src/threads/motors/dc_motors.c new file mode 100644 index 0000000..c029104 --- /dev/null +++ b/ThreadX_Os/Core/Src/threads/motors/dc_motors.c @@ -0,0 +1,37 @@ +#include "i2c_pca9685.h" +#include "can_protocol.h" + +VOID thread_dc_motors(ULONG initial_input) +{ + t_rx_can_msg msg; + t_rx_can_msg last_msg; + + if (pca9685_init(PCA9685_ADDR_MOTOR) != HAL_OK) + { + uart_send("DC Motors Thread: PCA9685 initialization failed\r\n"); + return ; + } else + uart_send("DC Motors Thread: PCA9685 initialized successfully\r\n"); + + while (1) + { + // waits permanently for a new message in the queue + if (tx_queue_receive(&i2c_dc_motors_queue, &msg, TX_WAIT_FOREVER) == TX_SUCCESS) + { + // Empties the queue and always takes the last available message + last_msg = msg; + while (tx_queue_receive(&i2c_dc_motors_queue, &last_msg, TX_NO_WAIT) == TX_SUCCESS) + msg = last_msg; + + if (msg.len >= 2) + { + int16_t throttle = (int16_t)(msg.data[0] | (msg.data[1] << 8)); + if (motor_set(MOTOR_LEFT, -throttle, 0) != HAL_OK) + uart_send("DC Motors Thread: Failed to set LEFT motor speed\r\n"); + + if (motor_set(MOTOR_RIGHT, throttle, 0) != HAL_OK) + uart_send("DC Motors Thread: Failed to set RIGHT motor speed\r\n"); + } + } + } +} diff --git a/ThreadX_Os/Core/Src/threads/motors/emergency_brake.c b/ThreadX_Os/Core/Src/threads/motors/emergency_brake.c new file mode 100644 index 0000000..684ac6e --- /dev/null +++ b/ThreadX_Os/Core/Src/threads/motors/emergency_brake.c @@ -0,0 +1,19 @@ +#include "i2c_pca9685.h" +#include "can_protocol.h" + +VOID thread_emergency_brake(ULONG thread_input) +{ + t_rx_can_msg msg; + //t_rx_can_msg last_msg; + + tx_thread_sleep(100); // Allow other threads to initialize + while (1) + { + if (tx_queue_receive(&can_emergency_brake_queue, &msg, TX_WAIT_FOREVER) == TX_SUCCESS) + { + motor_set(MOTOR_LEFT, 0, 1); + motor_set(MOTOR_RIGHT, 0, 1); + tx_thread_sleep(500); + } + } +} \ No newline at end of file diff --git a/ThreadX_Os/Core/Src/threads/motors/servo.c b/ThreadX_Os/Core/Src/threads/motors/servo.c new file mode 100644 index 0000000..f4cfc96 --- /dev/null +++ b/ThreadX_Os/Core/Src/threads/motors/servo.c @@ -0,0 +1,25 @@ +#include "i2c_pca9685.h" +#include "can_protocol.h" + +VOID thread_servo(ULONG initial_input) +{ + t_rx_can_msg msg; + memset(&msg, 0, sizeof(t_rx_can_msg)); + + if (pca9685_init(PCA9685_ADDR_SERVO) != HAL_OK) { + uart_send("Servo Thread: PCA9685 initialization failed\r\n"); + return ; + } + + while (1) + { + if (tx_queue_receive(&i2c_servo_queue, &msg, TX_WAIT_FOREVER) == TX_SUCCESS) { + + if (msg.len >= 2) { + int16_t steering = (int16_t)(msg.data[0] | (msg.data[1] << 8)); + if (pca9685_set_servo_angle(0, steering) != HAL_OK) + uart_send("Servo Thread: Failed to set servo angle\r\n"); + } + } + } +} diff --git a/ThreadX_Os/Core/Src/threads/rx_can.c b/ThreadX_Os/Core/Src/threads/rx_can.c deleted file mode 100644 index 7f43995..0000000 --- a/ThreadX_Os/Core/Src/threads/rx_can.c +++ /dev/null @@ -1,50 +0,0 @@ -#include "app_threadx.h" - -// CAN RX callback function -uint8_t rx_receive(t_rx_can_msg *msg) -{ - FDCAN_RxHeaderTypeDef rxHeader; - uint8_t rx_data[8]; - - if (HAL_FDCAN_GetRxFifoFillLevel(&hfdcan1, FDCAN_RX_FIFO0) > 0) - { - if (HAL_FDCAN_GetRxMessage(&hfdcan1, FDCAN_RX_FIFO0, &rxHeader, rx_data) == HAL_OK) - { - msg->type = rxHeader.Identifier; - msg->len = (rxHeader.DataLength <= 8) ? rxHeader.DataLength : 8; - memcpy(msg->data, rx_data, msg->len); - return (1); // Success - } - } - return (0); // Failure -} - -// THREAD - responsible to receive CAN messages -VOID thread_rx_can(ULONG thread_input) -{ - t_rx_can_msg msg; - memset(&msg, 0, sizeof(t_rx_can_msg)); - - uart_send("CAN RX thread started\r\n"); - while (1) - { - if (rx_receive(&msg)) - { - switch(msg.type) - { - case 0x100: // Emergency break - tx_queue_send(&can_rx_queue, &msg, TX_NO_WAIT); - uart_send("Received Emergency break msg\r\n"); - break ; - case 0x101: // Steering and throttle - tx_queue_send(&can_rx_queue, &msg, TX_NO_WAIT); - uart_send("Received CAN MSG STEERING THROTTLE\r\n"); - break ; - default: - uart_send("Received UNKNOWN CAN MSG\r\n"); - break ; - } - } - tx_thread_sleep(1); - } -} diff --git a/ThreadX_Os/Core/Src/threads/speedSensor.c b/ThreadX_Os/Core/Src/threads/speed_sensor.c similarity index 82% rename from ThreadX_Os/Core/Src/threads/speedSensor.c rename to ThreadX_Os/Core/Src/threads/speed_sensor.c index 74ae2d9..0b854b3 100644 --- a/ThreadX_Os/Core/Src/threads/speedSensor.c +++ b/ThreadX_Os/Core/Src/threads/speed_sensor.c @@ -1,16 +1,5 @@ #include "app_threadx.h" - -VOID rpm_debug_print(ULONG rpm, ULONG cr1_reg, ULONG cnt_reg) { - - char debug[32]; - - int len = snprintf(debug, sizeof(debug), - "RPM=%lu | CR1=%lu | CNT=%lu\r\n", - rpm, cr1_reg, cnt_reg ); - - if (len > 0 && (size_t)len < sizeof(debug)) - HAL_UART_Transmit(&huart1, (uint8_t *)debug, len, 100); -} +#include "can_protocol.h" // Thread responsible for reading speed sensor and sending RPM via CAN VOID thread_SensorSpeed(ULONG thread_input) @@ -34,7 +23,7 @@ VOID thread_SensorSpeed(ULONG thread_input) { // Hardware timer values ULONG count = htim1.Instance->CNT; - ULONG cr1_reg = htim1.Instance->CR1; + //ULONG cr1_reg = htim1.Instance->CR1; ULONG ticks = tx_time_get(); rpm = convertValuesRPM(count, ticks, period, &state); @@ -53,7 +42,7 @@ VOID thread_SensorSpeed(ULONG thread_input) tx_thread_sleep(200); continue ; } - tx_thread_sleep(400); + tx_thread_sleep(50); } } diff --git a/ThreadX_Os/Core/Src/tx_initialize_low_level.S b/ThreadX_Os/Core/Src/tx_initialize_low_level.S index b0fce53..6c55087 100644 --- a/ThreadX_Os/Core/Src/tx_initialize_low_level.S +++ b/ThreadX_Os/Core/Src/tx_initialize_low_level.S @@ -45,7 +45,7 @@ /**************************************************************************/ /**************************************************************************/ -SYSTEM_CLOCK = 160000000 +SYSTEM_CLOCK = 72000000 SYSTICK_CYCLES = ((SYSTEM_CLOCK / 100) -1) /**************************************************************************/ @@ -262,7 +262,7 @@ __tx_DBGHandler: EXTERN __vector_table ; ; -SYSTEM_CLOCK EQU 160000000 +SYSTEM_CLOCK EQU 72000000 SYSTICK_CYCLES EQU ((SYSTEM_CLOCK / 100) -1) ; ; @@ -457,7 +457,7 @@ __tx_DBGHandler: /**************************************************************************/ /**************************************************************************/ -SYSTEM_CLOCK = 160000000 +SYSTEM_CLOCK = 72000000 SYSTICK_CYCLES = ((SYSTEM_CLOCK / 100) -1) /**************************************************************************/ diff --git a/ThreadX_Os/Core/Src/utils/debug_utils.c b/ThreadX_Os/Core/Src/utils/debug_utils.c new file mode 100644 index 0000000..7a4de3d --- /dev/null +++ b/ThreadX_Os/Core/Src/utils/debug_utils.c @@ -0,0 +1,28 @@ +#include "app_threadx.h" + +// Function to send a string over UART +VOID uart_send(const char *msg) +{ + HAL_UART_Transmit(&huart1, (uint8_t*)msg, strlen(msg), 100); +} + +// Function to send an integer over UART +VOID uart_send_int(int32_t value) +{ + char buffer[12]; // capacity of -2147483648 + null terminator + snprintf(buffer, sizeof(buffer), "%ld", value); + uart_send(buffer); +} + +// Function to print RPM debug information over UART +VOID rpm_debug_print(ULONG rpm, ULONG cr1_reg, ULONG cnt_reg) { + + char debug[32]; + + int len = snprintf(debug, sizeof(debug), + "RPM=%lu | CR1=%lu | CNT=%lu\r\n", + rpm, cr1_reg, cnt_reg); + + if (len > 0 && (size_t)len < sizeof(debug)) + HAL_UART_Transmit(&huart1, (uint8_t *)debug, len, 100); +} \ No newline at end of file diff --git a/ThreadX_Os/Core/Src/utils/i2c_utils.c b/ThreadX_Os/Core/Src/utils/i2c_utils.c new file mode 100644 index 0000000..9ac6c2f --- /dev/null +++ b/ThreadX_Os/Core/Src/utils/i2c_utils.c @@ -0,0 +1,33 @@ +#include "app_threadx.h" + +HAL_StatusTypeDef i2c_scan_bus(VOID) +{ + uint8_t i2c_address; + HAL_StatusTypeDef result; + + tx_thread_sleep(50); + + if (HAL_I2C_GetState(&hi2c3) != HAL_I2C_STATE_READY) + { + uart_send("I2C not ready\r\n"); + return HAL_BUSY; + } + else + uart_send("Scanning I2C bus...\r\n"); + + tx_mutex_get(&i2c_mutex, TX_WAIT_FOREVER); + for (i2c_address = 0x03; i2c_address < 0x78; i2c_address++) + { + result = HAL_I2C_IsDeviceReady(&hi2c3, (i2c_address << 1), 1, 10); + + if (result == HAL_OK) + { + char msg[32]; + snprintf(msg, sizeof(msg), "Found device at 0x%02X\r\n", i2c_address); + uart_send(msg); + } + } + tx_mutex_put(&i2c_mutex); + uart_send("I2C bus scan complete.\r\n"); + return (HAL_OK); +} \ No newline at end of file diff --git a/ThreadX_Os/Core/Src/utils/speed_rpm.c b/ThreadX_Os/Core/Src/utils/speed_rpm_utils.c similarity index 100% rename from ThreadX_Os/Core/Src/utils/speed_rpm.c rename to ThreadX_Os/Core/Src/utils/speed_rpm_utils.c diff --git a/ThreadX_Os/Drivers/STM32U5xx_HAL_Driver/Inc/stm32u5xx_ll_i2c.h b/ThreadX_Os/Drivers/STM32U5xx_HAL_Driver/Inc/stm32u5xx_ll_i2c.h new file mode 100644 index 0000000..1fb6e73 --- /dev/null +++ b/ThreadX_Os/Drivers/STM32U5xx_HAL_Driver/Inc/stm32u5xx_ll_i2c.h @@ -0,0 +1,2597 @@ +/** + ****************************************************************************** + * @file stm32u5xx_ll_i2c.h + * @author MCD Application Team + * @brief Header file of I2C LL module. + ****************************************************************************** + * @attention + * + * Copyright (c) 2021 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32U5xx_LL_I2C_H +#define STM32U5xx_LL_I2C_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32u5xx.h" + +/** @addtogroup STM32U5xx_LL_Driver + * @{ + */ + +#if defined (I2C1) || defined (I2C2) || defined (I2C3) || defined (I2C4) || defined (I2C5) || defined (I2C6) + +/** @defgroup I2C_LL I2C + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup I2C_LL_Private_Constants I2C Private Constants + * @{ + */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup I2C_LL_Private_Macros I2C Private Macros + * @{ + */ +#define IS_LL_I2C_GRP1_INSTANCE(__INSTANCE__) IS_I2C_GRP1_INSTANCE(__INSTANCE__) + +#define IS_LL_I2C_GRP2_INSTANCE(__INSTANCE__) IS_I2C_GRP2_INSTANCE(__INSTANCE__) +/** + * @} + */ + +/* Exported types ------------------------------------------------------------*/ +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup I2C_LL_ES_INIT I2C Exported Init structure + * @{ + */ +typedef struct +{ + uint32_t PeripheralMode; /*!< Specifies the peripheral mode. + This parameter can be a value of @ref I2C_LL_EC_PERIPHERAL_MODE. + + This feature can be modified afterwards using unitary function + @ref LL_I2C_SetMode(). */ + + uint32_t Timing; /*!< Specifies the SDA setup, hold time and the SCL high, low period values. + This parameter must be set by referring to the STM32CubeMX Tool and + the helper macro @ref __LL_I2C_CONVERT_TIMINGS(). + + This feature can be modified afterwards using unitary function + @ref LL_I2C_SetTiming(). */ + + uint32_t AnalogFilter; /*!< Enables or disables analog noise filter. + This parameter can be a value of @ref I2C_LL_EC_ANALOGFILTER_SELECTION. + + This feature can be modified afterwards using unitary functions + @ref LL_I2C_EnableAnalogFilter() or LL_I2C_DisableAnalogFilter(). */ + + uint32_t DigitalFilter; /*!< Configures the digital noise filter. + This parameter can be a number between Min_Data = 0x00 and Max_Data = 0x0F. + + This feature can be modified afterwards using unitary function + @ref LL_I2C_SetDigitalFilter(). */ + + uint32_t OwnAddress1; /*!< Specifies the device own address 1. + This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF. + + This feature can be modified afterwards using unitary function + @ref LL_I2C_SetOwnAddress1(). */ + + uint32_t TypeAcknowledge; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive + match code or next received byte. + This parameter can be a value of @ref I2C_LL_EC_I2C_ACKNOWLEDGE. + + This feature can be modified afterwards using unitary function + @ref LL_I2C_AcknowledgeNextData(). */ + + uint32_t OwnAddrSize; /*!< Specifies the device own address 1 size (7-bit or 10-bit). + This parameter can be a value of @ref I2C_LL_EC_OWNADDRESS1. + + This feature can be modified afterwards using unitary function + @ref LL_I2C_SetOwnAddress1(). */ +} LL_I2C_InitTypeDef; +/** + * @} + */ +#endif /*USE_FULL_LL_DRIVER*/ + +/* Exported constants --------------------------------------------------------*/ +/** @defgroup I2C_LL_Exported_Constants I2C Exported Constants + * @{ + */ + +/** @defgroup I2C_LL_EC_CLEAR_FLAG Clear Flags Defines + * @brief Flags defines which can be used with LL_I2C_WriteReg function + * @{ + */ +#define LL_I2C_ICR_ADDRCF I2C_ICR_ADDRCF /*!< Address Matched flag */ +#define LL_I2C_ICR_NACKCF I2C_ICR_NACKCF /*!< Not Acknowledge flag */ +#define LL_I2C_ICR_STOPCF I2C_ICR_STOPCF /*!< Stop detection flag */ +#define LL_I2C_ICR_BERRCF I2C_ICR_BERRCF /*!< Bus error flag */ +#define LL_I2C_ICR_ARLOCF I2C_ICR_ARLOCF /*!< Arbitration Lost flag */ +#define LL_I2C_ICR_OVRCF I2C_ICR_OVRCF /*!< Overrun/Underrun flag */ +#define LL_I2C_ICR_PECCF I2C_ICR_PECCF /*!< PEC error flag */ +#define LL_I2C_ICR_TIMOUTCF I2C_ICR_TIMOUTCF /*!< Timeout detection flag */ +#define LL_I2C_ICR_ALERTCF I2C_ICR_ALERTCF /*!< Alert flag */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_GET_FLAG Get Flags Defines + * @brief Flags defines which can be used with LL_I2C_ReadReg function + * @{ + */ +#define LL_I2C_ISR_TXE I2C_ISR_TXE /*!< Transmit data register empty */ +#define LL_I2C_ISR_TXIS I2C_ISR_TXIS /*!< Transmit interrupt status */ +#define LL_I2C_ISR_RXNE I2C_ISR_RXNE /*!< Receive data register not empty */ +#define LL_I2C_ISR_ADDR I2C_ISR_ADDR /*!< Address matched (slave mode) */ +#define LL_I2C_ISR_NACKF I2C_ISR_NACKF /*!< Not Acknowledge received flag */ +#define LL_I2C_ISR_STOPF I2C_ISR_STOPF /*!< Stop detection flag */ +#define LL_I2C_ISR_TC I2C_ISR_TC /*!< Transfer Complete (master mode) */ +#define LL_I2C_ISR_TCR I2C_ISR_TCR /*!< Transfer Complete Reload */ +#define LL_I2C_ISR_BERR I2C_ISR_BERR /*!< Bus error */ +#define LL_I2C_ISR_ARLO I2C_ISR_ARLO /*!< Arbitration lost */ +#define LL_I2C_ISR_OVR I2C_ISR_OVR /*!< Overrun/Underrun (slave mode) */ +#define LL_I2C_ISR_PECERR I2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */ +#define LL_I2C_ISR_TIMEOUT I2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */ +#define LL_I2C_ISR_ALERT I2C_ISR_ALERT /*!< SMBus alert (SMBus mode) */ +#define LL_I2C_ISR_BUSY I2C_ISR_BUSY /*!< Bus busy */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_IT IT Defines + * @brief IT defines which can be used with LL_I2C_ReadReg and LL_I2C_WriteReg functions + * @{ + */ +#define LL_I2C_CR1_TXIE I2C_CR1_TXIE /*!< TX Interrupt enable */ +#define LL_I2C_CR1_RXIE I2C_CR1_RXIE /*!< RX Interrupt enable */ +#define LL_I2C_CR1_ADDRIE I2C_CR1_ADDRIE /*!< Address match Interrupt enable (slave only) */ +#define LL_I2C_CR1_NACKIE I2C_CR1_NACKIE /*!< Not acknowledge received Interrupt enable */ +#define LL_I2C_CR1_STOPIE I2C_CR1_STOPIE /*!< STOP detection Interrupt enable */ +#define LL_I2C_CR1_TCIE I2C_CR1_TCIE /*!< Transfer Complete interrupt enable */ +#define LL_I2C_CR1_ERRIE I2C_CR1_ERRIE /*!< Error interrupts enable */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_PERIPHERAL_MODE Peripheral Mode + * @{ + */ +#define LL_I2C_MODE_I2C 0x00000000U /*!< I2C Master or Slave mode */ +#define LL_I2C_MODE_SMBUS_HOST I2C_CR1_SMBHEN /*!< SMBus Host address acknowledge */ +#define LL_I2C_MODE_SMBUS_DEVICE 0x00000000U /*!< SMBus Device default mode + (Default address not acknowledge) */ +#define LL_I2C_MODE_SMBUS_DEVICE_ARP I2C_CR1_SMBDEN /*!< SMBus Device Default address acknowledge */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_ANALOGFILTER_SELECTION Analog Filter Selection + * @{ + */ +#define LL_I2C_ANALOGFILTER_ENABLE 0x00000000U /*!< Analog filter is enabled. */ +#define LL_I2C_ANALOGFILTER_DISABLE I2C_CR1_ANFOFF /*!< Analog filter is disabled. */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_ADDRESSING_MODE Master Addressing Mode + * @{ + */ +#define LL_I2C_ADDRESSING_MODE_7BIT 0x00000000U /*!< Master operates in 7-bit addressing mode. */ +#define LL_I2C_ADDRESSING_MODE_10BIT I2C_CR2_ADD10 /*!< Master operates in 10-bit addressing mode.*/ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_OWNADDRESS1 Own Address 1 Length + * @{ + */ +#define LL_I2C_OWNADDRESS1_7BIT 0x00000000U /*!< Own address 1 is a 7-bit address. */ +#define LL_I2C_OWNADDRESS1_10BIT I2C_OAR1_OA1MODE /*!< Own address 1 is a 10-bit address.*/ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_OWNADDRESS2 Own Address 2 Masks + * @{ + */ +#define LL_I2C_OWNADDRESS2_NOMASK I2C_OAR2_OA2NOMASK /*!< Own Address2 No mask. */ +#define LL_I2C_OWNADDRESS2_MASK01 I2C_OAR2_OA2MASK01 /*!< Only Address2 bits[7:2] are compared. */ +#define LL_I2C_OWNADDRESS2_MASK02 I2C_OAR2_OA2MASK02 /*!< Only Address2 bits[7:3] are compared. */ +#define LL_I2C_OWNADDRESS2_MASK03 I2C_OAR2_OA2MASK03 /*!< Only Address2 bits[7:4] are compared. */ +#define LL_I2C_OWNADDRESS2_MASK04 I2C_OAR2_OA2MASK04 /*!< Only Address2 bits[7:5] are compared. */ +#define LL_I2C_OWNADDRESS2_MASK05 I2C_OAR2_OA2MASK05 /*!< Only Address2 bits[7:6] are compared. */ +#define LL_I2C_OWNADDRESS2_MASK06 I2C_OAR2_OA2MASK06 /*!< Only Address2 bits[7] are compared. */ +#define LL_I2C_OWNADDRESS2_MASK07 I2C_OAR2_OA2MASK07 /*!< No comparison is done. + All Address2 are acknowledged. */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation + * @{ + */ +#define LL_I2C_ACK 0x00000000U /*!< ACK is sent after current received byte. */ +#define LL_I2C_NACK I2C_CR2_NACK /*!< NACK is sent after current received byte.*/ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_ADDRSLAVE Slave Address Length + * @{ + */ +#define LL_I2C_ADDRSLAVE_7BIT 0x00000000U /*!< Slave Address in 7-bit. */ +#define LL_I2C_ADDRSLAVE_10BIT I2C_CR2_ADD10 /*!< Slave Address in 10-bit.*/ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_REQUEST Transfer Request Direction + * @{ + */ +#define LL_I2C_REQUEST_WRITE 0x00000000U /*!< Master request a write transfer. */ +#define LL_I2C_REQUEST_READ I2C_CR2_RD_WRN /*!< Master request a read transfer. */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_MODE Transfer End Mode + * @{ + */ +#define LL_I2C_MODE_RELOAD I2C_CR2_RELOAD /*!< Enable I2C Reload mode. */ +#define LL_I2C_MODE_AUTOEND I2C_CR2_AUTOEND /*!< Enable I2C Automatic end mode + with no HW PEC comparison. */ +#define LL_I2C_MODE_SOFTEND 0x00000000U /*!< Enable I2C Software end mode + with no HW PEC comparison. */ +#define LL_I2C_MODE_SMBUS_RELOAD LL_I2C_MODE_RELOAD /*!< Enable SMBUS Automatic end mode + with HW PEC comparison. */ +#define LL_I2C_MODE_SMBUS_AUTOEND_NO_PEC LL_I2C_MODE_AUTOEND /*!< Enable SMBUS Automatic end mode + with HW PEC comparison. */ +#define LL_I2C_MODE_SMBUS_SOFTEND_NO_PEC LL_I2C_MODE_SOFTEND /*!< Enable SMBUS Software end mode + with HW PEC comparison. */ +#define LL_I2C_MODE_SMBUS_AUTOEND_WITH_PEC (uint32_t)(LL_I2C_MODE_AUTOEND | I2C_CR2_PECBYTE) +/*!< Enable SMBUS Automatic end mode with HW PEC comparison. */ +#define LL_I2C_MODE_SMBUS_SOFTEND_WITH_PEC (uint32_t)(LL_I2C_MODE_SOFTEND | I2C_CR2_PECBYTE) +/*!< Enable SMBUS Software end mode with HW PEC comparison. */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_GENERATE Start And Stop Generation + * @{ + */ +#define LL_I2C_GENERATE_NOSTARTSTOP 0x00000000U +/*!< Don't Generate Stop and Start condition. */ +#define LL_I2C_GENERATE_STOP (uint32_t)(0x80000000U | I2C_CR2_STOP) +/*!< Generate Stop condition (Size should be set to 0). */ +#define LL_I2C_GENERATE_START_READ (uint32_t)(0x80000000U | I2C_CR2_START | I2C_CR2_RD_WRN) +/*!< Generate Start for read request. */ +#define LL_I2C_GENERATE_START_WRITE (uint32_t)(0x80000000U | I2C_CR2_START) +/*!< Generate Start for write request. */ +#define LL_I2C_GENERATE_RESTART_7BIT_READ (uint32_t)(0x80000000U | I2C_CR2_START | I2C_CR2_RD_WRN) +/*!< Generate Restart for read request, slave 7Bit address. */ +#define LL_I2C_GENERATE_RESTART_7BIT_WRITE (uint32_t)(0x80000000U | I2C_CR2_START) +/*!< Generate Restart for write request, slave 7Bit address. */ +#define LL_I2C_GENERATE_RESTART_10BIT_READ (uint32_t)(0x80000000U | I2C_CR2_START | \ + I2C_CR2_RD_WRN | I2C_CR2_HEAD10R) +/*!< Generate Restart for read request, slave 10Bit address. */ +#define LL_I2C_GENERATE_RESTART_10BIT_WRITE (uint32_t)(0x80000000U | I2C_CR2_START) +/*!< Generate Restart for write request, slave 10Bit address.*/ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_DIRECTION Read Write Direction + * @{ + */ +#define LL_I2C_DIRECTION_WRITE 0x00000000U /*!< Write transfer request by master, + slave enters receiver mode. */ +#define LL_I2C_DIRECTION_READ I2C_ISR_DIR /*!< Read transfer request by master, + slave enters transmitter mode.*/ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_DMA_REG_DATA DMA Register Data + * @{ + */ +#define LL_I2C_DMA_REG_DATA_TRANSMIT 0x00000000U /*!< Get address of data register used for + transmission */ +#define LL_I2C_DMA_REG_DATA_RECEIVE 0x00000001U /*!< Get address of data register used for + reception */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_SMBUS_TIMEOUTA_MODE SMBus TimeoutA Mode SCL SDA Timeout + * @{ + */ +#define LL_I2C_SMBUS_TIMEOUTA_MODE_SCL_LOW 0x00000000U /*!< TimeoutA is used to detect + SCL low level timeout. */ +#define LL_I2C_SMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH I2C_TIMEOUTR_TIDLE /*!< TimeoutA is used to detect + both SCL and SDA high level timeout.*/ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_SMBUS_TIMEOUT_SELECTION SMBus Timeout Selection + * @{ + */ +#define LL_I2C_SMBUS_TIMEOUTA I2C_TIMEOUTR_TIMOUTEN /*!< TimeoutA enable bit */ +#define LL_I2C_SMBUS_TIMEOUTB I2C_TIMEOUTR_TEXTEN /*!< TimeoutB (extended clock) + enable bit */ +#define LL_I2C_SMBUS_ALL_TIMEOUT (uint32_t)(I2C_TIMEOUTR_TIMOUTEN | \ + I2C_TIMEOUTR_TEXTEN) /*!< TimeoutA and TimeoutB +(extended clock) enable bits */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_AUTOCR_TRIGSEL Autonomous Trigger selection + * @brief I2C Autonomous Trigger selection + * @{ + */ +#define LL_I2C_TRIG_GRP1 (0x10000000U) /*!< Trigger Group for I2C1, I2C2, I2C4, I2C5, I2C6 (depends on Product) */ +#define LL_I2C_TRIG_GRP2 (0x20000000U) /*!< Trigger Group for I2C3 */ + +#define LL_I2C_GRP1_GPDMA_CH0_TCF_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x00000000U)) +/*!< HW Trigger signal is GPDMA_CH0_TRG */ +#define LL_I2C_GRP1_GPDMA_CH1_TCF_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x1U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is GPDMA_CH1_TRG */ +#define LL_I2C_GRP1_GPDMA_CH2_TCF_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x2U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is GPDMA_CH2_TRG */ +#define LL_I2C_GRP1_GPDMA_CH3_TCF_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x3U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is GPDMA_CH3_TRG */ +#define LL_I2C_GRP1_EXTI5_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x4U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is EXTI5_TRG */ +#define LL_I2C_GRP1_EXTI9_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x5U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is EXTI9_TRG */ +#define LL_I2C_GRP1_LPTIM1_CH1_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x6U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is LPTIM1_CH1_TRG */ +#define LL_I2C_GRP1_LPTIM2_CH1_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x7U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is LPTIM2_CH1_TRG */ +#define LL_I2C_GRP1_COMP1_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x8U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is COMP1_TRG */ +#define LL_I2C_GRP1_COMP2_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0x9U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is COMP2_TRG */ +#define LL_I2C_GRP1_RTC_ALRA_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0xAU << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is RTC_ALRA_TRG */ +#define LL_I2C_GRP1_RTC_WUT_TRG (uint32_t)(LL_I2C_TRIG_GRP1 | (0xBU << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is RTC_WUT_TRG */ + +#define LL_I2C_GRP2_LPDMA_CH0_TCF_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x00000000U)) +/*!< HW Trigger signal is LPDMA_CH0_TRG */ +#define LL_I2C_GRP2_LPDMA_CH1_TCF_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x1U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is LPDMA_CH1_TRG */ +#define LL_I2C_GRP2_LPDMA_CH2_TCF_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x2U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is LPDMA_CH2_TRG */ +#define LL_I2C_GRP2_LPDMA_CH3_TCF_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x3U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is LPDMA_CH3_TRG */ +#define LL_I2C_GRP2_EXTI5_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x4U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is EXTI5_TRG */ +#define LL_I2C_GRP2_EXTI8_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x5U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is EXTI8_TRG */ +#define LL_I2C_GRP2_LPTIM1_CH1_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x6U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is LPTIM1_CH1_TRG */ +#define LL_I2C_GRP2_LPTIM3_CH1_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x7U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is LPTIM3_CH1_TRG */ +#define LL_I2C_GRP2_COMP1_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x8U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is COMP1_TRG */ +#define LL_I2C_GRP2_COMP2_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0x9U << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is COMP2_TRG */ +#define LL_I2C_GRP2_RTC_ALRA_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0xAU << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is RTC_ALRA_TRG */ +#define LL_I2C_GRP2_RTC_WUT_TRG (uint32_t)(LL_I2C_TRIG_GRP2 | (0xBU << I2C_AUTOCR_TRIGSEL_Pos)) +/*!< HW Trigger signal is RTC_WUT_TRG */ +/** + * @} + */ + +/** @defgroup I2C_LL_EC_AUTOCR_TRIGPOL Autonomous Trigger Polarity + * @brief I2C Autonomous Trigger Polarity + * @{ + */ +#define LL_I2C_TRIG_POLARITY_RISING 0x00000000U /*!< I2C triggered on rising edge */ +#define LL_I2C_TRIG_POLARITY_FALLING I2C_AUTOCR_TRIGPOL /*!< I2C triggered on falling edge */ +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup I2C_LL_Exported_Macros I2C Exported Macros + * @{ + */ + +/** @defgroup I2C_LL_EM_WRITE_READ Common Write and read registers Macros + * @{ + */ + +/** + * @brief Write a value in I2C register + * @param __INSTANCE__ I2C Instance + * @param __REG__ Register to be written + * @param __VALUE__ Value to be written in the register + * @retval None + */ +#define LL_I2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) + +/** + * @brief Read a value in I2C register + * @param __INSTANCE__ I2C Instance + * @param __REG__ Register to be read + * @retval Register value + */ +#define LL_I2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) +/** + * @} + */ + +/** @defgroup I2C_LL_EM_CONVERT_TIMINGS Convert SDA SCL timings + * @{ + */ +/** + * @brief Configure the SDA setup, hold time and the SCL high, low period. + * @param __PRESCALER__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. + * @param __SETUP_TIME__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. + (tscldel = (SCLDEL+1)xtpresc) + * @param __HOLD_TIME__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. + (tsdadel = SDADELxtpresc) + * @param __SCLH_PERIOD__ This parameter must be a value between Min_Data=0 and Max_Data=0xFF. + (tsclh = (SCLH+1)xtpresc) + * @param __SCLL_PERIOD__ This parameter must be a value between Min_Data=0 and Max_Data=0xFF. + (tscll = (SCLL+1)xtpresc) + * @retval Value between Min_Data=0 and Max_Data=0xFFFFFFFF + */ +#define __LL_I2C_CONVERT_TIMINGS(__PRESCALER__, __SETUP_TIME__, __HOLD_TIME__, __SCLH_PERIOD__, __SCLL_PERIOD__) \ + ((((uint32_t)(__PRESCALER__) << I2C_TIMINGR_PRESC_Pos) & I2C_TIMINGR_PRESC) | \ + (((uint32_t)(__SETUP_TIME__) << I2C_TIMINGR_SCLDEL_Pos) & I2C_TIMINGR_SCLDEL) | \ + (((uint32_t)(__HOLD_TIME__) << I2C_TIMINGR_SDADEL_Pos) & I2C_TIMINGR_SDADEL) | \ + (((uint32_t)(__SCLH_PERIOD__) << I2C_TIMINGR_SCLH_Pos) & I2C_TIMINGR_SCLH) | \ + (((uint32_t)(__SCLL_PERIOD__) << I2C_TIMINGR_SCLL_Pos) & I2C_TIMINGR_SCLL)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup I2C_LL_Exported_Functions I2C Exported Functions + * @{ + */ + +/** @defgroup I2C_LL_EF_Configuration Configuration + * @{ + */ + +/** + * @brief Enable I2C peripheral (PE = 1). + * @rmtoll CR1 PE LL_I2C_Enable + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_Enable(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_PE); +} + +/** + * @brief Disable I2C peripheral (PE = 0). + * @note When PE = 0, the I2C SCL and SDA lines are released. + * Internal state machines and status bits are put back to their reset value. + * When cleared, PE must be kept low for at least 3 APB clock cycles. + * @rmtoll CR1 PE LL_I2C_Disable + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_Disable(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_PE); +} + +/** + * @brief Check if the I2C peripheral is enabled or disabled. + * @rmtoll CR1 PE LL_I2C_IsEnabled + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabled(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_PE) == (I2C_CR1_PE)) ? 1UL : 0UL); +} + +/** + * @brief Configure Noise Filters (Analog and Digital). + * @note If the analog filter is also enabled, the digital filter is added to analog filter. + * The filters can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR1 ANFOFF LL_I2C_ConfigFilters\n + * CR1 DNF LL_I2C_ConfigFilters + * @param I2Cx I2C Instance. + * @param AnalogFilter This parameter can be one of the following values: + * @arg @ref LL_I2C_ANALOGFILTER_ENABLE + * @arg @ref LL_I2C_ANALOGFILTER_DISABLE + * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) + and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*ti2cclk). + * This parameter is used to configure the digital noise filter on SDA and SCL input. + * The digital filter will filter spikes with a length of up to DNF[3:0]*ti2cclk. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ConfigFilters(I2C_TypeDef *I2Cx, uint32_t AnalogFilter, uint32_t DigitalFilter) +{ + MODIFY_REG(I2Cx->CR1, I2C_CR1_ANFOFF | I2C_CR1_DNF, AnalogFilter | (DigitalFilter << I2C_CR1_DNF_Pos)); +} + +/** + * @brief Configure Digital Noise Filter. + * @note If the analog filter is also enabled, the digital filter is added to analog filter. + * This filter can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR1 DNF LL_I2C_SetDigitalFilter + * @param I2Cx I2C Instance. + * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) + and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*ti2cclk). + * This parameter is used to configure the digital noise filter on SDA and SCL input. + * The digital filter will filter spikes with a length of up to DNF[3:0]*ti2cclk. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetDigitalFilter(I2C_TypeDef *I2Cx, uint32_t DigitalFilter) +{ + MODIFY_REG(I2Cx->CR1, I2C_CR1_DNF, DigitalFilter << I2C_CR1_DNF_Pos); +} + +/** + * @brief Get the current Digital Noise Filter configuration. + * @rmtoll CR1 DNF LL_I2C_GetDigitalFilter + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x0 and Max_Data=0xF + */ +__STATIC_INLINE uint32_t LL_I2C_GetDigitalFilter(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CR1, I2C_CR1_DNF) >> I2C_CR1_DNF_Pos); +} + +/** + * @brief Enable Analog Noise Filter. + * @note This filter can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR1 ANFOFF LL_I2C_EnableAnalogFilter + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableAnalogFilter(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_ANFOFF); +} + +/** + * @brief Disable Analog Noise Filter. + * @note This filter can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR1 ANFOFF LL_I2C_DisableAnalogFilter + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableAnalogFilter(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_ANFOFF); +} + +/** + * @brief Check if Analog Noise Filter is enabled or disabled. + * @rmtoll CR1 ANFOFF LL_I2C_IsEnabledAnalogFilter + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledAnalogFilter(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_ANFOFF) != (I2C_CR1_ANFOFF)) ? 1UL : 0UL); +} + +/** + * @brief Enable DMA transmission requests. + * @rmtoll CR1 TXDMAEN LL_I2C_EnableDMAReq_TX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableDMAReq_TX(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_TXDMAEN); +} + +/** + * @brief Disable DMA transmission requests. + * @rmtoll CR1 TXDMAEN LL_I2C_DisableDMAReq_TX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableDMAReq_TX(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_TXDMAEN); +} + +/** + * @brief Check if DMA transmission requests are enabled or disabled. + * @rmtoll CR1 TXDMAEN LL_I2C_IsEnabledDMAReq_TX + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_TX(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_TXDMAEN) == (I2C_CR1_TXDMAEN)) ? 1UL : 0UL); +} + +/** + * @brief Enable DMA reception requests. + * @rmtoll CR1 RXDMAEN LL_I2C_EnableDMAReq_RX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableDMAReq_RX(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_RXDMAEN); +} + +/** + * @brief Disable DMA reception requests. + * @rmtoll CR1 RXDMAEN LL_I2C_DisableDMAReq_RX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableDMAReq_RX(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_RXDMAEN); +} + +/** + * @brief Check if DMA reception requests are enabled or disabled. + * @rmtoll CR1 RXDMAEN LL_I2C_IsEnabledDMAReq_RX + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_RX(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_RXDMAEN) == (I2C_CR1_RXDMAEN)) ? 1UL : 0UL); +} + +/** + * @brief Get the data register address used for DMA transfer + * @rmtoll TXDR TXDATA LL_I2C_DMA_GetRegAddr\n + * RXDR RXDATA LL_I2C_DMA_GetRegAddr + * @param I2Cx I2C Instance + * @param Direction This parameter can be one of the following values: + * @arg @ref LL_I2C_DMA_REG_DATA_TRANSMIT + * @arg @ref LL_I2C_DMA_REG_DATA_RECEIVE + * @retval Address of data register + */ +__STATIC_INLINE uint32_t LL_I2C_DMA_GetRegAddr(const I2C_TypeDef *I2Cx, uint32_t Direction) +{ + uint32_t data_reg_addr; + + if (Direction == LL_I2C_DMA_REG_DATA_TRANSMIT) + { + /* return address of TXDR register */ + data_reg_addr = (uint32_t) &(I2Cx->TXDR); + } + else + { + /* return address of RXDR register */ + data_reg_addr = (uint32_t) &(I2Cx->RXDR); + } + + return data_reg_addr; +} + +/** + * @brief Enable Clock stretching. + * @note This bit can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR1 NOSTRETCH LL_I2C_EnableClockStretching + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableClockStretching(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); +} + +/** + * @brief Disable Clock stretching. + * @note This bit can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll CR1 NOSTRETCH LL_I2C_DisableClockStretching + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableClockStretching(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); +} + +/** + * @brief Check if Clock stretching is enabled or disabled. + * @rmtoll CR1 NOSTRETCH LL_I2C_IsEnabledClockStretching + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledClockStretching(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH) != (I2C_CR1_NOSTRETCH)) ? 1UL : 0UL); +} + +/** + * @brief Enable hardware byte control in slave mode. + * @rmtoll CR1 SBC LL_I2C_EnableSlaveByteControl + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableSlaveByteControl(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_SBC); +} + +/** + * @brief Disable hardware byte control in slave mode. + * @rmtoll CR1 SBC LL_I2C_DisableSlaveByteControl + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableSlaveByteControl(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_SBC); +} + +/** + * @brief Check if hardware byte control in slave mode is enabled or disabled. + * @rmtoll CR1 SBC LL_I2C_IsEnabledSlaveByteControl + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledSlaveByteControl(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_SBC) == (I2C_CR1_SBC)) ? 1UL : 0UL); +} + +/** + * @brief Enable Wakeup from STOP. + * @note The macro IS_I2C_WAKEUP_FROMSTOP_INSTANCE(I2Cx) can be used to check whether or not + * WakeUpFromStop feature is supported by the I2Cx Instance. + * @note This bit can only be programmed when Digital Filter is disabled. + * @rmtoll CR1 WUPEN LL_I2C_EnableWakeUpFromStop + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableWakeUpFromStop(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_WUPEN); +} + +/** + * @brief Disable Wakeup from STOP. + * @note The macro IS_I2C_WAKEUP_FROMSTOP_INSTANCE(I2Cx) can be used to check whether or not + * WakeUpFromStop feature is supported by the I2Cx Instance. + * @rmtoll CR1 WUPEN LL_I2C_DisableWakeUpFromStop + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableWakeUpFromStop(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_WUPEN); +} + +/** + * @brief Check if Wakeup from STOP is enabled or disabled. + * @note The macro IS_I2C_WAKEUP_FROMSTOP_INSTANCE(I2Cx) can be used to check whether or not + * WakeUpFromStop feature is supported by the I2Cx Instance. + * @rmtoll CR1 WUPEN LL_I2C_IsEnabledWakeUpFromStop + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledWakeUpFromStop(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_WUPEN) == (I2C_CR1_WUPEN)) ? 1UL : 0UL); +} + +/** + * @brief Enable General Call. + * @note When enabled the Address 0x00 is ACKed. + * @rmtoll CR1 GCEN LL_I2C_EnableGeneralCall + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableGeneralCall(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_GCEN); +} + +/** + * @brief Disable General Call. + * @note When disabled the Address 0x00 is NACKed. + * @rmtoll CR1 GCEN LL_I2C_DisableGeneralCall + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableGeneralCall(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_GCEN); +} + +/** + * @brief Check if General Call is enabled or disabled. + * @rmtoll CR1 GCEN LL_I2C_IsEnabledGeneralCall + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledGeneralCall(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_GCEN) == (I2C_CR1_GCEN)) ? 1UL : 0UL); +} + +/** + * @brief Enable I2C Fast Mode Plus (FMP = 1). + * @note 20mA I/O drive enable + * @rmtoll CR1 FMP LL_I2C_EnableFastModePlus + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableFastModePlus(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_FMP); +} + +/** + * @brief Disable I2C Fast Mode Plus (FMP = 0). + * @note 20mA I/O drive disable + * @rmtoll CR1 FMP LL_I2C_DisableFastModePlus + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableFastModePlus(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_FMP); +} + +/** + * @brief Check if the I2C Fast Mode Plus is enabled or disabled. + * @rmtoll CR1 FMP LL_I2C_IsEnabledFastModePlus + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledFastModePlus(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_FMP) == (I2C_CR1_FMP)) ? 1UL : 0UL); +} + +/** + * @brief Enable automatic clear of ADDR flag. + * @rmtoll CR1 ADDRACLR LL_I2C_EnableAutoClearFlag_ADDR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableAutoClearFlag_ADDR(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_ADDRACLR); +} + +/** + * @brief Disable automatic clear of ADDR flag. + * @rmtoll CR1 ADDRACLR LL_I2C_DisableAutoClearFlag_ADDR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableAutoClearFlag_ADDR(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_ADDRACLR); +} + +/** + * @brief Check if the automatic clear of ADDR flag is enabled or disabled. + * @rmtoll CR1 ADDRACLR LL_I2C_IsEnabledAutoClearFlag_ADDR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledAutoClearFlag_ADDR(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_ADDRACLR) == (I2C_CR1_ADDRACLR)) ? 1UL : 0UL); +} + +/** + * @brief Enable automatic clear of STOP flag. + * @rmtoll CR1 STOPFACLR LL_I2C_EnableAutoClearFlag_STOP + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableAutoClearFlag_STOP(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_STOPFACLR); +} + +/** + * @brief Disable automatic clear of STOP flag. + * @rmtoll CR1 STOPFACLR LL_I2C_DisableAutoClearFlag_STOP + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableAutoClearFlag_STOP(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_STOPFACLR); +} + +/** + * @brief Check if the automatic clear of STOP flag is enabled or disabled. + * @rmtoll CR1 STOPFACLR LL_I2C_IsEnabledAutoClearFlag_STOP + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledAutoClearFlag_STOP(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_STOPFACLR) == (I2C_CR1_STOPFACLR)) ? 1UL : 0UL); +} + +/** + * @brief Configure the Master to operate in 7-bit or 10-bit addressing mode. + * @note Changing this bit is not allowed, when the START bit is set. + * @rmtoll CR2 ADD10 LL_I2C_SetMasterAddressingMode + * @param I2Cx I2C Instance. + * @param AddressingMode This parameter can be one of the following values: + * @arg @ref LL_I2C_ADDRESSING_MODE_7BIT + * @arg @ref LL_I2C_ADDRESSING_MODE_10BIT + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetMasterAddressingMode(I2C_TypeDef *I2Cx, uint32_t AddressingMode) +{ + MODIFY_REG(I2Cx->CR2, I2C_CR2_ADD10, AddressingMode); +} + +/** + * @brief Get the Master addressing mode. + * @rmtoll CR2 ADD10 LL_I2C_GetMasterAddressingMode + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_ADDRESSING_MODE_7BIT + * @arg @ref LL_I2C_ADDRESSING_MODE_10BIT + */ +__STATIC_INLINE uint32_t LL_I2C_GetMasterAddressingMode(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CR2, I2C_CR2_ADD10)); +} + +/** + * @brief Set the Own Address1. + * @rmtoll OAR1 OA1 LL_I2C_SetOwnAddress1\n + * OAR1 OA1MODE LL_I2C_SetOwnAddress1 + * @param I2Cx I2C Instance. + * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF. + * @param OwnAddrSize This parameter can be one of the following values: + * @arg @ref LL_I2C_OWNADDRESS1_7BIT + * @arg @ref LL_I2C_OWNADDRESS1_10BIT + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetOwnAddress1(I2C_TypeDef *I2Cx, uint32_t OwnAddress1, uint32_t OwnAddrSize) +{ + MODIFY_REG(I2Cx->OAR1, I2C_OAR1_OA1 | I2C_OAR1_OA1MODE, OwnAddress1 | OwnAddrSize); +} + +/** + * @brief Enable acknowledge on Own Address1 match address. + * @rmtoll OAR1 OA1EN LL_I2C_EnableOwnAddress1 + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableOwnAddress1(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->OAR1, I2C_OAR1_OA1EN); +} + +/** + * @brief Disable acknowledge on Own Address1 match address. + * @rmtoll OAR1 OA1EN LL_I2C_DisableOwnAddress1 + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableOwnAddress1(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->OAR1, I2C_OAR1_OA1EN); +} + +/** + * @brief Check if Own Address1 acknowledge is enabled or disabled. + * @rmtoll OAR1 OA1EN LL_I2C_IsEnabledOwnAddress1 + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledOwnAddress1(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->OAR1, I2C_OAR1_OA1EN) == (I2C_OAR1_OA1EN)) ? 1UL : 0UL); +} + +/** + * @brief Set the 7bits Own Address2. + * @note This action has no effect if own address2 is enabled. + * @rmtoll OAR2 OA2 LL_I2C_SetOwnAddress2\n + * OAR2 OA2MSK LL_I2C_SetOwnAddress2 + * @param I2Cx I2C Instance. + * @param OwnAddress2 Value between Min_Data=0 and Max_Data=0x7F. + * @param OwnAddrMask This parameter can be one of the following values: + * @arg @ref LL_I2C_OWNADDRESS2_NOMASK + * @arg @ref LL_I2C_OWNADDRESS2_MASK01 + * @arg @ref LL_I2C_OWNADDRESS2_MASK02 + * @arg @ref LL_I2C_OWNADDRESS2_MASK03 + * @arg @ref LL_I2C_OWNADDRESS2_MASK04 + * @arg @ref LL_I2C_OWNADDRESS2_MASK05 + * @arg @ref LL_I2C_OWNADDRESS2_MASK06 + * @arg @ref LL_I2C_OWNADDRESS2_MASK07 + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetOwnAddress2(I2C_TypeDef *I2Cx, uint32_t OwnAddress2, uint32_t OwnAddrMask) +{ + MODIFY_REG(I2Cx->OAR2, I2C_OAR2_OA2 | I2C_OAR2_OA2MSK, OwnAddress2 | OwnAddrMask); +} + +/** + * @brief Enable acknowledge on Own Address2 match address. + * @rmtoll OAR2 OA2EN LL_I2C_EnableOwnAddress2 + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableOwnAddress2(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->OAR2, I2C_OAR2_OA2EN); +} + +/** + * @brief Disable acknowledge on Own Address2 match address. + * @rmtoll OAR2 OA2EN LL_I2C_DisableOwnAddress2 + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableOwnAddress2(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->OAR2, I2C_OAR2_OA2EN); +} + +/** + * @brief Check if Own Address1 acknowledge is enabled or disabled. + * @rmtoll OAR2 OA2EN LL_I2C_IsEnabledOwnAddress2 + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledOwnAddress2(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->OAR2, I2C_OAR2_OA2EN) == (I2C_OAR2_OA2EN)) ? 1UL : 0UL); +} + +/** + * @brief Configure the SDA setup, hold time and the SCL high, low period. + * @note This bit can only be programmed when the I2C is disabled (PE = 0). + * @rmtoll TIMINGR TIMINGR LL_I2C_SetTiming + * @param I2Cx I2C Instance. + * @param Timing This parameter must be a value between Min_Data=0 and Max_Data=0xFFFFFFFF. + * @note This parameter is computed with the STM32CubeMX Tool. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetTiming(I2C_TypeDef *I2Cx, uint32_t Timing) +{ + WRITE_REG(I2Cx->TIMINGR, Timing); +} + +/** + * @brief Get the Timing Prescaler setting. + * @rmtoll TIMINGR PRESC LL_I2C_GetTimingPrescaler + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x0 and Max_Data=0xF + */ +__STATIC_INLINE uint32_t LL_I2C_GetTimingPrescaler(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TIMINGR, I2C_TIMINGR_PRESC) >> I2C_TIMINGR_PRESC_Pos); +} + +/** + * @brief Get the SCL low period setting. + * @rmtoll TIMINGR SCLL LL_I2C_GetClockLowPeriod + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint32_t LL_I2C_GetClockLowPeriod(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TIMINGR, I2C_TIMINGR_SCLL) >> I2C_TIMINGR_SCLL_Pos); +} + +/** + * @brief Get the SCL high period setting. + * @rmtoll TIMINGR SCLH LL_I2C_GetClockHighPeriod + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint32_t LL_I2C_GetClockHighPeriod(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TIMINGR, I2C_TIMINGR_SCLH) >> I2C_TIMINGR_SCLH_Pos); +} + +/** + * @brief Get the SDA hold time. + * @rmtoll TIMINGR SDADEL LL_I2C_GetDataHoldTime + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x0 and Max_Data=0xF + */ +__STATIC_INLINE uint32_t LL_I2C_GetDataHoldTime(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TIMINGR, I2C_TIMINGR_SDADEL) >> I2C_TIMINGR_SDADEL_Pos); +} + +/** + * @brief Get the SDA setup time. + * @rmtoll TIMINGR SCLDEL LL_I2C_GetDataSetupTime + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x0 and Max_Data=0xF + */ +__STATIC_INLINE uint32_t LL_I2C_GetDataSetupTime(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TIMINGR, I2C_TIMINGR_SCLDEL) >> I2C_TIMINGR_SCLDEL_Pos); +} + +/** + * @brief Configure peripheral mode. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 SMBHEN LL_I2C_SetMode\n + * CR1 SMBDEN LL_I2C_SetMode + * @param I2Cx I2C Instance. + * @param PeripheralMode This parameter can be one of the following values: + * @arg @ref LL_I2C_MODE_I2C + * @arg @ref LL_I2C_MODE_SMBUS_HOST + * @arg @ref LL_I2C_MODE_SMBUS_DEVICE + * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetMode(I2C_TypeDef *I2Cx, uint32_t PeripheralMode) +{ + MODIFY_REG(I2Cx->CR1, I2C_CR1_SMBHEN | I2C_CR1_SMBDEN, PeripheralMode); +} + +/** + * @brief Get peripheral mode. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 SMBHEN LL_I2C_GetMode\n + * CR1 SMBDEN LL_I2C_GetMode + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_MODE_I2C + * @arg @ref LL_I2C_MODE_SMBUS_HOST + * @arg @ref LL_I2C_MODE_SMBUS_DEVICE + * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP + */ +__STATIC_INLINE uint32_t LL_I2C_GetMode(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CR1, I2C_CR1_SMBHEN | I2C_CR1_SMBDEN)); +} + +/** + * @brief Enable SMBus alert (Host or Device mode) + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note SMBus Device mode: + * - SMBus Alert pin is drived low and + * Alert Response Address Header acknowledge is enabled. + * SMBus Host mode: + * - SMBus Alert pin management is supported. + * @rmtoll CR1 ALERTEN LL_I2C_EnableSMBusAlert + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableSMBusAlert(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_ALERTEN); +} + +/** + * @brief Disable SMBus alert (Host or Device mode) + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note SMBus Device mode: + * - SMBus Alert pin is not drived (can be used as a standard GPIO) and + * Alert Response Address Header acknowledge is disabled. + * SMBus Host mode: + * - SMBus Alert pin management is not supported. + * @rmtoll CR1 ALERTEN LL_I2C_DisableSMBusAlert + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableSMBusAlert(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_ALERTEN); +} + +/** + * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 ALERTEN LL_I2C_IsEnabledSMBusAlert + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusAlert(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_ALERTEN) == (I2C_CR1_ALERTEN)) ? 1UL : 0UL); +} + +/** + * @brief Enable SMBus Packet Error Calculation (PEC). + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 PECEN LL_I2C_EnableSMBusPEC + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableSMBusPEC(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_PECEN); +} + +/** + * @brief Disable SMBus Packet Error Calculation (PEC). + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 PECEN LL_I2C_DisableSMBusPEC + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableSMBusPEC(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_PECEN); +} + +/** + * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR1 PECEN LL_I2C_IsEnabledSMBusPEC + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPEC(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_PECEN) == (I2C_CR1_PECEN)) ? 1UL : 0UL); +} + +/** + * @brief Configure the SMBus Clock Timeout. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note This configuration can only be programmed when associated Timeout is disabled (TimeoutA and/orTimeoutB). + * @rmtoll TIMEOUTR TIMEOUTA LL_I2C_ConfigSMBusTimeout\n + * TIMEOUTR TIDLE LL_I2C_ConfigSMBusTimeout\n + * TIMEOUTR TIMEOUTB LL_I2C_ConfigSMBusTimeout + * @param I2Cx I2C Instance. + * @param TimeoutA This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. + * @param TimeoutAMode This parameter can be one of the following values: + * @arg @ref LL_I2C_SMBUS_TIMEOUTA_MODE_SCL_LOW + * @arg @ref LL_I2C_SMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH + * @param TimeoutB + * @retval None + */ +__STATIC_INLINE void LL_I2C_ConfigSMBusTimeout(I2C_TypeDef *I2Cx, uint32_t TimeoutA, uint32_t TimeoutAMode, + uint32_t TimeoutB) +{ + MODIFY_REG(I2Cx->TIMEOUTR, I2C_TIMEOUTR_TIMEOUTA | I2C_TIMEOUTR_TIDLE | I2C_TIMEOUTR_TIMEOUTB, + TimeoutA | TimeoutAMode | (TimeoutB << I2C_TIMEOUTR_TIMEOUTB_Pos)); +} + +/** + * @brief Configure the SMBus Clock TimeoutA (SCL low timeout or SCL and SDA high timeout depends on TimeoutA mode). + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note These bits can only be programmed when TimeoutA is disabled. + * @rmtoll TIMEOUTR TIMEOUTA LL_I2C_SetSMBusTimeoutA + * @param I2Cx I2C Instance. + * @param TimeoutA This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetSMBusTimeoutA(I2C_TypeDef *I2Cx, uint32_t TimeoutA) +{ + WRITE_REG(I2Cx->TIMEOUTR, TimeoutA); +} + +/** + * @brief Get the SMBus Clock TimeoutA setting. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll TIMEOUTR TIMEOUTA LL_I2C_GetSMBusTimeoutA + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0 and Max_Data=0xFFF + */ +__STATIC_INLINE uint32_t LL_I2C_GetSMBusTimeoutA(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TIMEOUTR, I2C_TIMEOUTR_TIMEOUTA)); +} + +/** + * @brief Set the SMBus Clock TimeoutA mode. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note This bit can only be programmed when TimeoutA is disabled. + * @rmtoll TIMEOUTR TIDLE LL_I2C_SetSMBusTimeoutAMode + * @param I2Cx I2C Instance. + * @param TimeoutAMode This parameter can be one of the following values: + * @arg @ref LL_I2C_SMBUS_TIMEOUTA_MODE_SCL_LOW + * @arg @ref LL_I2C_SMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetSMBusTimeoutAMode(I2C_TypeDef *I2Cx, uint32_t TimeoutAMode) +{ + WRITE_REG(I2Cx->TIMEOUTR, TimeoutAMode); +} + +/** + * @brief Get the SMBus Clock TimeoutA mode. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll TIMEOUTR TIDLE LL_I2C_GetSMBusTimeoutAMode + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_SMBUS_TIMEOUTA_MODE_SCL_LOW + * @arg @ref LL_I2C_SMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH + */ +__STATIC_INLINE uint32_t LL_I2C_GetSMBusTimeoutAMode(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TIMEOUTR, I2C_TIMEOUTR_TIDLE)); +} + +/** + * @brief Configure the SMBus Extended Cumulative Clock TimeoutB (Master or Slave mode). + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note These bits can only be programmed when TimeoutB is disabled. + * @rmtoll TIMEOUTR TIMEOUTB LL_I2C_SetSMBusTimeoutB + * @param I2Cx I2C Instance. + * @param TimeoutB This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetSMBusTimeoutB(I2C_TypeDef *I2Cx, uint32_t TimeoutB) +{ + WRITE_REG(I2Cx->TIMEOUTR, TimeoutB << I2C_TIMEOUTR_TIMEOUTB_Pos); +} + +/** + * @brief Get the SMBus Extended Cumulative Clock TimeoutB setting. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll TIMEOUTR TIMEOUTB LL_I2C_GetSMBusTimeoutB + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0 and Max_Data=0xFFF + */ +__STATIC_INLINE uint32_t LL_I2C_GetSMBusTimeoutB(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->TIMEOUTR, I2C_TIMEOUTR_TIMEOUTB) >> I2C_TIMEOUTR_TIMEOUTB_Pos); +} + +/** + * @brief Enable the SMBus Clock Timeout. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll TIMEOUTR TIMOUTEN LL_I2C_EnableSMBusTimeout\n + * TIMEOUTR TEXTEN LL_I2C_EnableSMBusTimeout + * @param I2Cx I2C Instance. + * @param ClockTimeout This parameter can be one of the following values: + * @arg @ref LL_I2C_SMBUS_TIMEOUTA + * @arg @ref LL_I2C_SMBUS_TIMEOUTB + * @arg @ref LL_I2C_SMBUS_ALL_TIMEOUT + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableSMBusTimeout(I2C_TypeDef *I2Cx, uint32_t ClockTimeout) +{ + SET_BIT(I2Cx->TIMEOUTR, ClockTimeout); +} + +/** + * @brief Disable the SMBus Clock Timeout. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll TIMEOUTR TIMOUTEN LL_I2C_DisableSMBusTimeout\n + * TIMEOUTR TEXTEN LL_I2C_DisableSMBusTimeout + * @param I2Cx I2C Instance. + * @param ClockTimeout This parameter can be one of the following values: + * @arg @ref LL_I2C_SMBUS_TIMEOUTA + * @arg @ref LL_I2C_SMBUS_TIMEOUTB + * @arg @ref LL_I2C_SMBUS_ALL_TIMEOUT + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableSMBusTimeout(I2C_TypeDef *I2Cx, uint32_t ClockTimeout) +{ + CLEAR_BIT(I2Cx->TIMEOUTR, ClockTimeout); +} + +/** + * @brief Check if the SMBus Clock Timeout is enabled or disabled. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll TIMEOUTR TIMOUTEN LL_I2C_IsEnabledSMBusTimeout\n + * TIMEOUTR TEXTEN LL_I2C_IsEnabledSMBusTimeout + * @param I2Cx I2C Instance. + * @param ClockTimeout This parameter can be one of the following values: + * @arg @ref LL_I2C_SMBUS_TIMEOUTA + * @arg @ref LL_I2C_SMBUS_TIMEOUTB + * @arg @ref LL_I2C_SMBUS_ALL_TIMEOUT + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusTimeout(const I2C_TypeDef *I2Cx, uint32_t ClockTimeout) +{ + return ((READ_BIT(I2Cx->TIMEOUTR, (I2C_TIMEOUTR_TIMOUTEN | I2C_TIMEOUTR_TEXTEN)) == \ + (ClockTimeout)) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** @defgroup I2C_LL_EF_IT_Management IT_Management + * @{ + */ + +/** + * @brief Enable TXIS interrupt. + * @rmtoll CR1 TXIE LL_I2C_EnableIT_TX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_TX(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_TXIE); +} + +/** + * @brief Disable TXIS interrupt. + * @rmtoll CR1 TXIE LL_I2C_DisableIT_TX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_TX(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_TXIE); +} + +/** + * @brief Check if the TXIS Interrupt is enabled or disabled. + * @rmtoll CR1 TXIE LL_I2C_IsEnabledIT_TX + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_TX(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_TXIE) == (I2C_CR1_TXIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable RXNE interrupt. + * @rmtoll CR1 RXIE LL_I2C_EnableIT_RX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_RX(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_RXIE); +} + +/** + * @brief Disable RXNE interrupt. + * @rmtoll CR1 RXIE LL_I2C_DisableIT_RX + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_RX(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_RXIE); +} + +/** + * @brief Check if the RXNE Interrupt is enabled or disabled. + * @rmtoll CR1 RXIE LL_I2C_IsEnabledIT_RX + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_RX(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_RXIE) == (I2C_CR1_RXIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable Address match interrupt (slave mode only). + * @rmtoll CR1 ADDRIE LL_I2C_EnableIT_ADDR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_ADDR(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_ADDRIE); +} + +/** + * @brief Disable Address match interrupt (slave mode only). + * @rmtoll CR1 ADDRIE LL_I2C_DisableIT_ADDR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_ADDR(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_ADDRIE); +} + +/** + * @brief Check if Address match interrupt is enabled or disabled. + * @rmtoll CR1 ADDRIE LL_I2C_IsEnabledIT_ADDR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_ADDR(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_ADDRIE) == (I2C_CR1_ADDRIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable Not acknowledge received interrupt. + * @rmtoll CR1 NACKIE LL_I2C_EnableIT_NACK + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_NACK(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_NACKIE); +} + +/** + * @brief Disable Not acknowledge received interrupt. + * @rmtoll CR1 NACKIE LL_I2C_DisableIT_NACK + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_NACK(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_NACKIE); +} + +/** + * @brief Check if Not acknowledge received interrupt is enabled or disabled. + * @rmtoll CR1 NACKIE LL_I2C_IsEnabledIT_NACK + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_NACK(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_NACKIE) == (I2C_CR1_NACKIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable STOP detection interrupt. + * @rmtoll CR1 STOPIE LL_I2C_EnableIT_STOP + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_STOP(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_STOPIE); +} + +/** + * @brief Disable STOP detection interrupt. + * @rmtoll CR1 STOPIE LL_I2C_DisableIT_STOP + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_STOP(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_STOPIE); +} + +/** + * @brief Check if STOP detection interrupt is enabled or disabled. + * @rmtoll CR1 STOPIE LL_I2C_IsEnabledIT_STOP + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_STOP(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_STOPIE) == (I2C_CR1_STOPIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable Transfer Complete interrupt. + * @note Any of these events will generate interrupt : + * Transfer Complete (TC) + * Transfer Complete Reload (TCR) + * @rmtoll CR1 TCIE LL_I2C_EnableIT_TC + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_TC(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_TCIE); +} + +/** + * @brief Disable Transfer Complete interrupt. + * @note Any of these events will generate interrupt : + * Transfer Complete (TC) + * Transfer Complete Reload (TCR) + * @rmtoll CR1 TCIE LL_I2C_DisableIT_TC + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_TC(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_TCIE); +} + +/** + * @brief Check if Transfer Complete interrupt is enabled or disabled. + * @rmtoll CR1 TCIE LL_I2C_IsEnabledIT_TC + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_TC(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_TCIE) == (I2C_CR1_TCIE)) ? 1UL : 0UL); +} + +/** + * @brief Enable Error interrupts. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note Any of these errors will generate interrupt : + * Arbitration Loss (ARLO) + * Bus Error detection (BERR) + * Overrun/Underrun (OVR) + * SMBus Timeout detection (TIMEOUT) + * SMBus PEC error detection (PECERR) + * SMBus Alert pin event detection (ALERT) + * @rmtoll CR1 ERRIE LL_I2C_EnableIT_ERR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableIT_ERR(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR1, I2C_CR1_ERRIE); +} + +/** + * @brief Disable Error interrupts. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note Any of these errors will generate interrupt : + * Arbitration Loss (ARLO) + * Bus Error detection (BERR) + * Overrun/Underrun (OVR) + * SMBus Timeout detection (TIMEOUT) + * SMBus PEC error detection (PECERR) + * SMBus Alert pin event detection (ALERT) + * @rmtoll CR1 ERRIE LL_I2C_DisableIT_ERR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableIT_ERR(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR1, I2C_CR1_ERRIE); +} + +/** + * @brief Check if Error interrupts are enabled or disabled. + * @rmtoll CR1 ERRIE LL_I2C_IsEnabledIT_ERR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_ERR(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR1, I2C_CR1_ERRIE) == (I2C_CR1_ERRIE)) ? 1UL : 0UL); +} + +/** + * @} + */ + +/** @defgroup I2C_LL_EF_FLAG_management FLAG_management + * @{ + */ + +/** + * @brief Indicate the status of Transmit data register empty flag. + * @note RESET: When next data is written in Transmit data register. + * SET: When Transmit data register is empty. + * @rmtoll ISR TXE LL_I2C_IsActiveFlag_TXE + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TXE(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_TXE) == (I2C_ISR_TXE)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Transmit interrupt flag. + * @note RESET: When next data is written in Transmit data register. + * SET: When Transmit data register is empty. + * @rmtoll ISR TXIS LL_I2C_IsActiveFlag_TXIS + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TXIS(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_TXIS) == (I2C_ISR_TXIS)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Receive data register not empty flag. + * @note RESET: When Receive data register is read. + * SET: When the received data is copied in Receive data register. + * @rmtoll ISR RXNE LL_I2C_IsActiveFlag_RXNE + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_RXNE(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_RXNE) == (I2C_ISR_RXNE)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Address matched flag (slave mode). + * @note RESET: Clear default value. + * SET: When the received slave address matched with one of the enabled slave address. + * @rmtoll ISR ADDR LL_I2C_IsActiveFlag_ADDR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADDR(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_ADDR) == (I2C_ISR_ADDR)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Not Acknowledge received flag. + * @note RESET: Clear default value. + * SET: When a NACK is received after a byte transmission. + * @rmtoll ISR NACKF LL_I2C_IsActiveFlag_NACK + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_NACK(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_NACKF) == (I2C_ISR_NACKF)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Stop detection flag. + * @note RESET: Clear default value. + * SET: When a Stop condition is detected. + * @rmtoll ISR STOPF LL_I2C_IsActiveFlag_STOP + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_STOP(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_STOPF) == (I2C_ISR_STOPF)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Transfer complete flag (master mode). + * @note RESET: Clear default value. + * SET: When RELOAD=0, AUTOEND=0 and NBYTES date have been transferred. + * @rmtoll ISR TC LL_I2C_IsActiveFlag_TC + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TC(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_TC) == (I2C_ISR_TC)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Transfer complete flag (master mode). + * @note RESET: Clear default value. + * SET: When RELOAD=1 and NBYTES date have been transferred. + * @rmtoll ISR TCR LL_I2C_IsActiveFlag_TCR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TCR(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_TCR) == (I2C_ISR_TCR)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Bus error flag. + * @note RESET: Clear default value. + * SET: When a misplaced Start or Stop condition is detected. + * @rmtoll ISR BERR LL_I2C_IsActiveFlag_BERR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BERR(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_BERR) == (I2C_ISR_BERR)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Arbitration lost flag. + * @note RESET: Clear default value. + * SET: When arbitration lost. + * @rmtoll ISR ARLO LL_I2C_IsActiveFlag_ARLO + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ARLO(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_ARLO) == (I2C_ISR_ARLO)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Overrun/Underrun flag (slave mode). + * @note RESET: Clear default value. + * SET: When an overrun/underrun error occurs (Clock Stretching Disabled). + * @rmtoll ISR OVR LL_I2C_IsActiveFlag_OVR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_OVR(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_OVR) == (I2C_ISR_OVR)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of SMBus PEC error flag in reception. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note RESET: Clear default value. + * SET: When the received PEC does not match with the PEC register content. + * @rmtoll ISR PECERR LL_I2C_IsActiveSMBusFlag_PECERR + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_PECERR(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_PECERR) == (I2C_ISR_PECERR)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of SMBus Timeout detection flag. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note RESET: Clear default value. + * SET: When a timeout or extended clock timeout occurs. + * @rmtoll ISR TIMEOUT LL_I2C_IsActiveSMBusFlag_TIMEOUT + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_TIMEOUT(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_TIMEOUT) == (I2C_ISR_TIMEOUT)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of SMBus alert flag. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note RESET: Clear default value. + * SET: When SMBus host configuration, SMBus alert enabled and + * a falling edge event occurs on SMBA pin. + * @rmtoll ISR ALERT LL_I2C_IsActiveSMBusFlag_ALERT + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_ALERT(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_ALERT) == (I2C_ISR_ALERT)) ? 1UL : 0UL); +} + +/** + * @brief Indicate the status of Bus Busy flag. + * @note RESET: Clear default value. + * SET: When a Start condition is detected. + * @rmtoll ISR BUSY LL_I2C_IsActiveFlag_BUSY + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BUSY(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->ISR, I2C_ISR_BUSY) == (I2C_ISR_BUSY)) ? 1UL : 0UL); +} + +/** + * @brief Clear Address Matched flag. + * @rmtoll ICR ADDRCF LL_I2C_ClearFlag_ADDR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_ADDR(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_ADDRCF); +} + +/** + * @brief Clear Not Acknowledge flag. + * @rmtoll ICR NACKCF LL_I2C_ClearFlag_NACK + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_NACK(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_NACKCF); +} + +/** + * @brief Clear Stop detection flag. + * @rmtoll ICR STOPCF LL_I2C_ClearFlag_STOP + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_STOP(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_STOPCF); +} + +/** + * @brief Clear Transmit data register empty flag (TXE). + * @note This bit can be clear by software in order to flush the transmit data register (TXDR). + * @rmtoll ISR TXE LL_I2C_ClearFlag_TXE + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_TXE(I2C_TypeDef *I2Cx) +{ + WRITE_REG(I2Cx->ISR, I2C_ISR_TXE); +} + +/** + * @brief Clear Bus error flag. + * @rmtoll ICR BERRCF LL_I2C_ClearFlag_BERR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_BERR(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_BERRCF); +} + +/** + * @brief Clear Arbitration lost flag. + * @rmtoll ICR ARLOCF LL_I2C_ClearFlag_ARLO + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_ARLO(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_ARLOCF); +} + +/** + * @brief Clear Overrun/Underrun flag. + * @rmtoll ICR OVRCF LL_I2C_ClearFlag_OVR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearFlag_OVR(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_OVRCF); +} + +/** + * @brief Clear SMBus PEC error flag. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll ICR PECCF LL_I2C_ClearSMBusFlag_PECERR + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearSMBusFlag_PECERR(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_PECCF); +} + +/** + * @brief Clear SMBus Timeout detection flag. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll ICR TIMOUTCF LL_I2C_ClearSMBusFlag_TIMEOUT + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_TIMOUTCF); +} + +/** + * @brief Clear SMBus Alert flag. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll ICR ALERTCF LL_I2C_ClearSMBusFlag_ALERT + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_ClearSMBusFlag_ALERT(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->ICR, I2C_ICR_ALERTCF); +} + +/** + * @} + */ + +/** @defgroup I2C_LL_EF_Data_Management Data_Management + * @{ + */ + +/** + * @brief Enable automatic STOP condition generation (master mode). + * @note Automatic end mode : a STOP condition is automatically sent when NBYTES data are transferred. + * This bit has no effect in slave mode or when RELOAD bit is set. + * @rmtoll CR2 AUTOEND LL_I2C_EnableAutoEndMode + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableAutoEndMode(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_AUTOEND); +} + +/** + * @brief Disable automatic STOP condition generation (master mode). + * @note Software end mode : TC flag is set when NBYTES data are transferre, stretching SCL low. + * @rmtoll CR2 AUTOEND LL_I2C_DisableAutoEndMode + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableAutoEndMode(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_AUTOEND); +} + +/** + * @brief Check if automatic STOP condition is enabled or disabled. + * @rmtoll CR2 AUTOEND LL_I2C_IsEnabledAutoEndMode + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledAutoEndMode(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR2, I2C_CR2_AUTOEND) == (I2C_CR2_AUTOEND)) ? 1UL : 0UL); +} + +/** + * @brief Enable reload mode (master mode). + * @note The transfer is not completed after the NBYTES data transfer, NBYTES will be reloaded when TCR flag is set. + * @rmtoll CR2 RELOAD LL_I2C_EnableReloadMode + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableReloadMode(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_RELOAD); +} + +/** + * @brief Disable reload mode (master mode). + * @note The transfer is completed after the NBYTES data transfer(STOP or RESTART will follow). + * @rmtoll CR2 RELOAD LL_I2C_DisableReloadMode + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableReloadMode(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_RELOAD); +} + +/** + * @brief Check if reload mode is enabled or disabled. + * @rmtoll CR2 RELOAD LL_I2C_IsEnabledReloadMode + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledReloadMode(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR2, I2C_CR2_RELOAD) == (I2C_CR2_RELOAD)) ? 1UL : 0UL); +} + +/** + * @brief Configure the number of bytes for transfer. + * @note Changing these bits when START bit is set is not allowed. + * @rmtoll CR2 NBYTES LL_I2C_SetTransferSize + * @param I2Cx I2C Instance. + * @param TransferSize This parameter must be a value between Min_Data=0x00 and Max_Data=0xFF. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetTransferSize(I2C_TypeDef *I2Cx, uint32_t TransferSize) +{ + MODIFY_REG(I2Cx->CR2, I2C_CR2_NBYTES, TransferSize << I2C_CR2_NBYTES_Pos); +} + +/** + * @brief Get the number of bytes configured for transfer. + * @rmtoll CR2 NBYTES LL_I2C_GetTransferSize + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x0 and Max_Data=0xFF + */ +__STATIC_INLINE uint32_t LL_I2C_GetTransferSize(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CR2, I2C_CR2_NBYTES) >> I2C_CR2_NBYTES_Pos); +} + +/** + * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code + or next received byte. + * @note Usage in Slave mode only. + * @rmtoll CR2 NACK LL_I2C_AcknowledgeNextData + * @param I2Cx I2C Instance. + * @param TypeAcknowledge This parameter can be one of the following values: + * @arg @ref LL_I2C_ACK + * @arg @ref LL_I2C_NACK + * @retval None + */ +__STATIC_INLINE void LL_I2C_AcknowledgeNextData(I2C_TypeDef *I2Cx, uint32_t TypeAcknowledge) +{ + MODIFY_REG(I2Cx->CR2, I2C_CR2_NACK, TypeAcknowledge); +} + +/** + * @brief Generate a START or RESTART condition + * @note The START bit can be set even if bus is BUSY or I2C is in slave mode. + * This action has no effect when RELOAD is set. + * @rmtoll CR2 START LL_I2C_GenerateStartCondition + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_GenerateStartCondition(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_START); +} + +/** + * @brief Generate a STOP condition after the current byte transfer (master mode). + * @rmtoll CR2 STOP LL_I2C_GenerateStopCondition + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_GenerateStopCondition(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_STOP); +} + +/** + * @brief Enable automatic RESTART Read request condition for 10bit address header (master mode). + * @note The master sends the complete 10bit slave address read sequence : + * Start + 2 bytes 10bit address in Write direction + Restart + first 7 bits of 10bit address + in Read direction. + * @rmtoll CR2 HEAD10R LL_I2C_EnableAuto10BitRead + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableAuto10BitRead(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->CR2, I2C_CR2_HEAD10R); +} + +/** + * @brief Disable automatic RESTART Read request condition for 10bit address header (master mode). + * @note The master only sends the first 7 bits of 10bit address in Read direction. + * @rmtoll CR2 HEAD10R LL_I2C_DisableAuto10BitRead + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_DisableAuto10BitRead(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_HEAD10R); +} + +/** + * @brief Check if automatic RESTART Read request condition for 10bit address header is enabled or disabled. + * @rmtoll CR2 HEAD10R LL_I2C_IsEnabledAuto10BitRead + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledAuto10BitRead(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR2, I2C_CR2_HEAD10R) != (I2C_CR2_HEAD10R)) ? 1UL : 0UL); +} + +/** + * @brief Configure the transfer direction (master mode). + * @note Changing these bits when START bit is set is not allowed. + * @rmtoll CR2 RD_WRN LL_I2C_SetTransferRequest + * @param I2Cx I2C Instance. + * @param TransferRequest This parameter can be one of the following values: + * @arg @ref LL_I2C_REQUEST_WRITE + * @arg @ref LL_I2C_REQUEST_READ + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetTransferRequest(I2C_TypeDef *I2Cx, uint32_t TransferRequest) +{ + MODIFY_REG(I2Cx->CR2, I2C_CR2_RD_WRN, TransferRequest); +} + +/** + * @brief Get the transfer direction requested (master mode). + * @rmtoll CR2 RD_WRN LL_I2C_GetTransferRequest + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_REQUEST_WRITE + * @arg @ref LL_I2C_REQUEST_READ + */ +__STATIC_INLINE uint32_t LL_I2C_GetTransferRequest(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CR2, I2C_CR2_RD_WRN)); +} + +/** + * @brief Configure the slave address for transfer (master mode). + * @note Changing these bits when START bit is set is not allowed. + * @rmtoll CR2 SADD LL_I2C_SetSlaveAddr + * @param I2Cx I2C Instance. + * @param SlaveAddr This parameter must be a value between Min_Data=0x00 and Max_Data=0x3F. + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetSlaveAddr(I2C_TypeDef *I2Cx, uint32_t SlaveAddr) +{ + MODIFY_REG(I2Cx->CR2, I2C_CR2_SADD, SlaveAddr); +} + +/** + * @brief Get the slave address programmed for transfer. + * @rmtoll CR2 SADD LL_I2C_GetSlaveAddr + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x0 and Max_Data=0x3F + */ +__STATIC_INLINE uint32_t LL_I2C_GetSlaveAddr(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->CR2, I2C_CR2_SADD)); +} + +/** + * @brief Handles I2Cx communication when starting transfer or during transfer (TC or TCR flag are set). + * @rmtoll CR2 SADD LL_I2C_HandleTransfer\n + * CR2 ADD10 LL_I2C_HandleTransfer\n + * CR2 RD_WRN LL_I2C_HandleTransfer\n + * CR2 START LL_I2C_HandleTransfer\n + * CR2 STOP LL_I2C_HandleTransfer\n + * CR2 RELOAD LL_I2C_HandleTransfer\n + * CR2 NBYTES LL_I2C_HandleTransfer\n + * CR2 AUTOEND LL_I2C_HandleTransfer\n + * CR2 HEAD10R LL_I2C_HandleTransfer + * @param I2Cx I2C Instance. + * @param SlaveAddr Specifies the slave address to be programmed. + * @param SlaveAddrSize This parameter can be one of the following values: + * @arg @ref LL_I2C_ADDRSLAVE_7BIT + * @arg @ref LL_I2C_ADDRSLAVE_10BIT + * @param TransferSize Specifies the number of bytes to be programmed. + * This parameter must be a value between Min_Data=0 and Max_Data=255. + * @param EndMode This parameter can be one of the following values: + * @arg @ref LL_I2C_MODE_RELOAD + * @arg @ref LL_I2C_MODE_AUTOEND + * @arg @ref LL_I2C_MODE_SOFTEND + * @arg @ref LL_I2C_MODE_SMBUS_RELOAD + * @arg @ref LL_I2C_MODE_SMBUS_AUTOEND_NO_PEC + * @arg @ref LL_I2C_MODE_SMBUS_SOFTEND_NO_PEC + * @arg @ref LL_I2C_MODE_SMBUS_AUTOEND_WITH_PEC + * @arg @ref LL_I2C_MODE_SMBUS_SOFTEND_WITH_PEC + * @param Request This parameter can be one of the following values: + * @arg @ref LL_I2C_GENERATE_NOSTARTSTOP + * @arg @ref LL_I2C_GENERATE_STOP + * @arg @ref LL_I2C_GENERATE_START_READ + * @arg @ref LL_I2C_GENERATE_START_WRITE + * @arg @ref LL_I2C_GENERATE_RESTART_7BIT_READ + * @arg @ref LL_I2C_GENERATE_RESTART_7BIT_WRITE + * @arg @ref LL_I2C_GENERATE_RESTART_10BIT_READ + * @arg @ref LL_I2C_GENERATE_RESTART_10BIT_WRITE + * @retval None + */ +__STATIC_INLINE void LL_I2C_HandleTransfer(I2C_TypeDef *I2Cx, uint32_t SlaveAddr, uint32_t SlaveAddrSize, + uint32_t TransferSize, uint32_t EndMode, uint32_t Request) +{ + /* Declaration of tmp to prevent undefined behavior of volatile usage */ + uint32_t tmp = ((uint32_t)(((uint32_t)SlaveAddr & I2C_CR2_SADD) | \ + ((uint32_t)SlaveAddrSize & I2C_CR2_ADD10) | \ + (((uint32_t)TransferSize << I2C_CR2_NBYTES_Pos) & I2C_CR2_NBYTES) | \ + (uint32_t)EndMode | (uint32_t)Request) & (~0x80000000U)); + + /* update CR2 register */ + MODIFY_REG(I2Cx->CR2, I2C_CR2_SADD | I2C_CR2_ADD10 | + (I2C_CR2_RD_WRN & (uint32_t)(Request >> (31U - I2C_CR2_RD_WRN_Pos))) | + I2C_CR2_START | I2C_CR2_STOP | I2C_CR2_RELOAD | + I2C_CR2_NBYTES | I2C_CR2_AUTOEND | I2C_CR2_HEAD10R, + tmp); +} + +/** + * @brief Indicate the value of transfer direction (slave mode). + * @note RESET: Write transfer, Slave enters in receiver mode. + * SET: Read transfer, Slave enters in transmitter mode. + * @rmtoll ISR DIR LL_I2C_GetTransferDirection + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_DIRECTION_WRITE + * @arg @ref LL_I2C_DIRECTION_READ + */ +__STATIC_INLINE uint32_t LL_I2C_GetTransferDirection(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->ISR, I2C_ISR_DIR)); +} + +/** + * @brief Return the slave matched address. + * @rmtoll ISR ADDCODE LL_I2C_GetAddressMatchCode + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x00 and Max_Data=0x3F + */ +__STATIC_INLINE uint32_t LL_I2C_GetAddressMatchCode(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->ISR, I2C_ISR_ADDCODE) >> I2C_ISR_ADDCODE_Pos << 1); +} + +/** + * @brief Enable internal comparison of the SMBus Packet Error byte (transmission or reception mode). + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @note This feature is cleared by hardware when the PEC byte is transferred, or when a STOP condition + or an Address Matched is received. + * This bit has no effect when RELOAD bit is set. + * This bit has no effect in device mode when SBC bit is not set. + * @rmtoll CR2 PECBYTE LL_I2C_EnableSMBusPECCompare + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_EnableSMBusPECCompare(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->CR2, I2C_CR2_PECBYTE); +} + +/** + * @brief Check if the SMBus Packet Error byte internal comparison is requested or not. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll CR2 PECBYTE LL_I2C_IsEnabledSMBusPECCompare + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPECCompare(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->CR2, I2C_CR2_PECBYTE) == (I2C_CR2_PECBYTE)) ? 1UL : 0UL); +} + +/** + * @brief Get the SMBus Packet Error byte calculated. + * @note The macro IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not + * SMBus feature is supported by the I2Cx Instance. + * @rmtoll PECR PEC LL_I2C_GetSMBusPEC + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint32_t LL_I2C_GetSMBusPEC(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->PECR, I2C_PECR_PEC)); +} + +/** + * @brief Read Receive Data register. + * @rmtoll RXDR RXDATA LL_I2C_ReceiveData8 + * @param I2Cx I2C Instance. + * @retval Value between Min_Data=0x00 and Max_Data=0xFF + */ +__STATIC_INLINE uint8_t LL_I2C_ReceiveData8(const I2C_TypeDef *I2Cx) +{ + return (uint8_t)(READ_BIT(I2Cx->RXDR, I2C_RXDR_RXDATA)); +} + +/** + * @brief Write in Transmit Data Register . + * @rmtoll TXDR TXDATA LL_I2C_TransmitData8 + * @param I2Cx I2C Instance. + * @param Data Value between Min_Data=0x00 and Max_Data=0xFF + * @retval None + */ +__STATIC_INLINE void LL_I2C_TransmitData8(I2C_TypeDef *I2Cx, uint8_t Data) +{ + WRITE_REG(I2Cx->TXDR, Data); +} + +/** + * @} + */ + +/** @defgroup I2C_LL_EF_AutonomousMode Configuration functions related to Autonomous mode feature + * @{ + */ + +/** + * @brief Enable Selected Trigger + * @rmtoll AUTOCR TRIGEN LL_I2C_Enable_SelectedTrigger + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_Enable_SelectedTrigger(I2C_TypeDef *I2Cx) +{ + SET_BIT(I2Cx->AUTOCR, I2C_AUTOCR_TRIGEN); +} + +/** + * @brief Disable Selected Trigger + * @rmtoll AUTOCR TRIGEN LL_I2C_Disable_SelectedTrigger + * @param I2Cx I2C Instance. + * @retval None + */ +__STATIC_INLINE void LL_I2C_Disable_SelectedTrigger(I2C_TypeDef *I2Cx) +{ + CLEAR_BIT(I2Cx->AUTOCR, I2C_AUTOCR_TRIGEN); +} + +/** + * @brief Indicate if selected Trigger is disabled or enabled + * @rmtoll AUTOCR TRIGEN LL_I2C_IsEnabled_SelectedTrigger + * @param I2Cx I2C Instance. + * @retval State of bit (1 or 0). + */ +__STATIC_INLINE uint32_t LL_I2C_IsEnabled_SelectedTrigger(const I2C_TypeDef *I2Cx) +{ + return ((READ_BIT(I2Cx->AUTOCR, I2C_AUTOCR_TRIGEN) == (I2C_AUTOCR_TRIGEN)) ? 1UL : 0UL); +} + +/** + * @brief Set the trigger polarity + * @rmtoll AUTOCR TRIGPOL LL_I2C_SetTriggerPolarity + * @param I2Cx I2C Instance. + * @param Polarity This parameter can be one of the following values: + * @arg @ref LL_I2C_TRIG_POLARITY_RISING + * @arg @ref LL_I2C_TRIG_POLARITY_FALLING + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetTriggerPolarity(I2C_TypeDef *I2Cx, uint32_t Polarity) +{ + MODIFY_REG(I2Cx->AUTOCR, I2C_AUTOCR_TRIGPOL, Polarity); +} + +/** + * @brief Get the trigger polarity + * @rmtoll AUTOCR TRIGPOL LL_I2C_GetTriggerPolarity + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_TRIG_POLARITY_RISING + * @arg @ref LL_I2C_TRIG_POLARITY_FALLING + */ +__STATIC_INLINE uint32_t LL_I2C_GetTriggerPolarity(const I2C_TypeDef *I2Cx) +{ + return (uint32_t)(READ_BIT(I2Cx->AUTOCR, I2C_AUTOCR_TRIGPOL)); +} + +/** + * @brief Set the selected trigger + * @rmtoll AUTOCR TRIGSEL LL_I2C_SetSelectedTrigger + * @param I2Cx I2C Instance. + * @param Trigger This parameter can be one of the following values: + * @arg @ref LL_I2C_GRP1_GPDMA_CH0_TCF_TRG + * @arg @ref LL_I2C_GRP1_GPDMA_CH1_TCF_TRG + * @arg @ref LL_I2C_GRP1_GPDMA_CH2_TCF_TRG + * @arg @ref LL_I2C_GRP1_GPDMA_CH3_TCF_TRG + * @arg @ref LL_I2C_GRP1_EXTI5_TRG + * @arg @ref LL_I2C_GRP1_EXTI9_TRG + * @arg @ref LL_I2C_GRP1_LPTIM1_CH1_TRG + * @arg @ref LL_I2C_GRP1_LPTIM2_CH1_TRG + * @arg @ref LL_I2C_GRP1_COMP1_TRG + * @arg @ref LL_I2C_GRP1_COMP2_TRG + * @arg @ref LL_I2C_GRP1_RTC_ALRA_TRG + * @arg @ref LL_I2C_GRP1_RTC_WUT_TRG + * @arg @ref LL_I2C_GRP2_LPDMA_CH0_TCF_TRG + * @arg @ref LL_I2C_GRP2_LPDMA_CH1_TCF_TRG + * @arg @ref LL_I2C_GRP2_LPDMA_CH2_TCF_TRG + * @arg @ref LL_I2C_GRP2_LPDMA_CH3_TCF_TRG + * @arg @ref LL_I2C_GRP2_EXTI5_TRG + * @arg @ref LL_I2C_GRP2_EXTI8_TRG + * @arg @ref LL_I2C_GRP2_LPTIM1_CH1_TRG + * @arg @ref LL_I2C_GRP2_LPTIM3_CH1_TRG + * @arg @ref LL_I2C_GRP2_COMP1_TRG + * @arg @ref LL_I2C_GRP2_COMP2_TRG + * @arg @ref LL_I2C_GRP2_RTC_ALRA_TRG + * @arg @ref LL_I2C_GRP2_RTC_WUT_TRG + * @retval None + */ +__STATIC_INLINE void LL_I2C_SetSelectedTrigger(I2C_TypeDef *I2Cx, uint32_t Trigger) +{ + MODIFY_REG(I2Cx->AUTOCR, I2C_AUTOCR_TRIGSEL, (Trigger & I2C_AUTOCR_TRIGSEL_Msk)); +} + +/** + * @brief Get the selected trigger + * @rmtoll AUTOCR TRIGSEL LL_I2C_GetSelectedTrigger + * @param I2Cx I2C Instance. + * @retval Returned value can be one of the following values: + * @arg @ref LL_I2C_GRP1_GPDMA_CH0_TCF_TRG + * @arg @ref LL_I2C_GRP1_GPDMA_CH1_TCF_TRG + * @arg @ref LL_I2C_GRP1_GPDMA_CH2_TCF_TRG + * @arg @ref LL_I2C_GRP1_GPDMA_CH3_TCF_TRG + * @arg @ref LL_I2C_GRP1_EXTI5_TRG + * @arg @ref LL_I2C_GRP1_EXTI9_TRG + * @arg @ref LL_I2C_GRP1_LPTIM1_CH1_TRG + * @arg @ref LL_I2C_GRP1_LPTIM2_CH1_TRG + * @arg @ref LL_I2C_GRP1_COMP1_TRG + * @arg @ref LL_I2C_GRP1_COMP2_TRG + * @arg @ref LL_I2C_GRP1_RTC_ALRA_TRG + * @arg @ref LL_I2C_GRP1_RTC_WUT_TRG + * @arg @ref LL_I2C_GRP2_LPDMA_CH0_TCF_TRG + * @arg @ref LL_I2C_GRP2_LPDMA_CH1_TCF_TRG + * @arg @ref LL_I2C_GRP2_LPDMA_CH2_TCF_TRG + * @arg @ref LL_I2C_GRP2_LPDMA_CH3_TCF_TRG + * @arg @ref LL_I2C_GRP2_EXTI5_TRG + * @arg @ref LL_I2C_GRP2_EXTI8_TRG + * @arg @ref LL_I2C_GRP2_LPTIM1_CH1_TRG + * @arg @ref LL_I2C_GRP2_LPTIM3_CH1_TRG + * @arg @ref LL_I2C_GRP2_COMP1_TRG + * @arg @ref LL_I2C_GRP2_COMP2_TRG + * @arg @ref LL_I2C_GRP2_RTC_ALRA_TRG + * @arg @ref LL_I2C_GRP2_RTC_WUT_TRG + */ +__STATIC_INLINE uint32_t LL_I2C_GetSelectedTrigger(const I2C_TypeDef *I2Cx) +{ + if (IS_LL_I2C_GRP2_INSTANCE(I2Cx)) + { + return (uint32_t)((READ_BIT(I2Cx->AUTOCR, I2C_AUTOCR_TRIGSEL) | LL_I2C_TRIG_GRP2)); + } + else + { + return (uint32_t)((READ_BIT(I2Cx->AUTOCR, I2C_AUTOCR_TRIGSEL) | LL_I2C_TRIG_GRP1)); + } +} + +/** + * @} + */ + +#if defined(USE_FULL_LL_DRIVER) +/** @defgroup I2C_LL_EF_Init Initialization and de-initialization functions + * @{ + */ + +ErrorStatus LL_I2C_Init(I2C_TypeDef *I2Cx, const LL_I2C_InitTypeDef *I2C_InitStruct); +ErrorStatus LL_I2C_DeInit(const I2C_TypeDef *I2Cx); +void LL_I2C_StructInit(LL_I2C_InitTypeDef *I2C_InitStruct); + + +/** + * @} + */ +#endif /* USE_FULL_LL_DRIVER */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* I2C1 || I2C2 || I2C3 || I2C4 || I2C5 || I2C6 */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32U5xx_LL_I2C_H */ diff --git a/ThreadX_Os/ThreadX_Os.ioc b/ThreadX_Os/ThreadX_Os.ioc index 491ea92..670b289 100644 --- a/ThreadX_Os/ThreadX_Os.ioc +++ b/ThreadX_Os/ThreadX_Os.ioc @@ -6,18 +6,16 @@ CORTEX_M33_NS.userName=CORTEX_M33 FDCAN1.AutoRetransmission=ENABLE FDCAN1.CalculateBaudRateNominal=500000 FDCAN1.CalculateTimeBitNominal=2000 -FDCAN1.CalculateTimeQuantumNominal=100.0 -FDCAN1.DataTimeSeg1=1 -FDCAN1.DataTimeSeg2=1 -FDCAN1.FrameFormat=FDCAN_FRAME_CLASSIC -FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,FrameFormat,AutoRetransmission,Mode,TxFifoQueueMode,DataTimeSeg1,DataTimeSeg2,StdFiltersNbr,NominalTimeSeg1,NominalTimeSeg2 -FDCAN1.Mode=FDCAN_MODE_NORMAL -FDCAN1.NominalTimeSeg1=13 -FDCAN1.NominalTimeSeg2=6 -FDCAN1.StdFiltersNbr=1 +FDCAN1.CalculateTimeQuantumNominal=111.11111111111111 +FDCAN1.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,AutoRetransmission,NominalPrescaler,NominalTimeSeg1,NominalTimeSeg2,TxFifoQueueMode +FDCAN1.NominalPrescaler=4 +FDCAN1.NominalTimeSeg1=15 +FDCAN1.NominalTimeSeg2=2 FDCAN1.TxFifoQueueMode=FDCAN_TX_QUEUE_OPERATION File.Version=6 -GPIO.groupedBy= +GPIO.groupedBy=Group By Peripherals +I2C3.IPParameters=Timing +I2C3.Timing=0x10808DD3 KeepUserPlacement=false MMTAppRegionsCount=0 MMTConfigApplied=false @@ -26,12 +24,12 @@ Mcu.CPN=STM32U585AII6Q Mcu.ContextProject=TrustZoneDisabled Mcu.Family=STM32U5 Mcu.IP0=CORTEX_M33_NS -Mcu.IP1=DEBUG +Mcu.IP1=FDCAN1 Mcu.IP10=SYS Mcu.IP11=THREADX Mcu.IP12=TIM1 Mcu.IP13=USART1 -Mcu.IP2=FDCAN1 +Mcu.IP2=I2C3 Mcu.IP3=ICACHE Mcu.IP4=LPBAM Mcu.IP5=LPBAMQUEUE @@ -58,69 +56,67 @@ Mcu.Pin2=PA15 (JTDI) Mcu.Pin20=PC13 Mcu.Pin21=PB8 Mcu.Pin22=PH9 -Mcu.Pin23=PH4 -Mcu.Pin24=PH6 -Mcu.Pin25=PF8 -Mcu.Pin26=PF1 -Mcu.Pin27=PF2 -Mcu.Pin28=PD1 -Mcu.Pin29=PH7 +Mcu.Pin23=PH6 +Mcu.Pin24=PF8 +Mcu.Pin25=PF1 +Mcu.Pin26=PF2 +Mcu.Pin27=PD1 +Mcu.Pin28=PH7 +Mcu.Pin29=PH2 Mcu.Pin3=PI5 -Mcu.Pin30=PH5 -Mcu.Pin31=PH2 -Mcu.Pin32=PA10 -Mcu.Pin33=PA13 (JTMS/SWDIO) -Mcu.Pin34=PA12 -Mcu.Pin35=PF7 -Mcu.Pin36=PF9 -Mcu.Pin37=PF3 -Mcu.Pin38=PF4 -Mcu.Pin39=PA8 +Mcu.Pin30=PA10 +Mcu.Pin31=PA13 (JTMS/SWDIO) +Mcu.Pin32=PA12 +Mcu.Pin33=PF7 +Mcu.Pin34=PF9 +Mcu.Pin35=PF3 +Mcu.Pin36=PF4 +Mcu.Pin37=PA8 +Mcu.Pin38=PA9 +Mcu.Pin39=PA11 Mcu.Pin4=PI0 -Mcu.Pin40=PA9 -Mcu.Pin41=PA11 -Mcu.Pin42=PF10 -Mcu.Pin43=PF6 -Mcu.Pin44=PE10 -Mcu.Pin45=PG6 -Mcu.Pin46=PH1-OSC_OUT (PH1) -Mcu.Pin47=PC1 -Mcu.Pin48=PA7 -Mcu.Pin49=PE9 +Mcu.Pin40=PF10 +Mcu.Pin41=PF6 +Mcu.Pin42=PE10 +Mcu.Pin43=PG6 +Mcu.Pin44=PH1-OSC_OUT (PH1) +Mcu.Pin45=PC1 +Mcu.Pin46=PA7 +Mcu.Pin47=PE9 +Mcu.Pin48=PG5 +Mcu.Pin49=PD14 Mcu.Pin5=PH12 -Mcu.Pin50=PG5 -Mcu.Pin51=PD14 -Mcu.Pin52=PC3 -Mcu.Pin53=PF12 -Mcu.Pin54=PE8 -Mcu.Pin55=PB10 -Mcu.Pin56=PD10 -Mcu.Pin57=PD13 -Mcu.Pin58=PG2 -Mcu.Pin59=PF14 +Mcu.Pin50=PC3 +Mcu.Pin51=PF12 +Mcu.Pin52=PE8 +Mcu.Pin53=PB10 +Mcu.Pin54=PD10 +Mcu.Pin55=PD13 +Mcu.Pin56=PG2 +Mcu.Pin57=PF14 +Mcu.Pin58=PB11 +Mcu.Pin59=PB12 Mcu.Pin6=PH3-BOOT0 -Mcu.Pin60=PB11 -Mcu.Pin61=PB12 -Mcu.Pin62=PB15 -Mcu.Pin63=PF11 -Mcu.Pin64=PE11 -Mcu.Pin65=PB1 -Mcu.Pin66=PF15 -Mcu.Pin67=VP_ICACHE_VS_ICACHE -Mcu.Pin68=VP_LPBAMQUEUE_VS_QUEUE -Mcu.Pin69=VP_PWR_VS_DBSignals +Mcu.Pin60=PB15 +Mcu.Pin61=PF11 +Mcu.Pin62=PE11 +Mcu.Pin63=PB1 +Mcu.Pin64=PF15 +Mcu.Pin65=VP_ICACHE_VS_ICACHE +Mcu.Pin66=VP_LPBAMQUEUE_VS_QUEUE +Mcu.Pin67=VP_PWR_VS_DBSignals +Mcu.Pin68=VP_PWR_VS_SECSignals +Mcu.Pin69=VP_PWR_VS_LPOM Mcu.Pin7=PB5 -Mcu.Pin70=VP_PWR_VS_SECSignals -Mcu.Pin71=VP_PWR_VS_LPOM -Mcu.Pin72=VP_SYS_VS_tim6 -Mcu.Pin73=VP_THREADX_VS_RTOSJjThreadXJjCoreJjDefault -Mcu.Pin74=VP_TIM1_VS_ControllerModeClock -Mcu.Pin75=VP_LPBAM_VS_SIG1 -Mcu.Pin76=VP_LPBAM_VS_SIG4 -Mcu.Pin77=VP_MEMORYMAP_VS_MEMORYMAP +Mcu.Pin70=VP_SYS_VS_tim6 +Mcu.Pin71=VP_THREADX_VS_RTOSJjThreadXJjCoreJjDefault +Mcu.Pin72=VP_TIM1_VS_ControllerModeClock +Mcu.Pin73=VP_LPBAM_VS_SIG1 +Mcu.Pin74=VP_LPBAM_VS_SIG4 +Mcu.Pin75=VP_MEMORYMAP_VS_MEMORYMAP Mcu.Pin8=PD4 Mcu.Pin9=PC10 -Mcu.PinsNb=78 +Mcu.PinsNb=76 Mcu.ThirdPartyNb=0 Mcu.UserConstants= Mcu.UserName=STM32U585AIIxQ @@ -159,18 +155,19 @@ PA12.Signal=USB_OTG_FS_DP PA13\ (JTMS/SWDIO).GPIOParameters=GPIO_Label PA13\ (JTMS/SWDIO).GPIO_Label=T.SWDIO PA13\ (JTMS/SWDIO).Locked=true -PA13\ (JTMS/SWDIO).Mode=Trace_Asynchronous_SW PA13\ (JTMS/SWDIO).Signal=DEBUG_JTMS-SWDIO PA14\ (JTCK/SWCLK).GPIOParameters=GPIO_Label PA14\ (JTCK/SWCLK).GPIO_Label=T.SWCLK PA14\ (JTCK/SWCLK).Locked=true -PA14\ (JTCK/SWCLK).Mode=Trace_Asynchronous_SW PA14\ (JTCK/SWCLK).Signal=DEBUG_JTCK-SWCLK PA15\ (JTDI).GPIOParameters=GPIO_Label PA15\ (JTDI).GPIO_Label=USB.UCPD_CC1 PA15\ (JTDI).Locked=true PA15\ (JTDI).Signal=UCPD1_CC1 +PA7.GPIOParameters=GPIO_Pu +PA7.GPIO_Pu=GPIO_PULLUP PA7.Locked=true +PA7.Mode=I2C PA7.Signal=I2C3_SCL PA8.Signal=S_TIM1_CH1 PA9.GPIOParameters=GPIO_Label @@ -201,7 +198,6 @@ PB15.Signal=UCPD1_CC2 PB3\ (JTDO/TRACESWO).GPIOParameters=GPIO_Label PB3\ (JTDO/TRACESWO).GPIO_Label=T.SWO PB3\ (JTDO/TRACESWO).Locked=true -PB3\ (JTDO/TRACESWO).Mode=Trace_Asynchronous_SW PB3\ (JTDO/TRACESWO).Signal=DEBUG_JTDO-SWO PB5.GPIOParameters=GPIO_Label PB5.GPIO_Label=UCPD_PWR @@ -213,7 +209,10 @@ PB8.Signal=FDCAN1_RX PB9.Locked=true PB9.Mode=FDCAN_Activate PB9.Signal=FDCAN1_TX +PC1.GPIOParameters=GPIO_Pu +PC1.GPIO_Pu=GPIO_PULLUP PC1.Locked=true +PC1.Mode=I2C PC1.Signal=I2C3_SDA PC10.GPIOParameters=GPIO_Label PC10.GPIO_Label=WRLS.UART4_TX @@ -381,10 +380,6 @@ PH3-BOOT0.GPIOParameters=GPIO_Label PH3-BOOT0.GPIO_Label=PH3-BOOT0 PH3-BOOT0.Locked=true PH3-BOOT0.Signal=GPIO_Input -PH4.Locked=true -PH4.Signal=I2C2_SCL -PH5.Locked=true -PH5.Signal=I2C2_SDA PH6.GPIOParameters=GPIO_Label PH6.GPIO_Label=LED_RED PH6.Locked=true @@ -442,79 +437,80 @@ ProjectManager.ToolChainLocation= ProjectManager.UAScriptAfterPath= ProjectManager.UAScriptBeforePath= ProjectManager.UnderRoot=false -ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_ICACHE_Init-ICACHE-false-HAL-true,4-MX_USART1_UART_Init-USART1-false-HAL-true,5-MX_FDCAN1_Init-FDCAN1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,0-MX_CORTEX_M33_NS_Init-CORTEX_M33_NS-false-HAL-true,0-MX_PWR_Init-PWR-false-HAL-true +ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_ICACHE_Init-ICACHE-false-HAL-true,4-MX_USART1_UART_Init-USART1-false-HAL-true,5-MX_TIM1_Init-TIM1-false-HAL-true,6-MX_FDCAN1_Init-FDCAN1-false-HAL-true,7-MX_I2C3_Init-I2C3-false-HAL-true,0-MX_CORTEX_M33_NS_Init-CORTEX_M33_NS-false-HAL-true,0-MX_PWR_Init-PWR-false-HAL-true RCC.ADCFreq_Value=16000000 -RCC.ADF1Freq_Value=160000000 -RCC.AHBFreq_Value=160000000 -RCC.APB1Freq_Value=160000000 -RCC.APB1TimFreq_Value=160000000 -RCC.APB2Freq_Value=160000000 -RCC.APB2TimFreq_Value=160000000 -RCC.APB3Freq_Value=160000000 +RCC.ADF1Freq_Value=72000000 +RCC.AHBFreq_Value=72000000 +RCC.APB1Freq_Value=72000000 +RCC.APB1TimFreq_Value=72000000 +RCC.APB2Freq_Value=72000000 +RCC.APB2TimFreq_Value=72000000 +RCC.APB3Freq_Value=72000000 RCC.CK48Freq_Value=48000000 RCC.CRSFreq_Value=48000000 -RCC.CortexFreq_Value=160000000 +RCC.CortexFreq_Value=72000000 RCC.DACCLockSelectionVirtual=RCC_DAC1CLKSOURCE_LSI RCC.DACFreq_Value=32000 -RCC.EPOD_VALUE=4000000 -RCC.FCLKCortexFreq_Value=160000000 -RCC.FDCANFreq_Value=160000000 +RCC.EPOD_VALUE=48000000 +RCC.FCLKCortexFreq_Value=72000000 +RCC.FDCANFreq_Value=36000000 RCC.FamilyName=M -RCC.HCLKFreq_Value=160000000 +RCC.HCLKFreq_Value=72000000 RCC.HSE_VALUE=16000000 RCC.HSI48_VALUE=48000000 RCC.HSI_VALUE=16000000 -RCC.I2C1Freq_Value=160000000 -RCC.I2C2Freq_Value=160000000 -RCC.I2C3Freq_Value=160000000 -RCC.I2C4Freq_Value=160000000 -RCC.IPParameters=ADCFreq_Value,ADF1Freq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,APB3Freq_Value,CK48Freq_Value,CRSFreq_Value,CortexFreq_Value,DACCLockSelectionVirtual,DACFreq_Value,EPOD_VALUE,FCLKCortexFreq_Value,FDCANFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2C4Freq_Value,LPTIM2Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSIDIV_VALUE,LSI_VALUE,MCO1PinFreq_Value,MDF1Freq_Value,MSI_VALUE,OCTOSPIMFreq_Value,PLL2PoutputFreq_Value,PLL2QoutputFreq_Value,PLL2RoutputFreq_Value,PLL3PoutputFreq_Value,PLL3QoutputFreq_Value,PLL3RoutputFreq_Value,PLLN,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,RNGFreq_Value,SAESFreq_Value,SAI1Freq_Value,SAI2Freq_Value,SDMMCFreq_Value,SPI1Freq_Value,SPI2Freq_Value,SPI3Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,UART5Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOPLL2OutputFreq_Value,VCOPLL3OutputFreq_Value -RCC.LPTIM2Freq_Value=160000000 -RCC.LPUART1Freq_Value=160000000 +RCC.I2C1Freq_Value=72000000 +RCC.I2C2Freq_Value=72000000 +RCC.I2C3Freq_Value=72000000 +RCC.I2C4Freq_Value=72000000 +RCC.IPParameters=ADCFreq_Value,ADF1Freq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,APB3Freq_Value,CK48Freq_Value,CRSFreq_Value,CortexFreq_Value,DACCLockSelectionVirtual,DACFreq_Value,EPOD_VALUE,FCLKCortexFreq_Value,FDCANFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2C4Freq_Value,LPTIM2Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSIDIV_VALUE,LSI_VALUE,MCO1PinFreq_Value,MDF1Freq_Value,MSIClockRange,MSI_VALUE,OCTOSPIMFreq_Value,PLL1Q,PLL2PoutputFreq_Value,PLL2QoutputFreq_Value,PLL2RoutputFreq_Value,PLL3PoutputFreq_Value,PLL3QoutputFreq_Value,PLL3RoutputFreq_Value,PLLFRACN,PLLM,PLLN,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,RNGFreq_Value,SAESFreq_Value,SAI1Freq_Value,SAI2Freq_Value,SDMMCFreq_Value,SPI1Freq_Value,SPI2Freq_Value,SPI3Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,UART5Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOPLL2OutputFreq_Value,VCOPLL3OutputFreq_Value +RCC.LPTIM2Freq_Value=72000000 +RCC.LPUART1Freq_Value=72000000 RCC.LSCOPinFreq_Value=32000 RCC.LSIDIV_VALUE=32000 RCC.LSI_VALUE=32000 -RCC.MCO1PinFreq_Value=160000000 -RCC.MDF1Freq_Value=160000000 -RCC.MSI_VALUE=4000000 -RCC.OCTOSPIMFreq_Value=160000000 -RCC.PLL2PoutputFreq_Value=258000000 -RCC.PLL2QoutputFreq_Value=258000000 -RCC.PLL2RoutputFreq_Value=258000000 -RCC.PLL3PoutputFreq_Value=258000000 -RCC.PLL3QoutputFreq_Value=258000000 -RCC.PLL3RoutputFreq_Value=258000000 -RCC.PLLN=80 -RCC.PLLPoutputFreq_Value=160000000 -RCC.PLLQoutputFreq_Value=160000000 -RCC.PLLRCLKFreq_Value=160000000 +RCC.MCO1PinFreq_Value=72000000 +RCC.MDF1Freq_Value=72000000 +RCC.MSIClockRange=RCC_MSIRANGE_0 +RCC.MSI_VALUE=48000000 +RCC.OCTOSPIMFreq_Value=72000000 +RCC.PLL1Q=4 +RCC.PLL2PoutputFreq_Value=3096000000 +RCC.PLL2QoutputFreq_Value=3096000000 +RCC.PLL2RoutputFreq_Value=3096000000 +RCC.PLL3PoutputFreq_Value=3096000000 +RCC.PLL3QoutputFreq_Value=3096000000 +RCC.PLL3RoutputFreq_Value=3096000000 +RCC.PLLFRACN=0 +RCC.PLLM=3 +RCC.PLLN=9 +RCC.PLLPoutputFreq_Value=72000000 +RCC.PLLQoutputFreq_Value=36000000 +RCC.PLLRCLKFreq_Value=72000000 RCC.RNGFreq_Value=48000000 RCC.SAESFreq_Value=48000000 -RCC.SAI1Freq_Value=258000000 -RCC.SAI2Freq_Value=258000000 -RCC.SDMMCFreq_Value=160000000 -RCC.SPI1Freq_Value=160000000 -RCC.SPI2Freq_Value=160000000 -RCC.SPI3Freq_Value=160000000 -RCC.SYSCLKFreq_VALUE=160000000 +RCC.SAI1Freq_Value=3096000000 +RCC.SAI2Freq_Value=3096000000 +RCC.SDMMCFreq_Value=72000000 +RCC.SPI1Freq_Value=72000000 +RCC.SPI2Freq_Value=72000000 +RCC.SPI3Freq_Value=72000000 +RCC.SYSCLKFreq_VALUE=72000000 RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK -RCC.UART4Freq_Value=160000000 -RCC.UART5Freq_Value=160000000 -RCC.USART1Freq_Value=160000000 -RCC.USART2Freq_Value=160000000 -RCC.USART3Freq_Value=160000000 +RCC.UART4Freq_Value=72000000 +RCC.UART5Freq_Value=72000000 +RCC.USART1Freq_Value=72000000 +RCC.USART2Freq_Value=72000000 +RCC.USART3Freq_Value=72000000 RCC.USBFreq_Value=48000000 -RCC.VCOInput2Freq_Value=4000000 -RCC.VCOInput3Freq_Value=4000000 -RCC.VCOInputFreq_Value=4000000 -RCC.VCOOutputFreq_Value=320000000 -RCC.VCOPLL2OutputFreq_Value=516000000 -RCC.VCOPLL3OutputFreq_Value=516000000 +RCC.VCOInput2Freq_Value=48000000 +RCC.VCOInput3Freq_Value=48000000 +RCC.VCOInputFreq_Value=16000000 +RCC.VCOOutputFreq_Value=144000000 +RCC.VCOPLL2OutputFreq_Value=6192000000 +RCC.VCOPLL3OutputFreq_Value=6192000000 SH.S_TIM1_CH1.0=TIM1_CH1,TriggerSource_TI1FP1 SH.S_TIM1_CH1.ConfNb=1 -TIM1.IPParameters=Slave_TriggerFilter,Slave_TriggerPolarity -TIM1.Slave_TriggerFilter=15 -TIM1.Slave_TriggerPolarity=TIM_TRIGGERPOLARITY_FALLING USART1.IPParameters=VirtualMode-Asynchronous USART1.VirtualMode-Asynchronous=VM_ASYNC VP_ICACHE_VS_ICACHE.Mode=DirectMappedCache diff --git a/docs/safety_critical/index_requirements.md b/docs/safety_critical/index_requirements.md deleted file mode 100644 index 7b0446a..0000000 --- a/docs/safety_critical/index_requirements.md +++ /dev/null @@ -1,69 +0,0 @@ -# Requirements - -| Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-001 | SR | Speed Sensor -| SWR-STM32-002 | SWR | Right calculation of RPM ✅ -| RSR-STM32-003 | RSR | RPM invalid arguments ✅ -| RSR-STM32-004 | RSR | Overflow prevention ✅ -| RSR-STM32-005 | RSR | RPM value bounds ✅ -| RSR-STM32-006 | RSR | Hardware invalid arguments x -| RSR-STM32-007 | RSR | Broken timer x -| RSR-STM32-008 | RSR | Timer init validation x -| RSR-STM32-009 | RSR | RPM Debug Output x - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-003 | SR | Emergency Brake - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-004 | SR | Steering/Throttle - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-005 | SR | CAN Communication -| SR-STM32-007 | SWR | Transmit RPM via CAN -| SR-STM32-007 | RSR | Transmit RPM via CAN - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-006 | SR | Deterministic Operation - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-007 | SR | Concurrent Task Execution - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-002 | SR | Battery Status - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-009 | SR | Heartbeat Transmission - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-010 | SR | Watchdog Supervision - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-011 | SR | Debug Output - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-012 | SR | Error Handling - - -|Requirement ID | Type | Title -|---------------|------|------------- -| SR-STM32-013 | SR | Security diff --git a/docs/safety_critical/requirements.md b/docs/safety_critical/requirements.md deleted file mode 100644 index bd08559..0000000 --- a/docs/safety_critical/requirements.md +++ /dev/null @@ -1,135 +0,0 @@ -ID: SR-STM32-001 -Title: Speed Sensor -Type: Functional -Priority: High -Source: System - -Description: -The system shall correctly process wheel speed telemetry from speed sensor. - -Rationale: -Wheel speed telemetry is required for monitoring vehicle behavior and system status with the intentio of display this data into a display. - -Verification: -System Test - -Acceptance Criteria: -Each of this test should pass: - - SWR-STM32-002 - - RSR-STM32-003 - - RSR-STM32-004 - - RSR-STM32-005 - - RSR-STM32-006 - - RSR-STM32-007 - - RSR-STM32-008 - - RSR-STM32-009 - - RSR-STM32-010 - - --- - -ID: SWR-STM32-002 -Title: Right calculation of RPM -Type: Functional -Priority: High -Source: System - -Description: -The software shall calculate wheel speed in RPM based on the number of sensor pulses -measured during a fixed sampling period. - -Rationale: -Mathematical formula to calculate RPM must be verified to proceed to every other test that shares sensor speed. - -Parent Requirement: -SR-STM32-001 - -Related Components: -- Sensor Thread - -Verification: -Unit Test (UT-STM32-001) - -Acceptance Criteria: -- RPM equals (pulses / pulses_per_rev) × (60 / sampling_time). - ---- - -ID: RSR-STM32-003 -Title: RPM invalid arguments -Type: Safety -Priority: Medium -Source: System - -Description: -With invalid argumets, the system must proced with normal procedure. - -Rationale: -Important to understand what would happen if timer values are absurd due to a system error, and how the calculation function will deal with it. - -Parent Requirement: -SR-STM32-001 - -Related Components: -- Sensor Thread -- Timer -- Sensor Speed counter - -Verification: -Unit Test (RSR-STM32-003) - -Acceptance Criteria: -- Return must be equal to 0 - ---- - -ID: RSR-STM32-004 -Title: Overflow prevention -Type: Safety -Priority: Medium -Source: System - -Description: -Shall detect the RPM isn t right, so it must return MAX_RPM (1000) - -Rationale: -If, somehow the RPM is greater than physically the car goes, to protect overflow errors, the return will be clamped to 1000. - -Parent Requirement: -SR-STM32-001 - -Related Components: -- Sensor Thread - -Verification: -Unit Test (RSR-STM32-004) - -Acceptance Criteria: -- Return must be equal to 1000 - ---- - -ID: RSR-STM32-004 -Title: RPM value bounds -Type: Safety -Priority: Low -Source: Stakeholder - -Description: -Shall prevent some undefined error - -Rationale: -Sensor speed component can odly detect huge pulse count in a short time, -if so, probably something went wrong and the program must detect it. - -Parent Requirement: -SR-STM32-001 - -Related Components: -- Sensor Thread -- Speed sensor - -Verification: -Unit Test (RSR-STM32-005) - -Acceptance Criteria: -- Return must be equal to 1000 diff --git a/docs/safety_critical/traceability_matrix.md b/docs/safety_critical/traceability_matrix.md deleted file mode 100644 index 4fe7e59..0000000 --- a/docs/safety_critical/traceability_matrix.md +++ /dev/null @@ -1,16 +0,0 @@ -### System Requirement SR-STM32-001 - -| Requirement ID | Verification | Code Location | Test ID | Title -| -------------- | ------------ | ---------------- | ------------ | ------------ -| SWR-STM32-002 | Pass | speed_rpm.c | UT-STM32-001 | Right calculation of RPM -| RSR-STM32-003 | Pass | speed_rpm.c | UT_STM32_002 | RPM invalid arguments -| RSR-STM32-004 | Pass | speed_rpm.c | UT_STM32_003 | Overflow prevention -| RSR-STM32-005 | Pass | speed_rpm.c | UT_STM32_004 | RPM value bounds -| RSR-STM32-006 | Fail | speedSensor.c | IT_STM32_001 | Hardware invalid arguments -| RSR-STM32-007 | Fail | speedSensor.c | IT_STM32_002 | Broken timer -| RSR-STM32-008 | Fail | speedSensor.c | IT_STM32_003 | Timer init validation -| RSR-STM32-009 | Fail | speedSensor.c | IT_STM32_004 | RPM Debug Output - -| Line Coverage | Function Coverage | -| ------------- | ----------------- | -| 94.12% | 100% | diff --git a/tests/unit/test/test_ut_rpm.c b/tests/unit/test/test_ut_rpm.c index db30801..480aef2 100644 --- a/tests/unit/test/test_ut_rpm.c +++ b/tests/unit/test/test_ut_rpm.c @@ -2,7 +2,7 @@ #include "utils.h" // file being tested -TEST_SOURCE_FILE("speed_rpm.c"); +TEST_SOURCE_FILE("speed_rpm_utils.c"); void setUp(void) { // set stuff up here @@ -26,25 +26,25 @@ void test_right_calculation_of_RPM_UT_STM32_001(void) { TEST_ASSERT_EQUAL_UINT32(1000, state.last_time_ticks); // Second run with valid data (150 pulses in 600 ticks) - // PPR=20, ticks_per_second=1000 - // rpm = 150 * 60 * 1000 / (20 * 600) = 750 + // PPR=40, ticks_per_second=1000 + // rpm = 150 * 60 * 1000 / (40 * 600) = 375 rpm = convertValuesRPM(250, 1600, 65535, &state); - TEST_ASSERT_EQUAL_UINT(750, rpm); + TEST_ASSERT_EQUAL_UINT(375, rpm); // Third run with different data (80 pulses in 400 ticks) - // rpm = 80 * 60 * 1000 / (20 * 400) = 600 + // rpm = 80 * 60 * 1000 / (40 * 400) = 300 rpm = convertValuesRPM(330, 2000, 65535, &state); - TEST_ASSERT_EQUAL_UINT(600, rpm); + TEST_ASSERT_EQUAL_UINT(300, rpm); // Fourth run with higher speed (200 pulses in 200 ticks) - // rpm = 200 * 60 * 1000 / (20 * 200) = 3000 + // rpm = 200 * 60 * 1000 / (40 * 200) = 1500 rpm = convertValuesRPM(530, 2200, 65535, &state); - TEST_ASSERT_EQUAL_UINT(3000, rpm); + TEST_ASSERT_EQUAL_UINT(1500, rpm); // Fifth run with lower speed (30 pulses in 900 ticks) - // rpm = 30 * 60 * 1000 / (20 * 900) = 100 + // rpm = 30 * 60 * 1000 / (40 * 900) = 50 rpm = convertValuesRPM(560, 3100, 65535, &state); - TEST_ASSERT_EQUAL_UINT(100, rpm); + TEST_ASSERT_EQUAL_UINT(50, rpm); } /* RSR-STM32-003 */