├── img
├── stm32f103.webp
└── Screen Shot 2022-04-01 at 10.30.43.png
├── platform
├── chasis
│ ├── rear_v1.stl
│ ├── front_v1.stl
│ ├── rear_base_v1.stl
│ ├── base_chasis_v1.stl
│ ├── front_base_v1.stl
│ ├── side_chasis_v1.stl
│ └── front_rear_chasis_v1.stl
├── Left_front_leg
│ ├── links_v1.stl
│ ├── links_v2.stl
│ ├── left_tibia_v2.stl
│ ├── left_front_coxa_v1.stl
│ ├── left_front_femur_v1.stl
│ └── left_front_femur_v2.stl
├── Left_rear_leg
│ ├── links_v1.stl
│ ├── links_v2.stl
│ ├── left_rear_coxa_v1.stl
│ ├── left_rear_femur_v1.stl
│ ├── left_rear_femur_v2.stl
│ └── left_rear_tibia_v2.stl
├── Right_front_leg
│ ├── links_v1.stl
│ ├── links_v2.stl
│ ├── right_front_coxa_v1.stl
│ ├── right_front_femur_v1.stl
│ ├── right_front_femur_v2.stl
│ └── right_front_tibia_v2.stl
├── Right_rear_leg
│ ├── links_v1.stl
│ ├── links_v2.stl
│ ├── right_rear_coxa_v1.stl
│ ├── right_rear_femur_v1.stl
│ ├── right_rear_femur_v2.stl
│ └── right_rear_tibia_v2.stl
└── electronics.md
├── src
├── Drivers
│ ├── CMSIS
│ │ ├── Device
│ │ │ └── ST
│ │ │ │ └── STM32F1xx
│ │ │ │ └── Include
│ │ │ │ ├── stm32f1xx.h
│ │ │ │ ├── stm32f103xb.h
│ │ │ │ └── system_stm32f1xx.h
│ │ └── Include
│ │ │ ├── cmsis_version.h
│ │ │ ├── tz_context.h
│ │ │ ├── cmsis_compiler.h
│ │ │ ├── mpu_armv8.h
│ │ │ └── mpu_armv7.h
│ └── STM32F1xx_HAL_Driver
│ │ ├── Src
│ │ └── stm32f1xx_hal_gpio_ex.c
│ │ └── Inc
│ │ ├── stm32f1xx_hal_def.h
│ │ ├── stm32f1xx_hal_flash.h
│ │ ├── stm32f1xx_hal_tim_ex.h
│ │ ├── stm32f1xx_hal.h
│ │ └── stm32f1xx_hal_gpio.h
├── .settings
│ ├── stm32cubeide.project.prefs
│ └── language.settings.xml
├── Core
│ ├── Inc
│ │ ├── inverse_kinematics.h
│ │ ├── MPU6050.h
│ │ ├── stm32f1xx_it.h
│ │ ├── main.h
│ │ └── servo_configuration.h
│ ├── Src
│ │ ├── inverse_kinematics.c
│ │ ├── sysmem.c
│ │ ├── syscalls.c
│ │ ├── stm32f1xx_it.c
│ │ ├── MPU6050.c
│ │ └── stm32f1xx_hal_msp.c
│ └── Startup
│ │ └── startup_stm32f103c8tx.s
├── mini-quadruped.cfg
├── .project
├── STM32F103C8TX_FLASH.ld
├── .mxproject
├── mini-quadruped.ioc
├── mini-quadruped Release.launch
└── mini-quadruped.launch
├── mediapipe
└── webcam.py
└── README.md
/img/stm32f103.webp:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/img/stm32f103.webp
--------------------------------------------------------------------------------
/platform/chasis/rear_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/chasis/rear_v1.stl
--------------------------------------------------------------------------------
/platform/chasis/front_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/chasis/front_v1.stl
--------------------------------------------------------------------------------
/platform/chasis/rear_base_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/chasis/rear_base_v1.stl
--------------------------------------------------------------------------------
/platform/chasis/base_chasis_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/chasis/base_chasis_v1.stl
--------------------------------------------------------------------------------
/platform/chasis/front_base_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/chasis/front_base_v1.stl
--------------------------------------------------------------------------------
/platform/chasis/side_chasis_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/chasis/side_chasis_v1.stl
--------------------------------------------------------------------------------
/platform/Left_front_leg/links_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_front_leg/links_v1.stl
--------------------------------------------------------------------------------
/platform/Left_front_leg/links_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_front_leg/links_v2.stl
--------------------------------------------------------------------------------
/platform/Left_rear_leg/links_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_rear_leg/links_v1.stl
--------------------------------------------------------------------------------
/platform/Left_rear_leg/links_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_rear_leg/links_v2.stl
--------------------------------------------------------------------------------
/platform/Right_front_leg/links_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_front_leg/links_v1.stl
--------------------------------------------------------------------------------
/platform/Right_front_leg/links_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_front_leg/links_v2.stl
--------------------------------------------------------------------------------
/platform/Right_rear_leg/links_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_rear_leg/links_v1.stl
--------------------------------------------------------------------------------
/platform/Right_rear_leg/links_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_rear_leg/links_v2.stl
--------------------------------------------------------------------------------
/img/Screen Shot 2022-04-01 at 10.30.43.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/img/Screen Shot 2022-04-01 at 10.30.43.png
--------------------------------------------------------------------------------
/platform/Left_front_leg/left_tibia_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_front_leg/left_tibia_v2.stl
--------------------------------------------------------------------------------
/platform/chasis/front_rear_chasis_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/chasis/front_rear_chasis_v1.stl
--------------------------------------------------------------------------------
/platform/Left_rear_leg/left_rear_coxa_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_rear_leg/left_rear_coxa_v1.stl
--------------------------------------------------------------------------------
/platform/Left_front_leg/left_front_coxa_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_front_leg/left_front_coxa_v1.stl
--------------------------------------------------------------------------------
/platform/Left_front_leg/left_front_femur_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_front_leg/left_front_femur_v1.stl
--------------------------------------------------------------------------------
/platform/Left_front_leg/left_front_femur_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_front_leg/left_front_femur_v2.stl
--------------------------------------------------------------------------------
/platform/Left_rear_leg/left_rear_femur_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_rear_leg/left_rear_femur_v1.stl
--------------------------------------------------------------------------------
/platform/Left_rear_leg/left_rear_femur_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_rear_leg/left_rear_femur_v2.stl
--------------------------------------------------------------------------------
/platform/Left_rear_leg/left_rear_tibia_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Left_rear_leg/left_rear_tibia_v2.stl
--------------------------------------------------------------------------------
/platform/Right_rear_leg/right_rear_coxa_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_rear_leg/right_rear_coxa_v1.stl
--------------------------------------------------------------------------------
/platform/Right_rear_leg/right_rear_femur_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_rear_leg/right_rear_femur_v1.stl
--------------------------------------------------------------------------------
/platform/Right_rear_leg/right_rear_femur_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_rear_leg/right_rear_femur_v2.stl
--------------------------------------------------------------------------------
/platform/Right_rear_leg/right_rear_tibia_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_rear_leg/right_rear_tibia_v2.stl
--------------------------------------------------------------------------------
/platform/Right_front_leg/right_front_coxa_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_front_leg/right_front_coxa_v1.stl
--------------------------------------------------------------------------------
/platform/Right_front_leg/right_front_femur_v1.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_front_leg/right_front_femur_v1.stl
--------------------------------------------------------------------------------
/platform/Right_front_leg/right_front_femur_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_front_leg/right_front_femur_v2.stl
--------------------------------------------------------------------------------
/platform/Right_front_leg/right_front_tibia_v2.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/platform/Right_front_leg/right_front_tibia_v2.stl
--------------------------------------------------------------------------------
/src/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/src/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h
--------------------------------------------------------------------------------
/src/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/nicoRomeroCuruchet/mini-quadruped/HEAD/src/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h
--------------------------------------------------------------------------------
/src/.settings/stm32cubeide.project.prefs:
--------------------------------------------------------------------------------
1 | 66BE74F758C12D739921AEA421D593D3=8
2 | 8DF89ED150041C4CBC7CB9A9CAA90856=9BBDCEC26FA55D1F559EF9BBE33BCE24
3 | DC22A860405A8BF2F2C095E5B6529F12=9BBDCEC26FA55D1F559EF9BBE33BCE24
4 | eclipse.preferences.version=1
5 |
--------------------------------------------------------------------------------
/src/Core/Inc/inverse_kinematics.h:
--------------------------------------------------------------------------------
1 | /*
2 | * inverse_kinematics.h
3 | *
4 | * Created on: Mar 31, 2022
5 | * Author: nicoromero
6 | */
7 |
8 | #ifndef INC_INVERSE_KINEMATICS_H_
9 | #define INC_INVERSE_KINEMATICS_H_
10 |
11 |
12 |
13 | /**
14 | * @brief
15 | * @retval None
16 | */
17 | void inverse_kinematics(float* x, float L_1, float L_2, float L_3, char side, float* res);
18 | void roto_translation(float psi, float phi, float theta, float* T, float* vec, float* res);
19 | void subtract(float* v_1, float* v_2, float* res);
20 |
21 | #endif /* INC_INVERSE_KINEMATICS_H_ */
22 |
--------------------------------------------------------------------------------
/platform/electronics.md:
--------------------------------------------------------------------------------
1 | The electronic components that make up the platform that was investigated in this project are the following:
2 |
3 | - 5A XL4005 DC-DC Adjustable Step Down Module Power Supply Converter x 2
4 | - MPU6050 x 1
5 | - Servo Afrc D2307HC 7.5kg x 12
6 | - STM32F103C8T6 Blue Pill Development Board x 1
7 | - NVIDIA Jetson Nano x 1
8 | - Experimental board (20 mm x 80 mm) x 2
9 |
--------------------------------------------------------------------------------
/src/mini-quadruped.cfg:
--------------------------------------------------------------------------------
1 | # This is an genericBoard board with a single STM32F103C8Tx chip
2 | #
3 | # Generated by STM32CubeIDE
4 | # Take care that such file, as generated, may be overridden without any early notice. Please have a look to debug launch configuration setup(s)
5 |
6 | source [find interface/stlink-dap.cfg]
7 |
8 |
9 | set WORKAREASIZE 0x5000
10 |
11 | transport select "dapdirect_swd"
12 |
13 | set CHIPNAME STM32F103C8Tx
14 | set BOARDNAME genericBoard
15 |
16 | # Enable debug when in low power modes
17 | set ENABLE_LOW_POWER 1
18 |
19 | # Stop Watchdog counters when halt
20 | set STOP_WATCHDOG 1
21 |
22 | # STlink Debug clock frequency
23 | set CLOCK_FREQ 8000
24 |
25 | # Reset configuration
26 | # use hardware reset, connect under reset
27 | # connect_assert_srst needed if low power mode application running (WFI...)
28 | reset_config srst_only srst_nogate connect_assert_srst
29 | set CONNECT_UNDER_RESET 1
30 | set CORE_RESET 0
31 |
32 | # ACCESS PORT NUMBER
33 | set AP_NUM 0
34 | # GDB PORT
35 | set GDB_PORT 3333
36 |
37 |
38 |
39 | # BCTM CPU variables
40 |
41 | source [find target/stm32f1x.cfg]
42 |
43 |
--------------------------------------------------------------------------------
/src/.project:
--------------------------------------------------------------------------------
1 |
2 |
3 | mini-quadruped
4 |
5 |
6 |
7 |
8 |
9 | org.eclipse.cdt.managedbuilder.core.genmakebuilder
10 | clean,full,incremental,
11 |
12 |
13 |
14 |
15 | org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
16 | full,incremental,
17 |
18 |
19 |
20 |
21 |
22 | com.st.stm32cube.ide.mcu.MCUProjectNature
23 | com.st.stm32cube.ide.mcu.MCUCubeProjectNature
24 | org.eclipse.cdt.core.cnature
25 | com.st.stm32cube.ide.mcu.MCUCubeIdeServicesRevAev2ProjectNature
26 | com.st.stm32cube.ide.mcu.MCUAdvancedStructureProjectNature
27 | com.st.stm32cube.ide.mcu.MCUSingleCpuProjectNature
28 | com.st.stm32cube.ide.mcu.MCURootProjectNature
29 | org.eclipse.cdt.managedbuilder.core.managedBuildNature
30 | org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
31 |
32 |
33 |
--------------------------------------------------------------------------------
/src/Core/Inc/MPU6050.h:
--------------------------------------------------------------------------------
1 | #ifndef INC_MPU6050_H_
2 | #define INC_MPU6050_H_
3 |
4 | #include "main.h"
5 | #include "stm32f1xx_hal_i2c.h"
6 | #include
7 |
8 | // MPU6050 structure
9 | typedef struct
10 | {
11 |
12 | int16_t Accel_X_RAW;
13 | int16_t Accel_Y_RAW;
14 | int16_t Accel_Z_RAW;
15 | double Ax;
16 | double Ay;
17 | double Az;
18 |
19 | int16_t Gyro_X_RAW;
20 | int16_t Gyro_Y_RAW;
21 | int16_t Gyro_Z_RAW;
22 | double Gx;
23 | double Gy;
24 | double Gz;
25 |
26 | float Temperature;
27 |
28 | double KalmanAngleX;
29 | double KalmanAngleY;
30 | } MPU6050_t;
31 |
32 | // Kalman structure
33 | typedef struct
34 | {
35 | double Q_angle;
36 | double Q_bias;
37 | double R_measure;
38 | double angle;
39 | double bias;
40 | double P[2][2];
41 | } Kalman_t;
42 |
43 | uint8_t MPU6050_Init(I2C_HandleTypeDef *I2Cx);
44 |
45 | void MPU6050_Read_Accel(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct);
46 |
47 | void MPU6050_Read_Gyro(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct);
48 |
49 | void MPU6050_Read_Temp(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct);
50 |
51 | void MPU6050_Read_All(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct);
52 |
53 | double Kalman_getAngle(Kalman_t *Kalman, double newAngle, double newRate, double dt);
54 |
55 | #endif /* INC_MPU6050_H_ */
56 |
--------------------------------------------------------------------------------
/src/Core/Src/inverse_kinematics.c:
--------------------------------------------------------------------------------
1 | /*
2 | * inverse_kinematics.c
3 | *
4 | * Created on: Mar 31, 2022
5 | * Author: nicoromero
6 | */
7 |
8 | #include
9 | #include
10 |
11 | void inverse_kinematics(float* x,
12 | float L_1,
13 | float L_2,
14 | float L_3,
15 | char side,
16 | float* res)
17 | {
18 |
19 | float s = 1.0;
20 |
21 | if(side == 'l') s = -1.0;
22 |
23 | float x_1 = x[0];
24 | float x_2 = x[1];
25 | float x_3 = x[2];
26 |
27 | float D = (x_1*x_1 + x_2*x_2 + x_3*x_3 - L_1*L_1 - L_2*L_2 - L_3*L_3) / (2*L_2*L_3);
28 |
29 | float delta = sqrt(x_2*x_2 + x_3*x_3 - L_1*L_1);
30 |
31 | if(1 - D*D >=0)
32 | {
33 | res[0] = atan2(x_2, -x_3) + atan2(delta, -s*L_1);
34 | res[2] = atan2(sqrt(1 - D*D), D);
35 | res[1] = atan2(x_1, delta) - atan2(L_3*sin(res[2]), L_2 + L_3*cos(res[2]));
36 | }
37 |
38 | }
39 |
40 | void roto_translation(float psi,
41 | float phi,
42 | float theta,
43 | float* T,
44 | float* vec,
45 | float* res)
46 | {
47 | res[0] = vec[2]*sin(phi) + vec[0]*cos(phi)*cos(psi) - vec[1]*cos(phi)*sin(psi) + T[0];
48 | res[1] = vec[0]*(cos(theta)*sin(psi) + cos(psi)*sin(phi)*sin(theta)) + vec[1]*(cos(psi)*cos(theta) - sin(phi)*sin(psi)*sin(theta)) - vec[2]*cos(phi)*sin(theta) + T[1];
49 | res[2] = vec[0]*(sin(psi)*sin(theta) - cos(psi)*cos(theta)*sin(phi)) + vec[1]*(cos(psi)*sin(theta) + cos(theta)*sin(phi)*sin(psi)) + vec[2]*cos(phi)*cos(theta) + T[2];
50 | }
51 |
52 | void subtract(float* v_1, float* v_2, float* res)
53 | {
54 | res[0] = v_1[0] - v_2[0];
55 | res[1] = v_1[1] - v_2[1];
56 | res[2] = v_1[2] - v_2[2];
57 | }
58 |
--------------------------------------------------------------------------------
/src/Drivers/CMSIS/Include/cmsis_version.h:
--------------------------------------------------------------------------------
1 | /**************************************************************************//**
2 | * @file cmsis_version.h
3 | * @brief CMSIS Core(M) Version definitions
4 | * @version V5.0.2
5 | * @date 19. April 2017
6 | ******************************************************************************/
7 | /*
8 | * Copyright (c) 2009-2017 ARM Limited. All rights reserved.
9 | *
10 | * SPDX-License-Identifier: Apache-2.0
11 | *
12 | * Licensed under the Apache License, Version 2.0 (the License); you may
13 | * not use this file except in compliance with the License.
14 | * You may obtain a copy of the License at
15 | *
16 | * www.apache.org/licenses/LICENSE-2.0
17 | *
18 | * Unless required by applicable law or agreed to in writing, software
19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT
20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
21 | * See the License for the specific language governing permissions and
22 | * limitations under the License.
23 | */
24 |
25 | #if defined ( __ICCARM__ )
26 | #pragma system_include /* treat file as system include file for MISRA check */
27 | #elif defined (__clang__)
28 | #pragma clang system_header /* treat file as system include file */
29 | #endif
30 |
31 | #ifndef __CMSIS_VERSION_H
32 | #define __CMSIS_VERSION_H
33 |
34 | /* CMSIS Version definitions */
35 | #define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */
36 | #define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */
37 | #define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \
38 | __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */
39 | #endif
40 |
--------------------------------------------------------------------------------
/mediapipe/webcam.py:
--------------------------------------------------------------------------------
1 | import cv2
2 | import time
3 | import serial
4 | import mediapipe as mp
5 |
6 | cam = cv2.VideoCapture(0)
7 | mpHands = mp.solutions.hands
8 | hands = mpHands.Hands()
9 | mpDraw = mp.solutions.drawing_utils
10 |
11 | start = 0
12 | end = 0
13 | num_of_bytes = 5
14 |
15 | serial_port = serial.Serial(
16 | port="/dev/ttyUSB0",
17 | baudrate=115200,
18 | bytesize=serial.EIGHTBITS,
19 | parity=serial.PARITY_NONE,
20 | stopbits=serial.STOPBITS_ONE
21 | )
22 |
23 | time.sleep(1)
24 | r = 0
25 | r_x = 0
26 | r_y = 0
27 |
28 | a = True
29 |
30 | while True:
31 | _, img = cam.read()
32 | imgRGB = cv2.cvtColor(img, cv2.COLOR_BGR2RGB)
33 | results = hands.process(imgRGB)
34 |
35 | if results.multi_hand_landmarks:
36 | for handLms in results.multi_hand_landmarks:
37 | for id, lm in enumerate(handLms.landmark):
38 |
39 | h,w,c = img.shape
40 | cx, cy, cz = int(lm.x*w), int(lm.y*h), int(lm.z*h)
41 |
42 | if id == 9:
43 | r_x = -round(0.4*(cx - w/2)/w + 0.6*r_x, 2)
44 | r_y = -round(0.4*(cy - h/2)/h + 0.6*r_y, 2)
45 | data = str(r_x).zfill(num_of_bytes) + str(r_y).zfill(num_of_bytes) + str(int(r)).zfill(num_of_bytes)
46 | serial_port.write(data.encode())
47 |
48 | mpDraw.draw_landmarks(img, handLms, mpHands.HAND_CONNECTIONS)
49 | a=True
50 |
51 | else:
52 | if(a):
53 | data = str('xxx').rjust(15, '0')
54 | serial_port.write(data.encode())
55 |
56 | a = False
57 |
58 | start = time.time()
59 | fps = 1 / (start - end)
60 | end = start
61 | cv2.putText(img,str(int(fps)), (10,70), cv2.FONT_HERSHEY_PLAIN, 3,(0,255,0),3)
62 |
63 | cv2.imshow('Webcam', img)
64 | if cv2.waitKey(1) == ord('q'):
65 | break
66 |
67 | data = str('xxx').rjust(15, '0')
68 | serial_port.write(data.encode())
69 | time.sleep(1)
70 | cam.release()
71 | serial_port.close()
72 | cv2.destroyAllWindows()
73 |
--------------------------------------------------------------------------------
/src/.settings/language.settings.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
--------------------------------------------------------------------------------
/src/Core/Inc/stm32f1xx_it.h:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * @file stm32f1xx_it.h
5 | * @brief This file contains the headers of the interrupt handlers.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2021 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* USER CODE END Header */
20 |
21 | /* Define to prevent recursive inclusion -------------------------------------*/
22 | #ifndef __STM32F1xx_IT_H
23 | #define __STM32F1xx_IT_H
24 |
25 | #ifdef __cplusplus
26 | extern "C" {
27 | #endif
28 |
29 | /* Private includes ----------------------------------------------------------*/
30 | /* USER CODE BEGIN Includes */
31 |
32 | /* USER CODE END Includes */
33 |
34 | /* Exported types ------------------------------------------------------------*/
35 | /* USER CODE BEGIN ET */
36 |
37 | /* USER CODE END ET */
38 |
39 | /* Exported constants --------------------------------------------------------*/
40 | /* USER CODE BEGIN EC */
41 |
42 | /* USER CODE END EC */
43 |
44 | /* Exported macro ------------------------------------------------------------*/
45 | /* USER CODE BEGIN EM */
46 |
47 | /* USER CODE END EM */
48 |
49 | /* Exported functions prototypes ---------------------------------------------*/
50 | void NMI_Handler(void);
51 | void HardFault_Handler(void);
52 | void MemManage_Handler(void);
53 | void BusFault_Handler(void);
54 | void UsageFault_Handler(void);
55 | void SVC_Handler(void);
56 | void DebugMon_Handler(void);
57 | void PendSV_Handler(void);
58 | void SysTick_Handler(void);
59 | void USART2_IRQHandler(void);
60 | /* USER CODE BEGIN EFP */
61 |
62 | /* USER CODE END EFP */
63 |
64 | #ifdef __cplusplus
65 | }
66 | #endif
67 |
68 | #endif /* __STM32F1xx_IT_H */
69 |
70 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
71 |
--------------------------------------------------------------------------------
/src/Drivers/CMSIS/Device/ST/STM32F1xx/Include/system_stm32f1xx.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file system_stm32f10x.h
4 | * @author MCD Application Team
5 | * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2017 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /** @addtogroup CMSIS
21 | * @{
22 | */
23 |
24 | /** @addtogroup stm32f10x_system
25 | * @{
26 | */
27 |
28 | /**
29 | * @brief Define to prevent recursive inclusion
30 | */
31 | #ifndef __SYSTEM_STM32F10X_H
32 | #define __SYSTEM_STM32F10X_H
33 |
34 | #ifdef __cplusplus
35 | extern "C" {
36 | #endif
37 |
38 | /** @addtogroup STM32F10x_System_Includes
39 | * @{
40 | */
41 |
42 | /**
43 | * @}
44 | */
45 |
46 |
47 | /** @addtogroup STM32F10x_System_Exported_types
48 | * @{
49 | */
50 |
51 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
52 | extern const uint8_t AHBPrescTable[16U]; /*!< AHB prescalers table values */
53 | extern const uint8_t APBPrescTable[8U]; /*!< APB prescalers table values */
54 |
55 | /**
56 | * @}
57 | */
58 |
59 | /** @addtogroup STM32F10x_System_Exported_Constants
60 | * @{
61 | */
62 |
63 | /**
64 | * @}
65 | */
66 |
67 | /** @addtogroup STM32F10x_System_Exported_Macros
68 | * @{
69 | */
70 |
71 | /**
72 | * @}
73 | */
74 |
75 | /** @addtogroup STM32F10x_System_Exported_Functions
76 | * @{
77 | */
78 |
79 | extern void SystemInit(void);
80 | extern void SystemCoreClockUpdate(void);
81 | /**
82 | * @}
83 | */
84 |
85 | #ifdef __cplusplus
86 | }
87 | #endif
88 |
89 | #endif /*__SYSTEM_STM32F10X_H */
90 |
91 | /**
92 | * @}
93 | */
94 |
95 | /**
96 | * @}
97 | */
98 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
99 |
--------------------------------------------------------------------------------
/src/Core/Inc/main.h:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * @file : main.h
5 | * @brief : Header for main.c file.
6 | * This file contains the common defines of the application.
7 | ******************************************************************************
8 | * @attention
9 | *
10 | * © Copyright (c) 2021 STMicroelectronics.
11 | * All rights reserved.
12 | *
13 | * This software component is licensed by ST under BSD 3-Clause license,
14 | * the "License"; You may not use this file except in compliance with the
15 | * License. You may obtain a copy of the License at:
16 | * opensource.org/licenses/BSD-3-Clause
17 | *
18 | ******************************************************************************
19 | */
20 | /* USER CODE END Header */
21 |
22 | /* Define to prevent recursive inclusion -------------------------------------*/
23 | #ifndef __MAIN_H
24 | #define __MAIN_H
25 |
26 | #ifdef __cplusplus
27 | extern "C" {
28 | #endif
29 |
30 | /* Includes ------------------------------------------------------------------*/
31 | #include "stm32f1xx_hal.h"
32 |
33 | /* Private includes ----------------------------------------------------------*/
34 | /* USER CODE BEGIN Includes */
35 |
36 | /* USER CODE END Includes */
37 |
38 | /* Exported types ------------------------------------------------------------*/
39 | /* USER CODE BEGIN ET */
40 |
41 | /* USER CODE END ET */
42 |
43 | /* Exported constants --------------------------------------------------------*/
44 | /* USER CODE BEGIN EC */
45 |
46 | /* USER CODE END EC */
47 |
48 | /* Exported macro ------------------------------------------------------------*/
49 | /* USER CODE BEGIN EM */
50 |
51 | /* USER CODE END EM */
52 |
53 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
54 |
55 | /* Exported functions prototypes ---------------------------------------------*/
56 | void Error_Handler(void);
57 |
58 | /* USER CODE BEGIN EFP */
59 |
60 | /* USER CODE END EFP */
61 |
62 | /* Private defines -----------------------------------------------------------*/
63 | /* USER CODE BEGIN Private defines */
64 |
65 | /* USER CODE END Private defines */
66 |
67 | #ifdef __cplusplus
68 | }
69 | #endif
70 |
71 | #endif /* __MAIN_H */
72 |
73 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
74 |
--------------------------------------------------------------------------------
/src/Core/Inc/servo_configuration.h:
--------------------------------------------------------------------------------
1 | /*
2 | * servo_configurations.h
3 | *
4 | * Created on: Mar 30, 2022
5 | * Author: nicoromerocuruchet
6 | */
7 |
8 | #ifndef INC_SERVO_CONFIGURATION_H_
9 | #define INC_SERVO_CONFIGURATION_H_
10 |
11 | /* Left Front Leg */
12 | #define LF_a_servo_i 584.09839082
13 | #define LF_b_servo_i 1465.0
14 |
15 | #define LF_a_servo_ii -627.07020704
16 | #define LF_b_servo_ii 970
17 |
18 | #define LF_a_servo_iii 949.2240125
19 | #define LF_b_servo_iii -25.43047706
20 | // (i):
21 | #define MAX_LF_servo_i 2000
22 | #define MIN_LF_servo_i 1000
23 | #define LF_servo_i TIM1->CCR2
24 | // (ii)
25 | #define MAX_LF_servo_ii 2450
26 | #define MIN_LF_servo_ii 550
27 | #define LF_servo_ii TIM1->CCR1
28 | // (iii)
29 | #define MAX_LF_servo_iii 2100
30 | #define MIN_LF_servo_iii 900
31 | #define LF_servo_iii TIM1->CCR4
32 |
33 | /* Left Rear Leg */
34 | #define LR_a_servo_i -601.60542705
35 | #define LR_b_servo_i 1425.0
36 |
37 | #define LR_a_servo_ii -604.78852455
38 | #define LR_b_servo_ii 1050.0
39 |
40 | #define LR_a_servo_iii 957.22527156
41 | #define LR_b_servo_iii -114.77667663
42 |
43 | // (i):
44 | #define MAX_LR_servo_i 2000
45 | #define MIN_LR_servo_i 1000
46 | #define LR_servo_i TIM3->CCR1
47 | // (ii)
48 | #define MAX_LR_servo_ii 2450
49 | #define MIN_LR_servo_ii 600
50 | #define LR_servo_ii TIM3->CCR3
51 | // (iii)
52 | #define MAX_LR_servo_iii 2100
53 | #define MIN_LR_servo_iii 1100
54 | #define LR_servo_iii TIM3->CCR4
55 |
56 | /* Right Front Leg */
57 | #define RF_a_servo_i 598.42232956
58 | #define RF_b_servo_i 1500.0
59 |
60 | #define RF_a_servo_ii 601.60542705
61 | #define RF_b_servo_ii 1985.0
62 |
63 | #define RF_a_servo_iii -990.64488319
64 | #define RF_b_servo_iii 3088.20381872
65 |
66 | // (i)
67 | #define MAX_RF_servo_i 2000
68 | #define MIN_RF_servo_i 1000
69 | #define RF_servo_i TIM2->CCR4
70 | // (ii)
71 | #define MAX_RF_servo_ii 2370
72 | #define MIN_RF_servo_ii 600
73 | #define RF_servo_ii TIM1->CCR3
74 | //(iii)
75 | #define MAX_RF_servo_iii 2100
76 | #define MIN_RF_servo_iii 900
77 | #define RF_servo_iii TIM2->CCR3
78 |
79 | /* Right Rear Leg */
80 | #define RR_a_servo_i -601.60542705
81 | #define RR_b_servo_i 1473.33333333
82 |
83 | #define RR_a_servo_ii 636.61949953
84 | #define RR_b_servo_ii 2020.0
85 |
86 | #define RR_a_servo_iii -1053.44201921 //
87 | #define RR_b_servo_iii 3297.69769341
88 |
89 | // (i)
90 | #define MAX_RR_servo_i 2000
91 | #define MIN_RR_servo_i 1000
92 | #define RR_servo_i TIM2->CCR1
93 | // (ii)
94 | #define MAX_RR_servo_ii 2400
95 | #define MIN_RR_servo_ii 600
96 | #define RR_servo_ii TIM3->CCR2
97 | //(iii)
98 | #define MAX_RR_servo_iii 2100
99 | #define MIN_RR_servo_iii 900
100 | #define RR_servo_iii TIM2->CCR2
101 |
102 |
103 | #endif /* INC_SERVO_CONFIGURATION_H_ */
104 |
--------------------------------------------------------------------------------
/src/Drivers/CMSIS/Include/tz_context.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | * @file tz_context.h
3 | * @brief Context Management for Armv8-M TrustZone
4 | * @version V1.0.1
5 | * @date 10. January 2018
6 | ******************************************************************************/
7 | /*
8 | * Copyright (c) 2017-2018 Arm Limited. All rights reserved.
9 | *
10 | * SPDX-License-Identifier: Apache-2.0
11 | *
12 | * Licensed under the Apache License, Version 2.0 (the License); you may
13 | * not use this file except in compliance with the License.
14 | * You may obtain a copy of the License at
15 | *
16 | * www.apache.org/licenses/LICENSE-2.0
17 | *
18 | * Unless required by applicable law or agreed to in writing, software
19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT
20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
21 | * See the License for the specific language governing permissions and
22 | * limitations under the License.
23 | */
24 |
25 | #if defined ( __ICCARM__ )
26 | #pragma system_include /* treat file as system include file for MISRA check */
27 | #elif defined (__clang__)
28 | #pragma clang system_header /* treat file as system include file */
29 | #endif
30 |
31 | #ifndef TZ_CONTEXT_H
32 | #define TZ_CONTEXT_H
33 |
34 | #include
35 |
36 | #ifndef TZ_MODULEID_T
37 | #define TZ_MODULEID_T
38 | /// \details Data type that identifies secure software modules called by a process.
39 | typedef uint32_t TZ_ModuleId_t;
40 | #endif
41 |
42 | /// \details TZ Memory ID identifies an allocated memory slot.
43 | typedef uint32_t TZ_MemoryId_t;
44 |
45 | /// Initialize secure context memory system
46 | /// \return execution status (1: success, 0: error)
47 | uint32_t TZ_InitContextSystem_S (void);
48 |
49 | /// Allocate context memory for calling secure software modules in TrustZone
50 | /// \param[in] module identifies software modules called from non-secure mode
51 | /// \return value != 0 id TrustZone memory slot identifier
52 | /// \return value 0 no memory available or internal error
53 | TZ_MemoryId_t TZ_AllocModuleContext_S (TZ_ModuleId_t module);
54 |
55 | /// Free context memory that was previously allocated with \ref TZ_AllocModuleContext_S
56 | /// \param[in] id TrustZone memory slot identifier
57 | /// \return execution status (1: success, 0: error)
58 | uint32_t TZ_FreeModuleContext_S (TZ_MemoryId_t id);
59 |
60 | /// Load secure context (called on RTOS thread context switch)
61 | /// \param[in] id TrustZone memory slot identifier
62 | /// \return execution status (1: success, 0: error)
63 | uint32_t TZ_LoadContext_S (TZ_MemoryId_t id);
64 |
65 | /// Store secure context (called on RTOS thread context switch)
66 | /// \param[in] id TrustZone memory slot identifier
67 | /// \return execution status (1: success, 0: error)
68 | uint32_t TZ_StoreContext_S (TZ_MemoryId_t id);
69 |
70 | #endif // TZ_CONTEXT_H
71 |
--------------------------------------------------------------------------------
/src/Core/Src/sysmem.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file sysmem.c
4 | * @author Generated by STM32CubeIDE
5 | * @brief STM32CubeIDE System Memory calls file
6 | *
7 | * For more information about which C functions
8 | * need which of these lowlevel functions
9 | * please consult the newlib libc manual
10 | ******************************************************************************
11 | * @attention
12 | *
13 | * © Copyright (c) 2020 STMicroelectronics.
14 | * All rights reserved.
15 | *
16 | * This software component is licensed by ST under BSD 3-Clause license,
17 | * the "License"; You may not use this file except in compliance with the
18 | * License. You may obtain a copy of the License at:
19 | * opensource.org/licenses/BSD-3-Clause
20 | *
21 | ******************************************************************************
22 | */
23 |
24 | /* Includes */
25 | #include
26 | #include
27 |
28 | /**
29 | * Pointer to the current high watermark of the heap usage
30 | */
31 | static uint8_t *__sbrk_heap_end = NULL;
32 |
33 | /**
34 | * @brief _sbrk() allocates memory to the newlib heap and is used by malloc
35 | * and others from the C library
36 | *
37 | * @verbatim
38 | * ############################################################################
39 | * # .data # .bss # newlib heap # MSP stack #
40 | * # # # # Reserved by _Min_Stack_Size #
41 | * ############################################################################
42 | * ^-- RAM start ^-- _end _estack, RAM end --^
43 | * @endverbatim
44 | *
45 | * This implementation starts allocating at the '_end' linker symbol
46 | * The '_Min_Stack_Size' linker symbol reserves a memory for the MSP stack
47 | * The implementation considers '_estack' linker symbol to be RAM end
48 | * NOTE: If the MSP stack, at any point during execution, grows larger than the
49 | * reserved size, please increase the '_Min_Stack_Size'.
50 | *
51 | * @param incr Memory size
52 | * @return Pointer to allocated memory
53 | */
54 | void *_sbrk(ptrdiff_t incr)
55 | {
56 | extern uint8_t _end; /* Symbol defined in the linker script */
57 | extern uint8_t _estack; /* Symbol defined in the linker script */
58 | extern uint32_t _Min_Stack_Size; /* Symbol defined in the linker script */
59 | const uint32_t stack_limit = (uint32_t)&_estack - (uint32_t)&_Min_Stack_Size;
60 | const uint8_t *max_heap = (uint8_t *)stack_limit;
61 | uint8_t *prev_heap_end;
62 |
63 | /* Initialize heap end at first call */
64 | if (NULL == __sbrk_heap_end)
65 | {
66 | __sbrk_heap_end = &_end;
67 | }
68 |
69 | /* Protect heap from growing into the reserved MSP stack */
70 | if (__sbrk_heap_end + incr > max_heap)
71 | {
72 | errno = ENOMEM;
73 | return (void *)-1;
74 | }
75 |
76 | prev_heap_end = __sbrk_heap_end;
77 | __sbrk_heap_end += incr;
78 |
79 | return (void *)prev_heap_end;
80 | }
81 |
--------------------------------------------------------------------------------
/src/Core/Src/syscalls.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file syscalls.c
4 | * @author Auto-generated by STM32CubeIDE
5 | * @brief STM32CubeIDE Minimal System calls file
6 | *
7 | * For more information about which c-functions
8 | * need which of these lowlevel functions
9 | * please consult the Newlib libc-manual
10 | ******************************************************************************
11 | * @attention
12 | *
13 | * © Copyright (c) 2020 STMicroelectronics.
14 | * All rights reserved.
15 | *
16 | * This software component is licensed by ST under BSD 3-Clause license,
17 | * the "License"; You may not use this file except in compliance with the
18 | * License. You may obtain a copy of the License at:
19 | * opensource.org/licenses/BSD-3-Clause
20 | *
21 | ******************************************************************************
22 | */
23 |
24 | /* Includes */
25 | #include
26 | #include
27 | #include
28 | #include
29 | #include
30 | #include
31 | #include
32 | #include
33 |
34 |
35 | /* Variables */
36 | extern int __io_putchar(int ch) __attribute__((weak));
37 | extern int __io_getchar(void) __attribute__((weak));
38 |
39 |
40 | char *__env[1] = { 0 };
41 | char **environ = __env;
42 |
43 |
44 | /* Functions */
45 | void initialise_monitor_handles()
46 | {
47 | }
48 |
49 | int _getpid(void)
50 | {
51 | return 1;
52 | }
53 |
54 | int _kill(int pid, int sig)
55 | {
56 | errno = EINVAL;
57 | return -1;
58 | }
59 |
60 | void _exit (int status)
61 | {
62 | _kill(status, -1);
63 | while (1) {} /* Make sure we hang here */
64 | }
65 |
66 | __attribute__((weak)) int _read(int file, char *ptr, int len)
67 | {
68 | int DataIdx;
69 |
70 | for (DataIdx = 0; DataIdx < len; DataIdx++)
71 | {
72 | *ptr++ = __io_getchar();
73 | }
74 |
75 | return len;
76 | }
77 |
78 | __attribute__((weak)) int _write(int file, char *ptr, int len)
79 | {
80 | int DataIdx;
81 |
82 | for (DataIdx = 0; DataIdx < len; DataIdx++)
83 | {
84 | __io_putchar(*ptr++);
85 | }
86 | return len;
87 | }
88 |
89 | int _close(int file)
90 | {
91 | return -1;
92 | }
93 |
94 |
95 | int _fstat(int file, struct stat *st)
96 | {
97 | st->st_mode = S_IFCHR;
98 | return 0;
99 | }
100 |
101 | int _isatty(int file)
102 | {
103 | return 1;
104 | }
105 |
106 | int _lseek(int file, int ptr, int dir)
107 | {
108 | return 0;
109 | }
110 |
111 | int _open(char *path, int flags, ...)
112 | {
113 | /* Pretend like we always fail */
114 | return -1;
115 | }
116 |
117 | int _wait(int *status)
118 | {
119 | errno = ECHILD;
120 | return -1;
121 | }
122 |
123 | int _unlink(char *name)
124 | {
125 | errno = ENOENT;
126 | return -1;
127 | }
128 |
129 | int _times(struct tms *buf)
130 | {
131 | return -1;
132 | }
133 |
134 | int _stat(char *file, struct stat *st)
135 | {
136 | st->st_mode = S_IFCHR;
137 | return 0;
138 | }
139 |
140 | int _link(char *old, char *new)
141 | {
142 | errno = EMLINK;
143 | return -1;
144 | }
145 |
146 | int _fork(void)
147 | {
148 | errno = EAGAIN;
149 | return -1;
150 | }
151 |
152 | int _execve(char *name, char **argv, char **env)
153 | {
154 | errno = ENOMEM;
155 | return -1;
156 | }
157 |
--------------------------------------------------------------------------------
/src/Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio_ex.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f1xx_hal_gpio_ex.c
4 | * @author MCD Application Team
5 | * @brief GPIO Extension HAL module driver.
6 | * This file provides firmware functions to manage the following
7 | * functionalities of the General Purpose Input/Output (GPIO) extension peripheral.
8 | * + Extended features functions
9 | *
10 | @verbatim
11 | ==============================================================================
12 | ##### GPIO Peripheral extension features #####
13 | ==============================================================================
14 | [..] GPIO module on STM32F1 family, manage also the AFIO register:
15 | (+) Possibility to use the EVENTOUT Cortex feature
16 |
17 | ##### How to use this driver #####
18 | ==============================================================================
19 | [..] This driver provides functions to use EVENTOUT Cortex feature
20 | (#) Configure EVENTOUT Cortex feature using the function HAL_GPIOEx_ConfigEventout()
21 | (#) Activate EVENTOUT Cortex feature using the HAL_GPIOEx_EnableEventout()
22 | (#) Deactivate EVENTOUT Cortex feature using the HAL_GPIOEx_DisableEventout()
23 |
24 | @endverbatim
25 | ******************************************************************************
26 | * @attention
27 | *
28 | * © Copyright (c) 2016 STMicroelectronics.
29 | * All rights reserved.
30 | *
31 | * This software component is licensed by ST under BSD 3-Clause license,
32 | * the "License"; You may not use this file except in compliance with the
33 | * License. You may obtain a copy of the License at:
34 | * opensource.org/licenses/BSD-3-Clause
35 | *
36 | ******************************************************************************
37 | */
38 |
39 | /* Includes ------------------------------------------------------------------*/
40 | #include "stm32f1xx_hal.h"
41 |
42 | /** @addtogroup STM32F1xx_HAL_Driver
43 | * @{
44 | */
45 |
46 | /** @defgroup GPIOEx GPIOEx
47 | * @brief GPIO HAL module driver
48 | * @{
49 | */
50 |
51 | #ifdef HAL_GPIO_MODULE_ENABLED
52 |
53 | /** @defgroup GPIOEx_Exported_Functions GPIOEx Exported Functions
54 | * @{
55 | */
56 |
57 | /** @defgroup GPIOEx_Exported_Functions_Group1 Extended features functions
58 | * @brief Extended features functions
59 | *
60 | @verbatim
61 | ==============================================================================
62 | ##### Extended features functions #####
63 | ==============================================================================
64 | [..] This section provides functions allowing to:
65 | (+) Configure EVENTOUT Cortex feature using the function HAL_GPIOEx_ConfigEventout()
66 | (+) Activate EVENTOUT Cortex feature using the HAL_GPIOEx_EnableEventout()
67 | (+) Deactivate EVENTOUT Cortex feature using the HAL_GPIOEx_DisableEventout()
68 |
69 | @endverbatim
70 | * @{
71 | */
72 |
73 | /**
74 | * @brief Configures the port and pin on which the EVENTOUT Cortex signal will be connected.
75 | * @param GPIO_PortSource Select the port used to output the Cortex EVENTOUT signal.
76 | * This parameter can be a value of @ref GPIOEx_EVENTOUT_PORT.
77 | * @param GPIO_PinSource Select the pin used to output the Cortex EVENTOUT signal.
78 | * This parameter can be a value of @ref GPIOEx_EVENTOUT_PIN.
79 | * @retval None
80 | */
81 | void HAL_GPIOEx_ConfigEventout(uint32_t GPIO_PortSource, uint32_t GPIO_PinSource)
82 | {
83 | /* Verify the parameters */
84 | assert_param(IS_AFIO_EVENTOUT_PORT(GPIO_PortSource));
85 | assert_param(IS_AFIO_EVENTOUT_PIN(GPIO_PinSource));
86 |
87 | /* Apply the new configuration */
88 | MODIFY_REG(AFIO->EVCR, (AFIO_EVCR_PORT) | (AFIO_EVCR_PIN), (GPIO_PortSource) | (GPIO_PinSource));
89 | }
90 |
91 | /**
92 | * @brief Enables the Event Output.
93 | * @retval None
94 | */
95 | void HAL_GPIOEx_EnableEventout(void)
96 | {
97 | SET_BIT(AFIO->EVCR, AFIO_EVCR_EVOE);
98 | }
99 |
100 | /**
101 | * @brief Disables the Event Output.
102 | * @retval None
103 | */
104 | void HAL_GPIOEx_DisableEventout(void)
105 | {
106 | CLEAR_BIT(AFIO->EVCR, AFIO_EVCR_EVOE);
107 | }
108 |
109 | /**
110 | * @}
111 | */
112 |
113 | /**
114 | * @}
115 | */
116 |
117 | #endif /* HAL_GPIO_MODULE_ENABLED */
118 |
119 | /**
120 | * @}
121 | */
122 |
123 | /**
124 | * @}
125 | */
126 |
127 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
128 |
--------------------------------------------------------------------------------
/src/STM32F103C8TX_FLASH.ld:
--------------------------------------------------------------------------------
1 | /*
2 | ******************************************************************************
3 | **
4 | ** @file : LinkerScript.ld
5 | **
6 | ** @author : Auto-generated by STM32CubeIDE
7 | **
8 | ** @brief : Linker script for STM32F103C8Tx Device from STM32F1 series
9 | ** 64Kbytes FLASH
10 | ** 20Kbytes RAM
11 | **
12 | ** Set heap size, stack size and stack location according
13 | ** to application requirements.
14 | **
15 | ** Set memory bank area and size if external memory is used
16 | **
17 | ** Target : STMicroelectronics STM32
18 | **
19 | ** Distribution: The file is distributed as is, without any warranty
20 | ** of any kind.
21 | **
22 | ******************************************************************************
23 | ** @attention
24 | **
25 | ** © Copyright (c) 2021 STMicroelectronics.
26 | ** All rights reserved.
27 | **
28 | ** This software component is licensed by ST under BSD 3-Clause license,
29 | ** the "License"; You may not use this file except in compliance with the
30 | ** License. You may obtain a copy of the License at:
31 | ** opensource.org/licenses/BSD-3-Clause
32 | **
33 | ******************************************************************************
34 | */
35 |
36 | /* Entry Point */
37 | ENTRY(Reset_Handler)
38 |
39 | /* Highest address of the user mode stack */
40 | _estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
41 |
42 | _Min_Heap_Size = 0x200 ; /* required amount of heap */
43 | _Min_Stack_Size = 0x400 ; /* required amount of stack */
44 |
45 | /* Memories definition */
46 | MEMORY
47 | {
48 | RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K
49 | FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 64K
50 | }
51 |
52 | /* Sections */
53 | SECTIONS
54 | {
55 | /* The startup code into "FLASH" Rom type memory */
56 | .isr_vector :
57 | {
58 | . = ALIGN(4);
59 | KEEP(*(.isr_vector)) /* Startup code */
60 | . = ALIGN(4);
61 | } >FLASH
62 |
63 | /* The program code and other data into "FLASH" Rom type memory */
64 | .text :
65 | {
66 | . = ALIGN(4);
67 | *(.text) /* .text sections (code) */
68 | *(.text*) /* .text* sections (code) */
69 | *(.glue_7) /* glue arm to thumb code */
70 | *(.glue_7t) /* glue thumb to arm code */
71 | *(.eh_frame)
72 |
73 | KEEP (*(.init))
74 | KEEP (*(.fini))
75 |
76 | . = ALIGN(4);
77 | _etext = .; /* define a global symbols at end of code */
78 | } >FLASH
79 |
80 | /* Constant data into "FLASH" Rom type memory */
81 | .rodata :
82 | {
83 | . = ALIGN(4);
84 | *(.rodata) /* .rodata sections (constants, strings, etc.) */
85 | *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
86 | . = ALIGN(4);
87 | } >FLASH
88 |
89 | .ARM.extab : {
90 | . = ALIGN(4);
91 | *(.ARM.extab* .gnu.linkonce.armextab.*)
92 | . = ALIGN(4);
93 | } >FLASH
94 |
95 | .ARM : {
96 | . = ALIGN(4);
97 | __exidx_start = .;
98 | *(.ARM.exidx*)
99 | __exidx_end = .;
100 | . = ALIGN(4);
101 | } >FLASH
102 |
103 | .preinit_array :
104 | {
105 | . = ALIGN(4);
106 | PROVIDE_HIDDEN (__preinit_array_start = .);
107 | KEEP (*(.preinit_array*))
108 | PROVIDE_HIDDEN (__preinit_array_end = .);
109 | . = ALIGN(4);
110 | } >FLASH
111 |
112 | .init_array :
113 | {
114 | . = ALIGN(4);
115 | PROVIDE_HIDDEN (__init_array_start = .);
116 | KEEP (*(SORT(.init_array.*)))
117 | KEEP (*(.init_array*))
118 | PROVIDE_HIDDEN (__init_array_end = .);
119 | . = ALIGN(4);
120 | } >FLASH
121 |
122 | .fini_array :
123 | {
124 | . = ALIGN(4);
125 | PROVIDE_HIDDEN (__fini_array_start = .);
126 | KEEP (*(SORT(.fini_array.*)))
127 | KEEP (*(.fini_array*))
128 | PROVIDE_HIDDEN (__fini_array_end = .);
129 | . = ALIGN(4);
130 | } >FLASH
131 |
132 | /* Used by the startup to initialize data */
133 | _sidata = LOADADDR(.data);
134 |
135 | /* Initialized data sections into "RAM" Ram type memory */
136 | .data :
137 | {
138 | . = ALIGN(4);
139 | _sdata = .; /* create a global symbol at data start */
140 | *(.data) /* .data sections */
141 | *(.data*) /* .data* sections */
142 | *(.RamFunc) /* .RamFunc sections */
143 | *(.RamFunc*) /* .RamFunc* sections */
144 |
145 | . = ALIGN(4);
146 | _edata = .; /* define a global symbol at data end */
147 |
148 | } >RAM AT> FLASH
149 |
150 | /* Uninitialized data section into "RAM" Ram type memory */
151 | . = ALIGN(4);
152 | .bss :
153 | {
154 | /* This is used by the startup in order to initialize the .bss section */
155 | _sbss = .; /* define a global symbol at bss start */
156 | __bss_start__ = _sbss;
157 | *(.bss)
158 | *(.bss*)
159 | *(COMMON)
160 |
161 | . = ALIGN(4);
162 | _ebss = .; /* define a global symbol at bss end */
163 | __bss_end__ = _ebss;
164 | } >RAM
165 |
166 | /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
167 | ._user_heap_stack :
168 | {
169 | . = ALIGN(8);
170 | PROVIDE ( end = . );
171 | PROVIDE ( _end = . );
172 | . = . + _Min_Heap_Size;
173 | . = . + _Min_Stack_Size;
174 | . = ALIGN(8);
175 | } >RAM
176 |
177 | /* Remove information from the compiler libraries */
178 | /DISCARD/ :
179 | {
180 | libc.a ( * )
181 | libm.a ( * )
182 | libgcc.a ( * )
183 | }
184 |
185 | .ARM.attributes 0 : { *(.ARM.attributes) }
186 | }
187 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Mini-Quadruped
2 |
3 | This open-source project is designed for anyone interested in researching low-cost quadruped robotic platforms. It's built using the **Jetson Nano board** and the MCU **STM32F103C8T6**. By combining the equations for a rigid body rotations with leg inverse kinematics, I've developed an algorithm that accurately positions the multi-joint legs based on the orientation of the torso. With the incorporation of a gyroscope and accelerometer (MPU6050), and by fusing both measures, I'm able to obtain real-time information about the body's orientation. Additionally, I'm using a webcam to collect more data, which enables me to track hand movements.
4 |
5 | **Here's a really funny gif of my new pet following my hand for you all!**
6 |
7 | 
8 |
9 | # Youtube video
10 |
11 | https://youtu.be/wdcIH24sI44
12 |
13 | https://youtu.be/hFUbpantrfs
14 |
15 | # Jetno Nano
16 |
17 | Jetson Nano is a small, powerful, and low-cost computer developed by NVIDIA, designed for building AI applications and projects. It features a quad-core ARM Cortex-A57 CPU, a 128-core NVIDIA Maxwell GPU, and 4GB of LPDDR4 memory. The Jetson Nano also includes a variety of I/O ports, including USB 3.0, HDMI, Gigabit Ethernet, and GPIO, making it easy to interface with various devices and sensors.
18 |
19 | The Jetson Nano runs on a Linux-based operating system and supports a variety of popular machine learning frameworks, including TensorFlow, PyTorch, and MXNet. It can be used for a wide range of AI applications, such as object detection, image classification, natural language processing, and robotics. Its compact size and low power consumption make it ideal for building portable and embedded AI systems.
20 |
21 | A hand tracking solution that can detect and track the position and movement of hands in real-time video was designed using **MediaPipe**, which is an open-source framework developed by Google that provides a variety of pre-built, customizable machine learning models and processing pipelines for tasks such as image and video analysis, facial recognition, hand tracking, and more. MediaPipe also provides a set of C++ and Python libraries for developers to easily incorporate these models and pipelines into their own applications.
22 |
23 |
24 | # STM32F103C8, "the Blue Pill"
25 |
26 | The STM32F103C8 is a popular microcontroller from STMicroelectronics, based on the ARM Cortex-M3 core. It features 64 KB of Flash memory and 20 KB of SRAM, as well as a variety of on-chip peripherals, such as timers, SPI, I2C, USART, and ADC. The STM32F103C8 is commonly used in a wide range of embedded systems, including industrial control systems, motor control applications, and consumer electronics. Its high-performance, low-power consumption, and rich set of features make it a popular choice for developers looking to build complex and efficient systems. The STM32F103C8 is also supported by a variety of development tools and software, including the STM32CubeMX software tool, which allows developers to configure and generate code for the microcontroller.
27 |
28 | 
29 |
30 | # How to deploy the code in the MCU?
31 |
32 | The STM32CubeIDE is an advanced C/C++ development platform with peripheral configuration, code generation, code compilation,
33 | and debug features for STM32 microcontrollers and microprocessors. Is available for free for different operating systems at
34 | the following link:
35 |
36 | https://www.st.com/en/development-tools/stm32cubeide.html
37 |
38 | The **src** directory contains the code that should be executed with the STM32CubeIDE and deployed on the blue pill (STM32F103C8T6).
39 | Run STM32CubeIDE, go to **File -> Import**, pull down the tab **'General'**, select **'Project from Folder or Archive'** and click next.
40 | Finally, **choose the path of src** where you have cloned in your pc.
41 |
42 | In src/Core/Src/ (source file) and src/Core/Inc/ (header file) in this directory there are three files:
43 |
44 | - **main** : contains the main loop of the program that performs quadruped stabilization.
45 | - **inverse_kinematics** : the functions to determine the motion of a quadruped leg to reach a desired position
46 | - **MPU6050** : contains the driver to handle the gyroscope and accelerometer, and combine them. Also implements **Kalman's algorithm** to filtering the measurements observed over time. The author of this library is **Bulanov Konstantin** (@leech001) and you can check out his github repo with this link https://github.com/leech001/MPU6050
47 |
48 | The **src/Core/Inc/servo_configuration.h** contains the setup to control the servos of each leg:
49 |
50 | - **The Left Front Leg was handled via timer 1 channels 1, 2, 4**
51 | - **The Left Rear Leg was handled via timer 3 channels 1, 3, 4**
52 | - **The Right Front Leg was handled via timer 1 and 2. Timer 2 channels 3, 4 and timer 1 channel 3**
53 | - **The Right Rear Leg was handled via timer 2 and 3. Timer 2 channel 1, 2 and timer 3 channel 2**
54 |
55 | and the file in src/mini-quadruped.ioc cotains the setup of the microcontroller it, can be accessed via the STM32CubeIDE:
56 | 
57 |
58 | # Jeton Nano and Blue Pill conection
59 |
60 | Once the information is collected by the webcam and processed using the Mediapipe libraries running on the Jetson Nano, it's sent via USART (using Port A pins 2 and 3) to the Blue Pill. The Blue Pill then computes an algorithm to determine the position of the torso that's needed to center the hand in the image captured by the webcam, based on the hand's location on the screen.
61 |
62 | The code that runs on the Jetson Nano can be found in the **mini-quadruped/mediapipe/webcam.py** file. After downloading the code onto the blue pill and testing the connection between the Jetson Nano and the MCU, execute the following command to start running the libraries that obtain the hand's position:
63 |
64 | python webcam.py
65 |
66 | # MPU6050
67 |
68 | The MPU6050 measures rotational and linear motion, and provides accurate data about the quadruped's orientation and movement. It communicates with the host device using I2C interface and can be easily integrated into a variety of microcontroller-based projects. In this project, I am using I2C1, which is located on the port B pins 6 and 7 of the MCU, and handle with the library probided by **Bulanov Konstantin**.
69 |
--------------------------------------------------------------------------------
/src/.mxproject:
--------------------------------------------------------------------------------
1 | [PreviousLibFiles]
2 | LibFiles=Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_i2c.h;Drivers/STM32F1xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc_ex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_gpio.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_gpio_ex.h;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio_ex.c;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_dma_ex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_dma.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_cortex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_exti.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_tim.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_tim_ex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_i2c.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_dma.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_cortex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_pwr.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_exti.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_tim.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_tim_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_uart.c;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_i2c.h;Drivers/STM32F1xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc_ex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_gpio.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_gpio_ex.h;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio_ex.c;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_dma_ex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_dma.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_cortex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_exti.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_tim.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_tim_ex.h;Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h;Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h;Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h;Drivers/CMSIS/Device/ST/STM32F1xx/Include/system_stm32f1xx.h;Drivers/CMSIS/Device/ST/STM32F1xx/Source/Templates/system_stm32f1xx.c;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/tz_context.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/cmsis_compiler.h;Drivers/CMSIS/Include/cmsis_armclang.h;Drivers/CMSIS/Include/mpu_armv7.h;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/core_cm4.h;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/cmsis_iccarm.h;Drivers/CMSIS/Include/core_armv8mml.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_cm1.h;Drivers/CMSIS/Include/mpu_armv8.h;Drivers/CMSIS/Include/core_sc300.h;Drivers/CMSIS/Include/cmsis_gcc.h;Drivers/CMSIS/Include/cmsis_version.h;Drivers/CMSIS/Include/core_cm23.h;Drivers/CMSIS/Include/core_cm33.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/core_armv8mbl.h;
3 |
4 | [PreviousUsedCubeIDEFiles]
5 | SourceFiles=Core/Src/main.c;Core/Src/stm32f1xx_it.c;Core/Src/stm32f1xx_hal_msp.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_i2c.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_dma.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_cortex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_pwr.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_exti.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_tim.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_tim_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_uart.c;Drivers/CMSIS/Device/ST/STM32F1xx/Source/Templates/system_stm32f1xx.c;Core/Src/system_stm32f1xx.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_i2c.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_dma.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_cortex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_pwr.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_exti.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_tim.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_tim_ex.c;Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_uart.c;Drivers/CMSIS/Device/ST/STM32F1xx/Source/Templates/system_stm32f1xx.c;Core/Src/system_stm32f1xx.c;;;
6 | HeaderPath=Drivers/STM32F1xx_HAL_Driver/Inc;Drivers/STM32F1xx_HAL_Driver/Inc/Legacy;Drivers/CMSIS/Device/ST/STM32F1xx/Include;Drivers/CMSIS/Include;Core/Inc;
7 | CDefines=USE_HAL_DRIVER;STM32F103xB;USE_HAL_DRIVER;USE_HAL_DRIVER;
8 |
9 | [PreviousGenFiles]
10 | AdvancedFolderStructure=true
11 | HeaderFileListSize=3
12 | HeaderFiles#0=/Users/nicoromero/STM32CubeIDE/workspace_1.7.0/blue2/Core/Inc/stm32f1xx_it.h
13 | HeaderFiles#1=/Users/nicoromero/STM32CubeIDE/workspace_1.7.0/blue2/Core/Inc/stm32f1xx_hal_conf.h
14 | HeaderFiles#2=/Users/nicoromero/STM32CubeIDE/workspace_1.7.0/blue2/Core/Inc/main.h
15 | HeaderFolderListSize=1
16 | HeaderPath#0=/Users/nicoromero/STM32CubeIDE/workspace_1.7.0/blue2/Core/Inc
17 | HeaderFiles=;
18 | SourceFileListSize=3
19 | SourceFiles#0=/Users/nicoromero/STM32CubeIDE/workspace_1.7.0/blue2/Core/Src/stm32f1xx_it.c
20 | SourceFiles#1=/Users/nicoromero/STM32CubeIDE/workspace_1.7.0/blue2/Core/Src/stm32f1xx_hal_msp.c
21 | SourceFiles#2=/Users/nicoromero/STM32CubeIDE/workspace_1.7.0/blue2/Core/Src/main.c
22 | SourceFolderListSize=1
23 | SourcePath#0=/Users/nicoromero/STM32CubeIDE/workspace_1.7.0/blue2/Core/Src
24 | SourceFiles=;
25 |
26 |
--------------------------------------------------------------------------------
/src/Core/Src/stm32f1xx_it.c:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * @file stm32f1xx_it.c
5 | * @brief Interrupt Service Routines.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2021 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* USER CODE END Header */
20 |
21 | /* Includes ------------------------------------------------------------------*/
22 | #include "main.h"
23 | #include "stm32f1xx_it.h"
24 | /* Private includes ----------------------------------------------------------*/
25 | /* USER CODE BEGIN Includes */
26 | /* USER CODE END Includes */
27 |
28 | /* Private typedef -----------------------------------------------------------*/
29 | /* USER CODE BEGIN TD */
30 |
31 | /* USER CODE END TD */
32 |
33 | /* Private define ------------------------------------------------------------*/
34 | /* USER CODE BEGIN PD */
35 |
36 | /* USER CODE END PD */
37 |
38 | /* Private macro -------------------------------------------------------------*/
39 | /* USER CODE BEGIN PM */
40 |
41 | /* USER CODE END PM */
42 |
43 | /* Private variables ---------------------------------------------------------*/
44 | /* USER CODE BEGIN PV */
45 |
46 | /* USER CODE END PV */
47 |
48 | /* Private function prototypes -----------------------------------------------*/
49 | /* USER CODE BEGIN PFP */
50 |
51 | /* USER CODE END PFP */
52 |
53 | /* Private user code ---------------------------------------------------------*/
54 | /* USER CODE BEGIN 0 */
55 |
56 | /* USER CODE END 0 */
57 |
58 | /* External variables --------------------------------------------------------*/
59 | extern UART_HandleTypeDef huart2;
60 | /* USER CODE BEGIN EV */
61 |
62 | /* USER CODE END EV */
63 |
64 | /******************************************************************************/
65 | /* Cortex-M3 Processor Interruption and Exception Handlers */
66 | /******************************************************************************/
67 | /**
68 | * @brief This function handles Non maskable interrupt.
69 | */
70 | void NMI_Handler(void)
71 | {
72 | /* USER CODE BEGIN NonMaskableInt_IRQn 0 */
73 |
74 | /* USER CODE END NonMaskableInt_IRQn 0 */
75 | /* USER CODE BEGIN NonMaskableInt_IRQn 1 */
76 | while (1)
77 | {
78 | }
79 | /* USER CODE END NonMaskableInt_IRQn 1 */
80 | }
81 |
82 | /**
83 | * @brief This function handles Hard fault interrupt.
84 | */
85 | void HardFault_Handler(void)
86 | {
87 | /* USER CODE BEGIN HardFault_IRQn 0 */
88 |
89 | /* USER CODE END HardFault_IRQn 0 */
90 | while (1)
91 | {
92 | /* USER CODE BEGIN W1_HardFault_IRQn 0 */
93 | /* USER CODE END W1_HardFault_IRQn 0 */
94 | }
95 | }
96 |
97 | /**
98 | * @brief This function handles Memory management fault.
99 | */
100 | void MemManage_Handler(void)
101 | {
102 | /* USER CODE BEGIN MemoryManagement_IRQn 0 */
103 |
104 | /* USER CODE END MemoryManagement_IRQn 0 */
105 | while (1)
106 | {
107 | /* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
108 | /* USER CODE END W1_MemoryManagement_IRQn 0 */
109 | }
110 | }
111 |
112 | /**
113 | * @brief This function handles Prefetch fault, memory access fault.
114 | */
115 | void BusFault_Handler(void)
116 | {
117 | /* USER CODE BEGIN BusFault_IRQn 0 */
118 |
119 | /* USER CODE END BusFault_IRQn 0 */
120 | while (1)
121 | {
122 | /* USER CODE BEGIN W1_BusFault_IRQn 0 */
123 | /* USER CODE END W1_BusFault_IRQn 0 */
124 | }
125 | }
126 |
127 | /**
128 | * @brief This function handles Undefined instruction or illegal state.
129 | */
130 | void UsageFault_Handler(void)
131 | {
132 | /* USER CODE BEGIN UsageFault_IRQn 0 */
133 |
134 | /* USER CODE END UsageFault_IRQn 0 */
135 | while (1)
136 | {
137 | /* USER CODE BEGIN W1_UsageFault_IRQn 0 */
138 | /* USER CODE END W1_UsageFault_IRQn 0 */
139 | }
140 | }
141 |
142 | /**
143 | * @brief This function handles System service call via SWI instruction.
144 | */
145 | void SVC_Handler(void)
146 | {
147 | /* USER CODE BEGIN SVCall_IRQn 0 */
148 |
149 | /* USER CODE END SVCall_IRQn 0 */
150 | /* USER CODE BEGIN SVCall_IRQn 1 */
151 |
152 | /* USER CODE END SVCall_IRQn 1 */
153 | }
154 |
155 | /**
156 | * @brief This function handles Debug monitor.
157 | */
158 | void DebugMon_Handler(void)
159 | {
160 | /* USER CODE BEGIN DebugMonitor_IRQn 0 */
161 |
162 | /* USER CODE END DebugMonitor_IRQn 0 */
163 | /* USER CODE BEGIN DebugMonitor_IRQn 1 */
164 |
165 | /* USER CODE END DebugMonitor_IRQn 1 */
166 | }
167 |
168 | /**
169 | * @brief This function handles Pendable request for system service.
170 | */
171 | void PendSV_Handler(void)
172 | {
173 | /* USER CODE BEGIN PendSV_IRQn 0 */
174 |
175 | /* USER CODE END PendSV_IRQn 0 */
176 | /* USER CODE BEGIN PendSV_IRQn 1 */
177 |
178 | /* USER CODE END PendSV_IRQn 1 */
179 | }
180 |
181 | /**
182 | * @brief This function handles System tick timer.
183 | */
184 | void SysTick_Handler(void)
185 | {
186 | /* USER CODE BEGIN SysTick_IRQn 0 */
187 |
188 | /* USER CODE END SysTick_IRQn 0 */
189 | HAL_IncTick();
190 | /* USER CODE BEGIN SysTick_IRQn 1 */
191 |
192 | /* USER CODE END SysTick_IRQn 1 */
193 | }
194 |
195 | /******************************************************************************/
196 | /* STM32F1xx Peripheral Interrupt Handlers */
197 | /* Add here the Interrupt Handlers for the used peripherals. */
198 | /* For the available peripheral interrupt handler names, */
199 | /* please refer to the startup file (startup_stm32f1xx.s). */
200 | /******************************************************************************/
201 |
202 | /**
203 | * @brief This function handles USART2 global interrupt.
204 | */
205 | void USART2_IRQHandler(void)
206 | {
207 | /* USER CODE BEGIN USART2_IRQn 0 */
208 |
209 | /* USER CODE END USART2_IRQn 0 */
210 | HAL_UART_IRQHandler(&huart2);
211 | /* USER CODE BEGIN USART2_IRQn 1 */
212 |
213 | /* USER CODE END USART2_IRQn 1 */
214 | }
215 |
216 | /* USER CODE BEGIN 1 */
217 |
218 | /* USER CODE END 1 */
219 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
220 |
--------------------------------------------------------------------------------
/src/mini-quadruped.ioc:
--------------------------------------------------------------------------------
1 | #MicroXplorer Configuration settings - do not modify
2 | File.Version=6
3 | GPIO.groupedBy=Group By Peripherals
4 | I2C1.I2C_Mode=I2C_Fast
5 | I2C1.IPParameters=I2C_Mode
6 | KeepUserPlacement=false
7 | Mcu.Family=STM32F1
8 | Mcu.IP0=I2C1
9 | Mcu.IP1=NVIC
10 | Mcu.IP2=RCC
11 | Mcu.IP3=SYS
12 | Mcu.IP4=TIM1
13 | Mcu.IP5=TIM2
14 | Mcu.IP6=TIM3
15 | Mcu.IP7=USART2
16 | Mcu.IPNb=8
17 | Mcu.Name=STM32F103C(8-B)Tx
18 | Mcu.Package=LQFP48
19 | Mcu.Pin0=PC14-OSC32_IN
20 | Mcu.Pin1=PC15-OSC32_OUT
21 | Mcu.Pin10=PB0
22 | Mcu.Pin11=PB1
23 | Mcu.Pin12=PB10
24 | Mcu.Pin13=PB11
25 | Mcu.Pin14=PA8
26 | Mcu.Pin15=PA9
27 | Mcu.Pin16=PA10
28 | Mcu.Pin17=PA11
29 | Mcu.Pin18=PA13
30 | Mcu.Pin19=PA14
31 | Mcu.Pin2=PD0-OSC_IN
32 | Mcu.Pin20=PB6
33 | Mcu.Pin21=PB7
34 | Mcu.Pin22=VP_SYS_VS_Systick
35 | Mcu.Pin23=VP_TIM1_VS_ClockSourceINT
36 | Mcu.Pin24=VP_TIM2_VS_ClockSourceINT
37 | Mcu.Pin25=VP_TIM3_VS_ClockSourceINT
38 | Mcu.Pin3=PD1-OSC_OUT
39 | Mcu.Pin4=PA0-WKUP
40 | Mcu.Pin5=PA1
41 | Mcu.Pin6=PA2
42 | Mcu.Pin7=PA3
43 | Mcu.Pin8=PA6
44 | Mcu.Pin9=PA7
45 | Mcu.PinsNb=26
46 | Mcu.ThirdPartyNb=0
47 | Mcu.UserConstants=
48 | Mcu.UserName=STM32F103C8Tx
49 | MxCube.Version=6.3.0
50 | MxDb.Version=DB.6.0.30
51 | NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
52 | NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false
53 | NVIC.ForceEnableDMAVector=true
54 | NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
55 | NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false
56 | NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false
57 | NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false
58 | NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
59 | NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false
60 | NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true
61 | NVIC.USART2_IRQn=true\:0\:0\:false\:false\:true\:true\:true
62 | NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false
63 | PA0-WKUP.Signal=S_TIM2_CH1_ETR
64 | PA1.Signal=S_TIM2_CH2
65 | PA10.Signal=S_TIM1_CH3
66 | PA11.Signal=S_TIM1_CH4
67 | PA13.Mode=Serial_Wire
68 | PA13.Signal=SYS_JTMS-SWDIO
69 | PA14.Mode=Serial_Wire
70 | PA14.Signal=SYS_JTCK-SWCLK
71 | PA2.Mode=Asynchronous
72 | PA2.Signal=USART2_TX
73 | PA3.Mode=Asynchronous
74 | PA3.Signal=USART2_RX
75 | PA6.Signal=S_TIM3_CH1
76 | PA7.Signal=S_TIM3_CH2
77 | PA8.Signal=S_TIM1_CH1
78 | PA9.Signal=S_TIM1_CH2
79 | PB0.Signal=S_TIM3_CH3
80 | PB1.Signal=S_TIM3_CH4
81 | PB10.Signal=S_TIM2_CH3
82 | PB11.Signal=S_TIM2_CH4
83 | PB6.Mode=I2C
84 | PB6.Signal=I2C1_SCL
85 | PB7.Mode=I2C
86 | PB7.Signal=I2C1_SDA
87 | PC14-OSC32_IN.Mode=LSE-External-Oscillator
88 | PC14-OSC32_IN.Signal=RCC_OSC32_IN
89 | PC15-OSC32_OUT.Mode=LSE-External-Oscillator
90 | PC15-OSC32_OUT.Signal=RCC_OSC32_OUT
91 | PD0-OSC_IN.Mode=HSE-External-Oscillator
92 | PD0-OSC_IN.Signal=RCC_OSC_IN
93 | PD1-OSC_OUT.Mode=HSE-External-Oscillator
94 | PD1-OSC_OUT.Signal=RCC_OSC_OUT
95 | PinOutPanel.RotationAngle=0
96 | ProjectManager.AskForMigrate=true
97 | ProjectManager.BackupPrevious=false
98 | ProjectManager.CompilerOptimize=6
99 | ProjectManager.ComputerToolchain=false
100 | ProjectManager.CoupleFile=false
101 | ProjectManager.CustomerFirmwarePackage=
102 | ProjectManager.DefaultFWLocation=true
103 | ProjectManager.DeletePrevious=true
104 | ProjectManager.DeviceId=STM32F103C8Tx
105 | ProjectManager.FirmwarePackage=STM32Cube FW_F1 V1.8.4
106 | ProjectManager.FreePins=false
107 | ProjectManager.HalAssertFull=false
108 | ProjectManager.HeapSize=0x200
109 | ProjectManager.KeepUserCode=true
110 | ProjectManager.LastFirmware=true
111 | ProjectManager.LibraryCopy=1
112 | ProjectManager.MainLocation=Core/Src
113 | ProjectManager.NoMain=false
114 | ProjectManager.PreviousToolchain=
115 | ProjectManager.ProjectBuild=false
116 | ProjectManager.ProjectFileName=mini-quadruped.ioc
117 | ProjectManager.ProjectName=mini-quadruped
118 | ProjectManager.RegisterCallBack=
119 | ProjectManager.StackSize=0x400
120 | ProjectManager.TargetToolchain=STM32CubeIDE
121 | ProjectManager.ToolChainLocation=
122 | ProjectManager.UnderRoot=true
123 | ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_TIM1_Init-TIM1-false-HAL-true,4-MX_TIM2_Init-TIM2-false-HAL-true,5-MX_TIM3_Init-TIM3-false-HAL-true,6-MX_I2C1_Init-I2C1-false-HAL-true,7-MX_USART2_UART_Init-USART2-false-HAL-true
124 | RCC.ADCFreqValue=36000000
125 | RCC.AHBFreq_Value=72000000
126 | RCC.APB1CLKDivider=RCC_HCLK_DIV2
127 | RCC.APB1Freq_Value=36000000
128 | RCC.APB1TimFreq_Value=72000000
129 | RCC.APB2Freq_Value=72000000
130 | RCC.APB2TimFreq_Value=72000000
131 | RCC.FCLKCortexFreq_Value=72000000
132 | RCC.FamilyName=M
133 | RCC.HCLKFreq_Value=72000000
134 | RCC.IPParameters=ADCFreqValue,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,MCOFreq_Value,PLLCLKFreq_Value,PLLMCOFreq_Value,PLLMUL,PLLSourceVirtual,SYSCLKFreq_VALUE,SYSCLKSource,TimSysFreq_Value,USBFreq_Value,VCOOutput2Freq_Value
135 | RCC.MCOFreq_Value=72000000
136 | RCC.PLLCLKFreq_Value=72000000
137 | RCC.PLLMCOFreq_Value=36000000
138 | RCC.PLLMUL=RCC_PLL_MUL9
139 | RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
140 | RCC.SYSCLKFreq_VALUE=72000000
141 | RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
142 | RCC.TimSysFreq_Value=72000000
143 | RCC.USBFreq_Value=72000000
144 | RCC.VCOOutput2Freq_Value=8000000
145 | SH.S_TIM1_CH1.0=TIM1_CH1,PWM Generation1 CH1
146 | SH.S_TIM1_CH1.ConfNb=1
147 | SH.S_TIM1_CH2.0=TIM1_CH2,PWM Generation2 CH2
148 | SH.S_TIM1_CH2.ConfNb=1
149 | SH.S_TIM1_CH3.0=TIM1_CH3,PWM Generation3 CH3
150 | SH.S_TIM1_CH3.ConfNb=1
151 | SH.S_TIM1_CH4.0=TIM1_CH4,PWM Generation4 CH4
152 | SH.S_TIM1_CH4.ConfNb=1
153 | SH.S_TIM2_CH1_ETR.0=TIM2_CH1,PWM Generation1 CH1
154 | SH.S_TIM2_CH1_ETR.ConfNb=1
155 | SH.S_TIM2_CH2.0=TIM2_CH2,PWM Generation2 CH2
156 | SH.S_TIM2_CH2.ConfNb=1
157 | SH.S_TIM2_CH3.0=TIM2_CH3,PWM Generation3 CH3
158 | SH.S_TIM2_CH3.ConfNb=1
159 | SH.S_TIM2_CH4.0=TIM2_CH4,PWM Generation4 CH4
160 | SH.S_TIM2_CH4.ConfNb=1
161 | SH.S_TIM3_CH1.0=TIM3_CH1,PWM Generation1 CH1
162 | SH.S_TIM3_CH1.ConfNb=1
163 | SH.S_TIM3_CH2.0=TIM3_CH2,PWM Generation2 CH2
164 | SH.S_TIM3_CH2.ConfNb=1
165 | SH.S_TIM3_CH3.0=TIM3_CH3,PWM Generation3 CH3
166 | SH.S_TIM3_CH3.ConfNb=1
167 | SH.S_TIM3_CH4.0=TIM3_CH4,PWM Generation4 CH4
168 | SH.S_TIM3_CH4.ConfNb=1
169 | TIM1.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_ENABLE
170 | TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
171 | TIM1.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
172 | TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
173 | TIM1.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
174 | TIM1.IPParameters=Channel-PWM Generation1 CH1,Prescaler,Period,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4,AutoReloadPreload
175 | TIM1.Period=9999
176 | TIM1.Prescaler=72
177 | TIM2.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_ENABLE
178 | TIM2.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
179 | TIM2.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
180 | TIM2.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
181 | TIM2.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
182 | TIM2.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4,Prescaler,Period,AutoReloadPreload
183 | TIM2.Period=9999
184 | TIM2.Prescaler=72
185 | TIM3.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_ENABLE
186 | TIM3.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
187 | TIM3.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
188 | TIM3.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
189 | TIM3.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
190 | TIM3.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,Channel-PWM Generation4 CH4,Prescaler,Period,AutoReloadPreload
191 | TIM3.Period=9999
192 | TIM3.Prescaler=72
193 | USART2.IPParameters=VirtualMode
194 | USART2.VirtualMode=VM_ASYNC
195 | VP_SYS_VS_Systick.Mode=SysTick
196 | VP_SYS_VS_Systick.Signal=SYS_VS_Systick
197 | VP_TIM1_VS_ClockSourceINT.Mode=Internal
198 | VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT
199 | VP_TIM2_VS_ClockSourceINT.Mode=Internal
200 | VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT
201 | VP_TIM3_VS_ClockSourceINT.Mode=Internal
202 | VP_TIM3_VS_ClockSourceINT.Signal=TIM3_VS_ClockSourceINT
203 | board=custom
204 | isbadioc=false
205 |
--------------------------------------------------------------------------------
/src/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f1xx_hal_def.h
4 | * @author MCD Application Team
5 | * @brief This file contains HAL common defines, enumeration, macros and
6 | * structures definitions.
7 | ******************************************************************************
8 | * @attention
9 | *
10 | * © Copyright (c) 2017 STMicroelectronics.
11 | * All rights reserved.
12 | *
13 | * This software component is licensed by ST under BSD 3-Clause license,
14 | * the "License"; You may not use this file except in compliance with the
15 | * License. You may obtain a copy of the License at:
16 | * opensource.org/licenses/BSD-3-Clause
17 | *
18 | ******************************************************************************
19 | */
20 |
21 | /* Define to prevent recursive inclusion -------------------------------------*/
22 | #ifndef __STM32F1xx_HAL_DEF
23 | #define __STM32F1xx_HAL_DEF
24 |
25 | #ifdef __cplusplus
26 | extern "C" {
27 | #endif
28 |
29 | /* Includes ------------------------------------------------------------------*/
30 | #include "stm32f1xx.h"
31 | #include "Legacy/stm32_hal_legacy.h"
32 | #include
33 |
34 | /* Exported types ------------------------------------------------------------*/
35 |
36 | /**
37 | * @brief HAL Status structures definition
38 | */
39 | typedef enum
40 | {
41 | HAL_OK = 0x00U,
42 | HAL_ERROR = 0x01U,
43 | HAL_BUSY = 0x02U,
44 | HAL_TIMEOUT = 0x03U
45 | } HAL_StatusTypeDef;
46 |
47 | /**
48 | * @brief HAL Lock structures definition
49 | */
50 | typedef enum
51 | {
52 | HAL_UNLOCKED = 0x00U,
53 | HAL_LOCKED = 0x01U
54 | } HAL_LockTypeDef;
55 |
56 | /* Exported macro ------------------------------------------------------------*/
57 | #define HAL_MAX_DELAY 0xFFFFFFFFU
58 |
59 | #define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != 0U)
60 | #define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U)
61 |
62 | #define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \
63 | do{ \
64 | (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \
65 | (__DMA_HANDLE__).Parent = (__HANDLE__); \
66 | } while(0U)
67 |
68 | #define UNUSED(X) (void)X /* To avoid gcc/g++ warnings */
69 |
70 | /** @brief Reset the Handle's State field.
71 | * @param __HANDLE__ specifies the Peripheral Handle.
72 | * @note This macro can be used for the following purpose:
73 | * - When the Handle is declared as local variable; before passing it as parameter
74 | * to HAL_PPP_Init() for the first time, it is mandatory to use this macro
75 | * to set to 0 the Handle's "State" field.
76 | * Otherwise, "State" field may have any random value and the first time the function
77 | * HAL_PPP_Init() is called, the low level hardware initialization will be missed
78 | * (i.e. HAL_PPP_MspInit() will not be executed).
79 | * - When there is a need to reconfigure the low level hardware: instead of calling
80 | * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init().
81 | * In this later function, when the Handle's "State" field is set to 0, it will execute the function
82 | * HAL_PPP_MspInit() which will reconfigure the low level hardware.
83 | * @retval None
84 | */
85 | #define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U)
86 |
87 | #if (USE_RTOS == 1U)
88 | /* Reserved for future use */
89 | #error "USE_RTOS should be 0 in the current HAL release"
90 | #else
91 | #define __HAL_LOCK(__HANDLE__) \
92 | do{ \
93 | if((__HANDLE__)->Lock == HAL_LOCKED) \
94 | { \
95 | return HAL_BUSY; \
96 | } \
97 | else \
98 | { \
99 | (__HANDLE__)->Lock = HAL_LOCKED; \
100 | } \
101 | }while (0U)
102 |
103 | #define __HAL_UNLOCK(__HANDLE__) \
104 | do{ \
105 | (__HANDLE__)->Lock = HAL_UNLOCKED; \
106 | }while (0U)
107 | #endif /* USE_RTOS */
108 |
109 | #if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */
110 | #ifndef __weak
111 | #define __weak __attribute__((weak))
112 | #endif
113 | #ifndef __packed
114 | #define __packed __attribute__((packed))
115 | #endif
116 | #elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */
117 | #ifndef __weak
118 | #define __weak __attribute__((weak))
119 | #endif /* __weak */
120 | #ifndef __packed
121 | #define __packed __attribute__((__packed__))
122 | #endif /* __packed */
123 | #endif /* __GNUC__ */
124 |
125 |
126 | /* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */
127 | #if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */
128 | #ifndef __ALIGN_BEGIN
129 | #define __ALIGN_BEGIN
130 | #endif
131 | #ifndef __ALIGN_END
132 | #define __ALIGN_END __attribute__ ((aligned (4)))
133 | #endif
134 | #elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */
135 | #ifndef __ALIGN_END
136 | #define __ALIGN_END __attribute__ ((aligned (4)))
137 | #endif /* __ALIGN_END */
138 | #ifndef __ALIGN_BEGIN
139 | #define __ALIGN_BEGIN
140 | #endif /* __ALIGN_BEGIN */
141 | #else
142 | #ifndef __ALIGN_END
143 | #define __ALIGN_END
144 | #endif /* __ALIGN_END */
145 | #ifndef __ALIGN_BEGIN
146 | #if defined (__CC_ARM) /* ARM Compiler V5*/
147 | #define __ALIGN_BEGIN __align(4)
148 | #elif defined (__ICCARM__) /* IAR Compiler */
149 | #define __ALIGN_BEGIN
150 | #endif /* __CC_ARM */
151 | #endif /* __ALIGN_BEGIN */
152 | #endif /* __GNUC__ */
153 |
154 |
155 | /**
156 | * @brief __RAM_FUNC definition
157 | */
158 | #if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050))
159 | /* ARM Compiler V4/V5 and V6
160 | --------------------------
161 | RAM functions are defined using the toolchain options.
162 | Functions that are executed in RAM should reside in a separate source module.
163 | Using the 'Options for File' dialog you can simply change the 'Code / Const'
164 | area of a module to a memory space in physical RAM.
165 | Available memory areas are declared in the 'Target' tab of the 'Options for Target'
166 | dialog.
167 | */
168 | #define __RAM_FUNC
169 |
170 | #elif defined ( __ICCARM__ )
171 | /* ICCARM Compiler
172 | ---------------
173 | RAM functions are defined using a specific toolchain keyword "__ramfunc".
174 | */
175 | #define __RAM_FUNC __ramfunc
176 |
177 | #elif defined ( __GNUC__ )
178 | /* GNU Compiler
179 | ------------
180 | RAM functions are defined using a specific toolchain attribute
181 | "__attribute__((section(".RamFunc")))".
182 | */
183 | #define __RAM_FUNC __attribute__((section(".RamFunc")))
184 |
185 | #endif
186 |
187 | /**
188 | * @brief __NOINLINE definition
189 | */
190 | #if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ )
191 | /* ARM V4/V5 and V6 & GNU Compiler
192 | -------------------------------
193 | */
194 | #define __NOINLINE __attribute__ ( (noinline) )
195 |
196 | #elif defined ( __ICCARM__ )
197 | /* ICCARM Compiler
198 | ---------------
199 | */
200 | #define __NOINLINE _Pragma("optimize = no_inline")
201 |
202 | #endif
203 |
204 | #ifdef __cplusplus
205 | }
206 | #endif
207 |
208 | #endif /* ___STM32F1xx_HAL_DEF */
209 |
210 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
211 |
--------------------------------------------------------------------------------
/src/mini-quadruped Release.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
--------------------------------------------------------------------------------
/src/mini-quadruped.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
--------------------------------------------------------------------------------
/src/Core/Src/MPU6050.c:
--------------------------------------------------------------------------------
1 | /*
2 | * mpu6050.c
3 | *
4 | * Created on: Nov 13, 2019
5 | * Author: Bulanov Konstantin
6 | *
7 | * Contact information
8 | * -------------------
9 | *
10 | * e-mail : leech001@gmail.com
11 | */
12 |
13 | /*
14 | * |---------------------------------------------------------------------------------|
15 | * | Copyright (C) Bulanov Konstantin,2021 |
16 | * | |
17 | * | This program is free software: you can redistribute it and/or modify |
18 | * | it under the terms of the GNU General Public License as published by |
19 | * | the Free Software Foundation, either version 3 of the License, or |
20 | * | any later version. |
21 | * | |
22 | * | This program is distributed in the hope that it will be useful, |
23 | * | but WITHOUT ANY WARRANTY; without even the implied warranty of |
24 | * | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
25 | * | GNU General Public License for more details. |
26 | * | |
27 | * | You should have received a copy of the GNU General Public License |
28 | * | along with this program. If not, see . |
29 | * | |
30 | * | Kalman filter algorithm used from https://github.com/TKJElectronics/KalmanFilter|
31 | * |----------------------------------------------------------------------------------
32 | */
33 |
34 | #include
35 | #include "mpu6050.h"
36 |
37 | #define RAD_TO_DEG 57.295779513082320876798154814105
38 |
39 | #define WHO_AM_I_REG 0x75
40 | #define PWR_MGMT_1_REG 0x6B
41 | #define SMPLRT_DIV_REG 0x19
42 | #define ACCEL_CONFIG_REG 0x1C
43 | #define ACCEL_XOUT_H_REG 0x3B
44 | #define TEMP_OUT_H_REG 0x41
45 | #define GYRO_CONFIG_REG 0x1B
46 | #define GYRO_XOUT_H_REG 0x43
47 |
48 | // Setup MPU6050
49 | #define MPU6050_ADDR 0xD0
50 | const uint16_t i2c_timeout = 100;
51 | const double Accel_Z_corrector = 14418.0;
52 |
53 | uint32_t timer;
54 |
55 | Kalman_t KalmanX = {
56 | .Q_angle = 0.001f,
57 | .Q_bias = 0.003f,
58 | .R_measure = 0.03f};
59 |
60 | Kalman_t KalmanY = {
61 | .Q_angle = 0.001f,
62 | .Q_bias = 0.003f,
63 | .R_measure = 0.03f,
64 | };
65 |
66 | uint8_t MPU6050_Init(I2C_HandleTypeDef *I2Cx)
67 | {
68 | uint8_t check;
69 | uint8_t Data;
70 |
71 | // check device ID WHO_AM_I
72 |
73 | HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, WHO_AM_I_REG, 1, &check, 1, i2c_timeout);
74 |
75 | if (check == 104) // 0x68 will be returned by the sensor if everything goes well
76 | {
77 | // power management register 0X6B we should write all 0's to wake the sensor up
78 | Data = 0;
79 | HAL_I2C_Mem_Write(I2Cx, MPU6050_ADDR, PWR_MGMT_1_REG, 1, &Data, 1, i2c_timeout);
80 |
81 | // Set DATA RATE of 1KHz by writing SMPLRT_DIV register
82 | Data = 0x07;
83 | HAL_I2C_Mem_Write(I2Cx, MPU6050_ADDR, SMPLRT_DIV_REG, 1, &Data, 1, i2c_timeout);
84 |
85 | // Set accelerometer configuration in ACCEL_CONFIG Register
86 | // XA_ST=0,YA_ST=0,ZA_ST=0, FS_SEL=0 -> � 2g
87 | Data = 0x00;
88 | HAL_I2C_Mem_Write(I2Cx, MPU6050_ADDR, ACCEL_CONFIG_REG, 1, &Data, 1, i2c_timeout);
89 |
90 | // Set Gyroscopic configuration in GYRO_CONFIG Register
91 | // XG_ST=0,YG_ST=0,ZG_ST=0, FS_SEL=0 -> � 250 �/s
92 | Data = 0x00;
93 | HAL_I2C_Mem_Write(I2Cx, MPU6050_ADDR, GYRO_CONFIG_REG, 1, &Data, 1, i2c_timeout);
94 | return 0;
95 | }
96 | return 1;
97 | }
98 |
99 | void MPU6050_Read_Accel(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct)
100 | {
101 | uint8_t Rec_Data[6];
102 |
103 | // Read 6 BYTES of data starting from ACCEL_XOUT_H register
104 |
105 | HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, ACCEL_XOUT_H_REG, 1, Rec_Data, 6, i2c_timeout);
106 |
107 | DataStruct->Accel_X_RAW = (int16_t)(Rec_Data[0] << 8 | Rec_Data[1]);
108 | DataStruct->Accel_Y_RAW = (int16_t)(Rec_Data[2] << 8 | Rec_Data[3]);
109 | DataStruct->Accel_Z_RAW = (int16_t)(Rec_Data[4] << 8 | Rec_Data[5]);
110 |
111 | /*** convert the RAW values into acceleration in 'g'
112 | we have to divide according to the Full scale value set in FS_SEL
113 | I have configured FS_SEL = 0. So I am dividing by 16384.0
114 | for more details check ACCEL_CONFIG Register ****/
115 |
116 | DataStruct->Ax = DataStruct->Accel_X_RAW / 16384.0;
117 | DataStruct->Ay = DataStruct->Accel_Y_RAW / 16384.0;
118 | DataStruct->Az = DataStruct->Accel_Z_RAW / Accel_Z_corrector;
119 | }
120 |
121 | void MPU6050_Read_Gyro(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct)
122 | {
123 | uint8_t Rec_Data[6];
124 |
125 | // Read 6 BYTES of data starting from GYRO_XOUT_H register
126 |
127 | HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, GYRO_XOUT_H_REG, 1, Rec_Data, 6, i2c_timeout);
128 |
129 | DataStruct->Gyro_X_RAW = (int16_t)(Rec_Data[0] << 8 | Rec_Data[1]);
130 | DataStruct->Gyro_Y_RAW = (int16_t)(Rec_Data[2] << 8 | Rec_Data[3]);
131 | DataStruct->Gyro_Z_RAW = (int16_t)(Rec_Data[4] << 8 | Rec_Data[5]);
132 |
133 | /*** convert the RAW values into dps (�/s)
134 | we have to divide according to the Full scale value set in FS_SEL
135 | I have configured FS_SEL = 0. So I am dividing by 131.0
136 | for more details check GYRO_CONFIG Register ****/
137 |
138 | DataStruct->Gx = DataStruct->Gyro_X_RAW / 131.0;
139 | DataStruct->Gy = DataStruct->Gyro_Y_RAW / 131.0;
140 | DataStruct->Gz = DataStruct->Gyro_Z_RAW / 131.0;
141 | }
142 |
143 | void MPU6050_Read_Temp(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct)
144 | {
145 | uint8_t Rec_Data[2];
146 | int16_t temp;
147 |
148 | // Read 2 BYTES of data starting from TEMP_OUT_H_REG register
149 |
150 | HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, TEMP_OUT_H_REG, 1, Rec_Data, 2, i2c_timeout);
151 |
152 | temp = (int16_t)(Rec_Data[0] << 8 | Rec_Data[1]);
153 | DataStruct->Temperature = (float)((int16_t)temp / (float)340.0 + (float)36.53);
154 | }
155 |
156 | void MPU6050_Read_All(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct)
157 | {
158 | uint8_t Rec_Data[14];
159 | int16_t temp;
160 |
161 | // Read 14 BYTES of data starting from ACCEL_XOUT_H register
162 |
163 | HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, ACCEL_XOUT_H_REG, 1, Rec_Data, 14, i2c_timeout);
164 |
165 | DataStruct->Accel_X_RAW = (int16_t)(Rec_Data[0] << 8 | Rec_Data[1]);
166 | DataStruct->Accel_Y_RAW = (int16_t)(Rec_Data[2] << 8 | Rec_Data[3]);
167 | DataStruct->Accel_Z_RAW = (int16_t)(Rec_Data[4] << 8 | Rec_Data[5]);
168 | temp = (int16_t)(Rec_Data[6] << 8 | Rec_Data[7]);
169 | DataStruct->Gyro_X_RAW = (int16_t)(Rec_Data[8] << 8 | Rec_Data[9]);
170 | DataStruct->Gyro_Y_RAW = (int16_t)(Rec_Data[10] << 8 | Rec_Data[11]);
171 | DataStruct->Gyro_Z_RAW = (int16_t)(Rec_Data[12] << 8 | Rec_Data[13]);
172 |
173 | DataStruct->Ax = DataStruct->Accel_X_RAW / 16384.0;
174 | DataStruct->Ay = DataStruct->Accel_Y_RAW / 16384.0;
175 | DataStruct->Az = DataStruct->Accel_Z_RAW / Accel_Z_corrector;
176 | DataStruct->Temperature = (float)((int16_t)temp / (float)340.0 + (float)36.53);
177 | DataStruct->Gx = DataStruct->Gyro_X_RAW / 131.0;
178 | DataStruct->Gy = DataStruct->Gyro_Y_RAW / 131.0;
179 | DataStruct->Gz = DataStruct->Gyro_Z_RAW / 131.0;
180 |
181 | // Kalman angle solve
182 | double dt = (double)(HAL_GetTick() - timer) / 1000;
183 | timer = HAL_GetTick();
184 | double roll;
185 | double roll_sqrt = sqrt(
186 | DataStruct->Accel_X_RAW * DataStruct->Accel_X_RAW + DataStruct->Accel_Z_RAW * DataStruct->Accel_Z_RAW);
187 | if (roll_sqrt != 0.0)
188 | {
189 | roll = atan(DataStruct->Accel_Y_RAW / roll_sqrt) * RAD_TO_DEG;
190 | }
191 | else
192 | {
193 | roll = 0.0;
194 | }
195 | double pitch = atan2(-DataStruct->Accel_X_RAW, DataStruct->Accel_Z_RAW) * RAD_TO_DEG;
196 | if ((pitch < -90 && DataStruct->KalmanAngleY > 90) || (pitch > 90 && DataStruct->KalmanAngleY < -90))
197 | {
198 | KalmanY.angle = pitch;
199 | DataStruct->KalmanAngleY = pitch;
200 | }
201 | else
202 | {
203 | DataStruct->KalmanAngleY = Kalman_getAngle(&KalmanY, pitch, DataStruct->Gy, dt);
204 | }
205 | if (fabs(DataStruct->KalmanAngleY) > 90)
206 | DataStruct->Gx = -DataStruct->Gx;
207 | DataStruct->KalmanAngleX = Kalman_getAngle(&KalmanX, roll, DataStruct->Gx, dt);
208 | }
209 |
210 | double Kalman_getAngle(Kalman_t *Kalman, double newAngle, double newRate, double dt)
211 | {
212 | double rate = newRate - Kalman->bias;
213 | Kalman->angle += dt * rate;
214 |
215 | Kalman->P[0][0] += dt * (dt * Kalman->P[1][1] - Kalman->P[0][1] - Kalman->P[1][0] + Kalman->Q_angle);
216 | Kalman->P[0][1] -= dt * Kalman->P[1][1];
217 | Kalman->P[1][0] -= dt * Kalman->P[1][1];
218 | Kalman->P[1][1] += Kalman->Q_bias * dt;
219 |
220 | double S = Kalman->P[0][0] + Kalman->R_measure;
221 | double K[2];
222 | K[0] = Kalman->P[0][0] / S;
223 | K[1] = Kalman->P[1][0] / S;
224 |
225 | double y = newAngle - Kalman->angle;
226 | Kalman->angle += K[0] * y;
227 | Kalman->bias += K[1] * y;
228 |
229 | double P00_temp = Kalman->P[0][0];
230 | double P01_temp = Kalman->P[0][1];
231 |
232 | Kalman->P[0][0] -= K[0] * P00_temp;
233 | Kalman->P[0][1] -= K[0] * P01_temp;
234 | Kalman->P[1][0] -= K[1] * P00_temp;
235 | Kalman->P[1][1] -= K[1] * P01_temp;
236 |
237 | return Kalman->angle;
238 | };
239 |
--------------------------------------------------------------------------------
/src/Drivers/CMSIS/Include/cmsis_compiler.h:
--------------------------------------------------------------------------------
1 | /**************************************************************************//**
2 | * @file cmsis_compiler.h
3 | * @brief CMSIS compiler generic header file
4 | * @version V5.0.4
5 | * @date 10. January 2018
6 | ******************************************************************************/
7 | /*
8 | * Copyright (c) 2009-2018 Arm Limited. All rights reserved.
9 | *
10 | * SPDX-License-Identifier: Apache-2.0
11 | *
12 | * Licensed under the Apache License, Version 2.0 (the License); you may
13 | * not use this file except in compliance with the License.
14 | * You may obtain a copy of the License at
15 | *
16 | * www.apache.org/licenses/LICENSE-2.0
17 | *
18 | * Unless required by applicable law or agreed to in writing, software
19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT
20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
21 | * See the License for the specific language governing permissions and
22 | * limitations under the License.
23 | */
24 |
25 | #ifndef __CMSIS_COMPILER_H
26 | #define __CMSIS_COMPILER_H
27 |
28 | #include
29 |
30 | /*
31 | * Arm Compiler 4/5
32 | */
33 | #if defined ( __CC_ARM )
34 | #include "cmsis_armcc.h"
35 |
36 |
37 | /*
38 | * Arm Compiler 6 (armclang)
39 | */
40 | #elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
41 | #include "cmsis_armclang.h"
42 |
43 |
44 | /*
45 | * GNU Compiler
46 | */
47 | #elif defined ( __GNUC__ )
48 | #include "cmsis_gcc.h"
49 |
50 |
51 | /*
52 | * IAR Compiler
53 | */
54 | #elif defined ( __ICCARM__ )
55 | #include
56 |
57 |
58 | /*
59 | * TI Arm Compiler
60 | */
61 | #elif defined ( __TI_ARM__ )
62 | #include
63 |
64 | #ifndef __ASM
65 | #define __ASM __asm
66 | #endif
67 | #ifndef __INLINE
68 | #define __INLINE inline
69 | #endif
70 | #ifndef __STATIC_INLINE
71 | #define __STATIC_INLINE static inline
72 | #endif
73 | #ifndef __STATIC_FORCEINLINE
74 | #define __STATIC_FORCEINLINE __STATIC_INLINE
75 | #endif
76 | #ifndef __NO_RETURN
77 | #define __NO_RETURN __attribute__((noreturn))
78 | #endif
79 | #ifndef __USED
80 | #define __USED __attribute__((used))
81 | #endif
82 | #ifndef __WEAK
83 | #define __WEAK __attribute__((weak))
84 | #endif
85 | #ifndef __PACKED
86 | #define __PACKED __attribute__((packed))
87 | #endif
88 | #ifndef __PACKED_STRUCT
89 | #define __PACKED_STRUCT struct __attribute__((packed))
90 | #endif
91 | #ifndef __PACKED_UNION
92 | #define __PACKED_UNION union __attribute__((packed))
93 | #endif
94 | #ifndef __UNALIGNED_UINT32 /* deprecated */
95 | struct __attribute__((packed)) T_UINT32 { uint32_t v; };
96 | #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
97 | #endif
98 | #ifndef __UNALIGNED_UINT16_WRITE
99 | __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
100 | #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val))
101 | #endif
102 | #ifndef __UNALIGNED_UINT16_READ
103 | __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
104 | #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
105 | #endif
106 | #ifndef __UNALIGNED_UINT32_WRITE
107 | __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
108 | #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
109 | #endif
110 | #ifndef __UNALIGNED_UINT32_READ
111 | __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
112 | #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
113 | #endif
114 | #ifndef __ALIGNED
115 | #define __ALIGNED(x) __attribute__((aligned(x)))
116 | #endif
117 | #ifndef __RESTRICT
118 | #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
119 | #define __RESTRICT
120 | #endif
121 |
122 |
123 | /*
124 | * TASKING Compiler
125 | */
126 | #elif defined ( __TASKING__ )
127 | /*
128 | * The CMSIS functions have been implemented as intrinsics in the compiler.
129 | * Please use "carm -?i" to get an up to date list of all intrinsics,
130 | * Including the CMSIS ones.
131 | */
132 |
133 | #ifndef __ASM
134 | #define __ASM __asm
135 | #endif
136 | #ifndef __INLINE
137 | #define __INLINE inline
138 | #endif
139 | #ifndef __STATIC_INLINE
140 | #define __STATIC_INLINE static inline
141 | #endif
142 | #ifndef __STATIC_FORCEINLINE
143 | #define __STATIC_FORCEINLINE __STATIC_INLINE
144 | #endif
145 | #ifndef __NO_RETURN
146 | #define __NO_RETURN __attribute__((noreturn))
147 | #endif
148 | #ifndef __USED
149 | #define __USED __attribute__((used))
150 | #endif
151 | #ifndef __WEAK
152 | #define __WEAK __attribute__((weak))
153 | #endif
154 | #ifndef __PACKED
155 | #define __PACKED __packed__
156 | #endif
157 | #ifndef __PACKED_STRUCT
158 | #define __PACKED_STRUCT struct __packed__
159 | #endif
160 | #ifndef __PACKED_UNION
161 | #define __PACKED_UNION union __packed__
162 | #endif
163 | #ifndef __UNALIGNED_UINT32 /* deprecated */
164 | struct __packed__ T_UINT32 { uint32_t v; };
165 | #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
166 | #endif
167 | #ifndef __UNALIGNED_UINT16_WRITE
168 | __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
169 | #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
170 | #endif
171 | #ifndef __UNALIGNED_UINT16_READ
172 | __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
173 | #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
174 | #endif
175 | #ifndef __UNALIGNED_UINT32_WRITE
176 | __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
177 | #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
178 | #endif
179 | #ifndef __UNALIGNED_UINT32_READ
180 | __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
181 | #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
182 | #endif
183 | #ifndef __ALIGNED
184 | #define __ALIGNED(x) __align(x)
185 | #endif
186 | #ifndef __RESTRICT
187 | #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
188 | #define __RESTRICT
189 | #endif
190 |
191 |
192 | /*
193 | * COSMIC Compiler
194 | */
195 | #elif defined ( __CSMC__ )
196 | #include
197 |
198 | #ifndef __ASM
199 | #define __ASM _asm
200 | #endif
201 | #ifndef __INLINE
202 | #define __INLINE inline
203 | #endif
204 | #ifndef __STATIC_INLINE
205 | #define __STATIC_INLINE static inline
206 | #endif
207 | #ifndef __STATIC_FORCEINLINE
208 | #define __STATIC_FORCEINLINE __STATIC_INLINE
209 | #endif
210 | #ifndef __NO_RETURN
211 | // NO RETURN is automatically detected hence no warning here
212 | #define __NO_RETURN
213 | #endif
214 | #ifndef __USED
215 | #warning No compiler specific solution for __USED. __USED is ignored.
216 | #define __USED
217 | #endif
218 | #ifndef __WEAK
219 | #define __WEAK __weak
220 | #endif
221 | #ifndef __PACKED
222 | #define __PACKED @packed
223 | #endif
224 | #ifndef __PACKED_STRUCT
225 | #define __PACKED_STRUCT @packed struct
226 | #endif
227 | #ifndef __PACKED_UNION
228 | #define __PACKED_UNION @packed union
229 | #endif
230 | #ifndef __UNALIGNED_UINT32 /* deprecated */
231 | @packed struct T_UINT32 { uint32_t v; };
232 | #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
233 | #endif
234 | #ifndef __UNALIGNED_UINT16_WRITE
235 | __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
236 | #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
237 | #endif
238 | #ifndef __UNALIGNED_UINT16_READ
239 | __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
240 | #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
241 | #endif
242 | #ifndef __UNALIGNED_UINT32_WRITE
243 | __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
244 | #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
245 | #endif
246 | #ifndef __UNALIGNED_UINT32_READ
247 | __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
248 | #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
249 | #endif
250 | #ifndef __ALIGNED
251 | #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored.
252 | #define __ALIGNED(x)
253 | #endif
254 | #ifndef __RESTRICT
255 | #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
256 | #define __RESTRICT
257 | #endif
258 |
259 |
260 | #else
261 | #error Unknown compiler.
262 | #endif
263 |
264 |
265 | #endif /* __CMSIS_COMPILER_H */
266 |
267 |
--------------------------------------------------------------------------------
/src/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f1xx_hal_flash.h
4 | * @author MCD Application Team
5 | * @brief Header file of Flash HAL module.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2016 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Define to prevent recursive inclusion -------------------------------------*/
21 | #ifndef __STM32F1xx_HAL_FLASH_H
22 | #define __STM32F1xx_HAL_FLASH_H
23 |
24 | #ifdef __cplusplus
25 | extern "C" {
26 | #endif
27 |
28 | /* Includes ------------------------------------------------------------------*/
29 | #include "stm32f1xx_hal_def.h"
30 |
31 | /** @addtogroup STM32F1xx_HAL_Driver
32 | * @{
33 | */
34 |
35 | /** @addtogroup FLASH
36 | * @{
37 | */
38 |
39 | /** @addtogroup FLASH_Private_Constants
40 | * @{
41 | */
42 | #define FLASH_TIMEOUT_VALUE 50000U /* 50 s */
43 | /**
44 | * @}
45 | */
46 |
47 | /** @addtogroup FLASH_Private_Macros
48 | * @{
49 | */
50 |
51 | #define IS_FLASH_TYPEPROGRAM(VALUE) (((VALUE) == FLASH_TYPEPROGRAM_HALFWORD) || \
52 | ((VALUE) == FLASH_TYPEPROGRAM_WORD) || \
53 | ((VALUE) == FLASH_TYPEPROGRAM_DOUBLEWORD))
54 |
55 | #if defined(FLASH_ACR_LATENCY)
56 | #define IS_FLASH_LATENCY(__LATENCY__) (((__LATENCY__) == FLASH_LATENCY_0) || \
57 | ((__LATENCY__) == FLASH_LATENCY_1) || \
58 | ((__LATENCY__) == FLASH_LATENCY_2))
59 |
60 | #else
61 | #define IS_FLASH_LATENCY(__LATENCY__) ((__LATENCY__) == FLASH_LATENCY_0)
62 | #endif /* FLASH_ACR_LATENCY */
63 | /**
64 | * @}
65 | */
66 |
67 | /* Exported types ------------------------------------------------------------*/
68 | /** @defgroup FLASH_Exported_Types FLASH Exported Types
69 | * @{
70 | */
71 |
72 | /**
73 | * @brief FLASH Procedure structure definition
74 | */
75 | typedef enum
76 | {
77 | FLASH_PROC_NONE = 0U,
78 | FLASH_PROC_PAGEERASE = 1U,
79 | FLASH_PROC_MASSERASE = 2U,
80 | FLASH_PROC_PROGRAMHALFWORD = 3U,
81 | FLASH_PROC_PROGRAMWORD = 4U,
82 | FLASH_PROC_PROGRAMDOUBLEWORD = 5U
83 | } FLASH_ProcedureTypeDef;
84 |
85 | /**
86 | * @brief FLASH handle Structure definition
87 | */
88 | typedef struct
89 | {
90 | __IO FLASH_ProcedureTypeDef ProcedureOnGoing; /*!< Internal variable to indicate which procedure is ongoing or not in IT context */
91 |
92 | __IO uint32_t DataRemaining; /*!< Internal variable to save the remaining pages to erase or half-word to program in IT context */
93 |
94 | __IO uint32_t Address; /*!< Internal variable to save address selected for program or erase */
95 |
96 | __IO uint64_t Data; /*!< Internal variable to save data to be programmed */
97 |
98 | HAL_LockTypeDef Lock; /*!< FLASH locking object */
99 |
100 | __IO uint32_t ErrorCode; /*!< FLASH error code
101 | This parameter can be a value of @ref FLASH_Error_Codes */
102 | } FLASH_ProcessTypeDef;
103 |
104 | /**
105 | * @}
106 | */
107 |
108 | /* Exported constants --------------------------------------------------------*/
109 | /** @defgroup FLASH_Exported_Constants FLASH Exported Constants
110 | * @{
111 | */
112 |
113 | /** @defgroup FLASH_Error_Codes FLASH Error Codes
114 | * @{
115 | */
116 |
117 | #define HAL_FLASH_ERROR_NONE 0x00U /*!< No error */
118 | #define HAL_FLASH_ERROR_PROG 0x01U /*!< Programming error */
119 | #define HAL_FLASH_ERROR_WRP 0x02U /*!< Write protection error */
120 | #define HAL_FLASH_ERROR_OPTV 0x04U /*!< Option validity error */
121 |
122 | /**
123 | * @}
124 | */
125 |
126 | /** @defgroup FLASH_Type_Program FLASH Type Program
127 | * @{
128 | */
129 | #define FLASH_TYPEPROGRAM_HALFWORD 0x01U /*!ACR |= FLASH_ACR_HLFCYA)
183 |
184 | /**
185 | * @brief Disable the FLASH half cycle access.
186 | * @note half cycle access can only be used with a low-frequency clock of less than
187 | 8 MHz that can be obtained with the use of HSI or HSE but not of PLL.
188 | * @retval None
189 | */
190 | #define __HAL_FLASH_HALF_CYCLE_ACCESS_DISABLE() (FLASH->ACR &= (~FLASH_ACR_HLFCYA))
191 |
192 | /**
193 | * @}
194 | */
195 |
196 | #if defined(FLASH_ACR_LATENCY)
197 | /** @defgroup FLASH_EM_Latency FLASH Latency
198 | * @brief macros to handle FLASH Latency
199 | * @{
200 | */
201 |
202 | /**
203 | * @brief Set the FLASH Latency.
204 | * @param __LATENCY__ FLASH Latency
205 | * The value of this parameter depend on device used within the same series
206 | * @retval None
207 | */
208 | #define __HAL_FLASH_SET_LATENCY(__LATENCY__) (FLASH->ACR = (FLASH->ACR&(~FLASH_ACR_LATENCY)) | (__LATENCY__))
209 |
210 |
211 | /**
212 | * @brief Get the FLASH Latency.
213 | * @retval FLASH Latency
214 | * The value of this parameter depend on device used within the same series
215 | */
216 | #define __HAL_FLASH_GET_LATENCY() (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY))
217 |
218 | /**
219 | * @}
220 | */
221 |
222 | #endif /* FLASH_ACR_LATENCY */
223 | /** @defgroup FLASH_Prefetch FLASH Prefetch
224 | * @brief macros to handle FLASH Prefetch buffer
225 | * @{
226 | */
227 | /**
228 | * @brief Enable the FLASH prefetch buffer.
229 | * @retval None
230 | */
231 | #define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTBE)
232 |
233 | /**
234 | * @brief Disable the FLASH prefetch buffer.
235 | * @retval None
236 | */
237 | #define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTBE))
238 |
239 | /**
240 | * @}
241 | */
242 |
243 | /**
244 | * @}
245 | */
246 |
247 | /* Include FLASH HAL Extended module */
248 | #include "stm32f1xx_hal_flash_ex.h"
249 |
250 | /* Exported functions --------------------------------------------------------*/
251 | /** @addtogroup FLASH_Exported_Functions
252 | * @{
253 | */
254 |
255 | /** @addtogroup FLASH_Exported_Functions_Group1
256 | * @{
257 | */
258 | /* IO operation functions *****************************************************/
259 | HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data);
260 | HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data);
261 |
262 | /* FLASH IRQ handler function */
263 | void HAL_FLASH_IRQHandler(void);
264 | /* Callbacks in non blocking modes */
265 | void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue);
266 | void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue);
267 |
268 | /**
269 | * @}
270 | */
271 |
272 | /** @addtogroup FLASH_Exported_Functions_Group2
273 | * @{
274 | */
275 | /* Peripheral Control functions ***********************************************/
276 | HAL_StatusTypeDef HAL_FLASH_Unlock(void);
277 | HAL_StatusTypeDef HAL_FLASH_Lock(void);
278 | HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void);
279 | HAL_StatusTypeDef HAL_FLASH_OB_Lock(void);
280 | void HAL_FLASH_OB_Launch(void);
281 |
282 | /**
283 | * @}
284 | */
285 |
286 | /** @addtogroup FLASH_Exported_Functions_Group3
287 | * @{
288 | */
289 | /* Peripheral State and Error functions ***************************************/
290 | uint32_t HAL_FLASH_GetError(void);
291 |
292 | /**
293 | * @}
294 | */
295 |
296 | /**
297 | * @}
298 | */
299 |
300 | /* Private function -------------------------------------------------*/
301 | /** @addtogroup FLASH_Private_Functions
302 | * @{
303 | */
304 | HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout);
305 | #if defined(FLASH_BANK2_END)
306 | HAL_StatusTypeDef FLASH_WaitForLastOperationBank2(uint32_t Timeout);
307 | #endif /* FLASH_BANK2_END */
308 |
309 | /**
310 | * @}
311 | */
312 |
313 | /**
314 | * @}
315 | */
316 |
317 | /**
318 | * @}
319 | */
320 |
321 | #ifdef __cplusplus
322 | }
323 | #endif
324 |
325 | #endif /* __STM32F1xx_HAL_FLASH_H */
326 |
327 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
328 |
329 |
--------------------------------------------------------------------------------
/src/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_tim_ex.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f1xx_hal_tim_ex.h
4 | * @author MCD Application Team
5 | * @brief Header file of TIM HAL Extended module.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2016 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Define to prevent recursive inclusion -------------------------------------*/
21 | #ifndef STM32F1xx_HAL_TIM_EX_H
22 | #define STM32F1xx_HAL_TIM_EX_H
23 |
24 | #ifdef __cplusplus
25 | extern "C" {
26 | #endif
27 |
28 | /* Includes ------------------------------------------------------------------*/
29 | #include "stm32f1xx_hal_def.h"
30 |
31 | /** @addtogroup STM32F1xx_HAL_Driver
32 | * @{
33 | */
34 |
35 | /** @addtogroup TIMEx
36 | * @{
37 | */
38 |
39 | /* Exported types ------------------------------------------------------------*/
40 | /** @defgroup TIMEx_Exported_Types TIM Extended Exported Types
41 | * @{
42 | */
43 |
44 | /**
45 | * @brief TIM Hall sensor Configuration Structure definition
46 | */
47 |
48 | typedef struct
49 | {
50 | uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal.
51 | This parameter can be a value of @ref TIM_Input_Capture_Polarity */
52 |
53 | uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler.
54 | This parameter can be a value of @ref TIM_Input_Capture_Prescaler */
55 |
56 | uint32_t IC1Filter; /*!< Specifies the input capture filter.
57 | This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */
58 |
59 | uint32_t Commutation_Delay; /*!< Specifies the pulse value to be loaded into the Capture Compare Register.
60 | This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */
61 | } TIM_HallSensor_InitTypeDef;
62 | /**
63 | * @}
64 | */
65 | /* End of exported types -----------------------------------------------------*/
66 |
67 | /* Exported constants --------------------------------------------------------*/
68 | /** @defgroup TIMEx_Exported_Constants TIM Extended Exported Constants
69 | * @{
70 | */
71 |
72 | /** @defgroup TIMEx_Remap TIM Extended Remapping
73 | * @{
74 | */
75 | /**
76 | * @}
77 | */
78 |
79 | /**
80 | * @}
81 | */
82 | /* End of exported constants -------------------------------------------------*/
83 |
84 | /* Exported macro ------------------------------------------------------------*/
85 | /** @defgroup TIMEx_Exported_Macros TIM Extended Exported Macros
86 | * @{
87 | */
88 |
89 | /**
90 | * @}
91 | */
92 | /* End of exported macro -----------------------------------------------------*/
93 |
94 | /* Private macro -------------------------------------------------------------*/
95 | /** @defgroup TIMEx_Private_Macros TIM Extended Private Macros
96 | * @{
97 | */
98 |
99 | /**
100 | * @}
101 | */
102 | /* End of private macro ------------------------------------------------------*/
103 |
104 | /* Exported functions --------------------------------------------------------*/
105 | /** @addtogroup TIMEx_Exported_Functions TIM Extended Exported Functions
106 | * @{
107 | */
108 |
109 | /** @addtogroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions
110 | * @brief Timer Hall Sensor functions
111 | * @{
112 | */
113 | /* Timer Hall Sensor functions **********************************************/
114 | HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig);
115 | HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim);
116 |
117 | void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim);
118 | void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim);
119 |
120 | /* Blocking mode: Polling */
121 | HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim);
122 | HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim);
123 | /* Non-Blocking mode: Interrupt */
124 | HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim);
125 | HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim);
126 | /* Non-Blocking mode: DMA */
127 | HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length);
128 | HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim);
129 | /**
130 | * @}
131 | */
132 |
133 | /** @addtogroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions
134 | * @brief Timer Complementary Output Compare functions
135 | * @{
136 | */
137 | /* Timer Complementary Output Compare functions *****************************/
138 | /* Blocking mode: Polling */
139 | HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel);
140 | HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel);
141 |
142 | /* Non-Blocking mode: Interrupt */
143 | HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
144 | HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
145 |
146 | /* Non-Blocking mode: DMA */
147 | HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length);
148 | HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel);
149 | /**
150 | * @}
151 | */
152 |
153 | /** @addtogroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions
154 | * @brief Timer Complementary PWM functions
155 | * @{
156 | */
157 | /* Timer Complementary PWM functions ****************************************/
158 | /* Blocking mode: Polling */
159 | HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel);
160 | HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel);
161 |
162 | /* Non-Blocking mode: Interrupt */
163 | HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
164 | HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel);
165 | /* Non-Blocking mode: DMA */
166 | HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length);
167 | HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel);
168 | /**
169 | * @}
170 | */
171 |
172 | /** @addtogroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions
173 | * @brief Timer Complementary One Pulse functions
174 | * @{
175 | */
176 | /* Timer Complementary One Pulse functions **********************************/
177 | /* Blocking mode: Polling */
178 | HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
179 | HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
180 |
181 | /* Non-Blocking mode: Interrupt */
182 | HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
183 | HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel);
184 | /**
185 | * @}
186 | */
187 |
188 | /** @addtogroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions
189 | * @brief Peripheral Control functions
190 | * @{
191 | */
192 | /* Extended Control functions ************************************************/
193 | HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
194 | uint32_t CommutationSource);
195 | HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
196 | uint32_t CommutationSource);
197 | HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger,
198 | uint32_t CommutationSource);
199 | HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim,
200 | TIM_MasterConfigTypeDef *sMasterConfig);
201 | HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim,
202 | TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig);
203 | HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap);
204 | /**
205 | * @}
206 | */
207 |
208 | /** @addtogroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions
209 | * @brief Extended Callbacks functions
210 | * @{
211 | */
212 | /* Extended Callback **********************************************************/
213 | void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim);
214 | void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim);
215 | void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim);
216 | /**
217 | * @}
218 | */
219 |
220 | /** @addtogroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions
221 | * @brief Extended Peripheral State functions
222 | * @{
223 | */
224 | /* Extended Peripheral State functions ***************************************/
225 | HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim);
226 | HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN);
227 | /**
228 | * @}
229 | */
230 |
231 | /**
232 | * @}
233 | */
234 | /* End of exported functions -------------------------------------------------*/
235 |
236 | /* Private functions----------------------------------------------------------*/
237 | /** @addtogroup TIMEx_Private_Functions TIMEx Private Functions
238 | * @{
239 | */
240 | void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma);
241 | void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma);
242 | /**
243 | * @}
244 | */
245 | /* End of private functions --------------------------------------------------*/
246 |
247 | /**
248 | * @}
249 | */
250 |
251 | /**
252 | * @}
253 | */
254 |
255 | #ifdef __cplusplus
256 | }
257 | #endif
258 |
259 |
260 | #endif /* STM32F1xx_HAL_TIM_EX_H */
261 |
262 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
263 |
--------------------------------------------------------------------------------
/src/Core/Startup/startup_stm32f103c8tx.s:
--------------------------------------------------------------------------------
1 | /**
2 | *************** (C) COPYRIGHT 2017 STMicroelectronics ************************
3 | * @file startup_stm32f103xb.s
4 | * @author MCD Application Team
5 | * @brief STM32F103xB Devices vector table for Atollic toolchain.
6 | * This module performs:
7 | * - Set the initial SP
8 | * - Set the initial PC == Reset_Handler,
9 | * - Set the vector table entries with the exceptions ISR address
10 | * - Configure the clock system
11 | * - Branches to main in the C library (which eventually
12 | * calls main()).
13 | * After Reset the Cortex-M3 processor is in Thread mode,
14 | * priority is Privileged, and the Stack is set to Main.
15 | ******************************************************************************
16 | * @attention
17 | *
18 | * © Copyright (c) 2017 STMicroelectronics.
19 | * All rights reserved.
20 | *
21 | * This software component is licensed by ST under BSD 3-Clause license,
22 | * the "License"; You may not use this file except in compliance with the
23 | * License. You may obtain a copy of the License at:
24 | * opensource.org/licenses/BSD-3-Clause
25 | *
26 | ******************************************************************************
27 | */
28 |
29 | .syntax unified
30 | .cpu cortex-m3
31 | .fpu softvfp
32 | .thumb
33 |
34 | .global g_pfnVectors
35 | .global Default_Handler
36 |
37 | /* start address for the initialization values of the .data section.
38 | defined in linker script */
39 | .word _sidata
40 | /* start address for the .data section. defined in linker script */
41 | .word _sdata
42 | /* end address for the .data section. defined in linker script */
43 | .word _edata
44 | /* start address for the .bss section. defined in linker script */
45 | .word _sbss
46 | /* end address for the .bss section. defined in linker script */
47 | .word _ebss
48 |
49 | .equ BootRAM, 0xF108F85F
50 | /**
51 | * @brief This is the code that gets called when the processor first
52 | * starts execution following a reset event. Only the absolutely
53 | * necessary set is performed, after which the application
54 | * supplied main() routine is called.
55 | * @param None
56 | * @retval : None
57 | */
58 |
59 | .section .text.Reset_Handler
60 | .weak Reset_Handler
61 | .type Reset_Handler, %function
62 | Reset_Handler:
63 |
64 | /* Copy the data segment initializers from flash to SRAM */
65 | ldr r0, =_sdata
66 | ldr r1, =_edata
67 | ldr r2, =_sidata
68 | movs r3, #0
69 | b LoopCopyDataInit
70 |
71 | CopyDataInit:
72 | ldr r4, [r2, r3]
73 | str r4, [r0, r3]
74 | adds r3, r3, #4
75 |
76 | LoopCopyDataInit:
77 | adds r4, r0, r3
78 | cmp r4, r1
79 | bcc CopyDataInit
80 |
81 | /* Zero fill the bss segment. */
82 | ldr r2, =_sbss
83 | ldr r4, =_ebss
84 | movs r3, #0
85 | b LoopFillZerobss
86 |
87 | FillZerobss:
88 | str r3, [r2]
89 | adds r2, r2, #4
90 |
91 | LoopFillZerobss:
92 | cmp r2, r4
93 | bcc FillZerobss
94 |
95 | /* Call the clock system intitialization function.*/
96 | bl SystemInit
97 | /* Call static constructors */
98 | bl __libc_init_array
99 | /* Call the application's entry point.*/
100 | bl main
101 | bx lr
102 | .size Reset_Handler, .-Reset_Handler
103 |
104 | /**
105 | * @brief This is the code that gets called when the processor receives an
106 | * unexpected interrupt. This simply enters an infinite loop, preserving
107 | * the system state for examination by a debugger.
108 | *
109 | * @param None
110 | * @retval : None
111 | */
112 | .section .text.Default_Handler,"ax",%progbits
113 | Default_Handler:
114 | Infinite_Loop:
115 | b Infinite_Loop
116 | .size Default_Handler, .-Default_Handler
117 | /******************************************************************************
118 | *
119 | * The minimal vector table for a Cortex M3. Note that the proper constructs
120 | * must be placed on this to ensure that it ends up at physical address
121 | * 0x0000.0000.
122 | *
123 | ******************************************************************************/
124 | .section .isr_vector,"a",%progbits
125 | .type g_pfnVectors, %object
126 | .size g_pfnVectors, .-g_pfnVectors
127 |
128 |
129 | g_pfnVectors:
130 |
131 | .word _estack
132 | .word Reset_Handler
133 | .word NMI_Handler
134 | .word HardFault_Handler
135 | .word MemManage_Handler
136 | .word BusFault_Handler
137 | .word UsageFault_Handler
138 | .word 0
139 | .word 0
140 | .word 0
141 | .word 0
142 | .word SVC_Handler
143 | .word DebugMon_Handler
144 | .word 0
145 | .word PendSV_Handler
146 | .word SysTick_Handler
147 | .word WWDG_IRQHandler
148 | .word PVD_IRQHandler
149 | .word TAMPER_IRQHandler
150 | .word RTC_IRQHandler
151 | .word FLASH_IRQHandler
152 | .word RCC_IRQHandler
153 | .word EXTI0_IRQHandler
154 | .word EXTI1_IRQHandler
155 | .word EXTI2_IRQHandler
156 | .word EXTI3_IRQHandler
157 | .word EXTI4_IRQHandler
158 | .word DMA1_Channel1_IRQHandler
159 | .word DMA1_Channel2_IRQHandler
160 | .word DMA1_Channel3_IRQHandler
161 | .word DMA1_Channel4_IRQHandler
162 | .word DMA1_Channel5_IRQHandler
163 | .word DMA1_Channel6_IRQHandler
164 | .word DMA1_Channel7_IRQHandler
165 | .word ADC1_2_IRQHandler
166 | .word USB_HP_CAN1_TX_IRQHandler
167 | .word USB_LP_CAN1_RX0_IRQHandler
168 | .word CAN1_RX1_IRQHandler
169 | .word CAN1_SCE_IRQHandler
170 | .word EXTI9_5_IRQHandler
171 | .word TIM1_BRK_IRQHandler
172 | .word TIM1_UP_IRQHandler
173 | .word TIM1_TRG_COM_IRQHandler
174 | .word TIM1_CC_IRQHandler
175 | .word TIM2_IRQHandler
176 | .word TIM3_IRQHandler
177 | .word TIM4_IRQHandler
178 | .word I2C1_EV_IRQHandler
179 | .word I2C1_ER_IRQHandler
180 | .word I2C2_EV_IRQHandler
181 | .word I2C2_ER_IRQHandler
182 | .word SPI1_IRQHandler
183 | .word SPI2_IRQHandler
184 | .word USART1_IRQHandler
185 | .word USART2_IRQHandler
186 | .word USART3_IRQHandler
187 | .word EXTI15_10_IRQHandler
188 | .word RTC_Alarm_IRQHandler
189 | .word USBWakeUp_IRQHandler
190 | .word 0
191 | .word 0
192 | .word 0
193 | .word 0
194 | .word 0
195 | .word 0
196 | .word 0
197 | .word BootRAM /* @0x108. This is for boot in RAM mode for
198 | STM32F10x Medium Density devices. */
199 |
200 | /*******************************************************************************
201 | *
202 | * Provide weak aliases for each Exception handler to the Default_Handler.
203 | * As they are weak aliases, any function with the same name will override
204 | * this definition.
205 | *
206 | *******************************************************************************/
207 |
208 | .weak NMI_Handler
209 | .thumb_set NMI_Handler,Default_Handler
210 |
211 | .weak HardFault_Handler
212 | .thumb_set HardFault_Handler,Default_Handler
213 |
214 | .weak MemManage_Handler
215 | .thumb_set MemManage_Handler,Default_Handler
216 |
217 | .weak BusFault_Handler
218 | .thumb_set BusFault_Handler,Default_Handler
219 |
220 | .weak UsageFault_Handler
221 | .thumb_set UsageFault_Handler,Default_Handler
222 |
223 | .weak SVC_Handler
224 | .thumb_set SVC_Handler,Default_Handler
225 |
226 | .weak DebugMon_Handler
227 | .thumb_set DebugMon_Handler,Default_Handler
228 |
229 | .weak PendSV_Handler
230 | .thumb_set PendSV_Handler,Default_Handler
231 |
232 | .weak SysTick_Handler
233 | .thumb_set SysTick_Handler,Default_Handler
234 |
235 | .weak WWDG_IRQHandler
236 | .thumb_set WWDG_IRQHandler,Default_Handler
237 |
238 | .weak PVD_IRQHandler
239 | .thumb_set PVD_IRQHandler,Default_Handler
240 |
241 | .weak TAMPER_IRQHandler
242 | .thumb_set TAMPER_IRQHandler,Default_Handler
243 |
244 | .weak RTC_IRQHandler
245 | .thumb_set RTC_IRQHandler,Default_Handler
246 |
247 | .weak FLASH_IRQHandler
248 | .thumb_set FLASH_IRQHandler,Default_Handler
249 |
250 | .weak RCC_IRQHandler
251 | .thumb_set RCC_IRQHandler,Default_Handler
252 |
253 | .weak EXTI0_IRQHandler
254 | .thumb_set EXTI0_IRQHandler,Default_Handler
255 |
256 | .weak EXTI1_IRQHandler
257 | .thumb_set EXTI1_IRQHandler,Default_Handler
258 |
259 | .weak EXTI2_IRQHandler
260 | .thumb_set EXTI2_IRQHandler,Default_Handler
261 |
262 | .weak EXTI3_IRQHandler
263 | .thumb_set EXTI3_IRQHandler,Default_Handler
264 |
265 | .weak EXTI4_IRQHandler
266 | .thumb_set EXTI4_IRQHandler,Default_Handler
267 |
268 | .weak DMA1_Channel1_IRQHandler
269 | .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
270 |
271 | .weak DMA1_Channel2_IRQHandler
272 | .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
273 |
274 | .weak DMA1_Channel3_IRQHandler
275 | .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
276 |
277 | .weak DMA1_Channel4_IRQHandler
278 | .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
279 |
280 | .weak DMA1_Channel5_IRQHandler
281 | .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
282 |
283 | .weak DMA1_Channel6_IRQHandler
284 | .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
285 |
286 | .weak DMA1_Channel7_IRQHandler
287 | .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
288 |
289 | .weak ADC1_2_IRQHandler
290 | .thumb_set ADC1_2_IRQHandler,Default_Handler
291 |
292 | .weak USB_HP_CAN1_TX_IRQHandler
293 | .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
294 |
295 | .weak USB_LP_CAN1_RX0_IRQHandler
296 | .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
297 |
298 | .weak CAN1_RX1_IRQHandler
299 | .thumb_set CAN1_RX1_IRQHandler,Default_Handler
300 |
301 | .weak CAN1_SCE_IRQHandler
302 | .thumb_set CAN1_SCE_IRQHandler,Default_Handler
303 |
304 | .weak EXTI9_5_IRQHandler
305 | .thumb_set EXTI9_5_IRQHandler,Default_Handler
306 |
307 | .weak TIM1_BRK_IRQHandler
308 | .thumb_set TIM1_BRK_IRQHandler,Default_Handler
309 |
310 | .weak TIM1_UP_IRQHandler
311 | .thumb_set TIM1_UP_IRQHandler,Default_Handler
312 |
313 | .weak TIM1_TRG_COM_IRQHandler
314 | .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
315 |
316 | .weak TIM1_CC_IRQHandler
317 | .thumb_set TIM1_CC_IRQHandler,Default_Handler
318 |
319 | .weak TIM2_IRQHandler
320 | .thumb_set TIM2_IRQHandler,Default_Handler
321 |
322 | .weak TIM3_IRQHandler
323 | .thumb_set TIM3_IRQHandler,Default_Handler
324 |
325 | .weak TIM4_IRQHandler
326 | .thumb_set TIM4_IRQHandler,Default_Handler
327 |
328 | .weak I2C1_EV_IRQHandler
329 | .thumb_set I2C1_EV_IRQHandler,Default_Handler
330 |
331 | .weak I2C1_ER_IRQHandler
332 | .thumb_set I2C1_ER_IRQHandler,Default_Handler
333 |
334 | .weak I2C2_EV_IRQHandler
335 | .thumb_set I2C2_EV_IRQHandler,Default_Handler
336 |
337 | .weak I2C2_ER_IRQHandler
338 | .thumb_set I2C2_ER_IRQHandler,Default_Handler
339 |
340 | .weak SPI1_IRQHandler
341 | .thumb_set SPI1_IRQHandler,Default_Handler
342 |
343 | .weak SPI2_IRQHandler
344 | .thumb_set SPI2_IRQHandler,Default_Handler
345 |
346 | .weak USART1_IRQHandler
347 | .thumb_set USART1_IRQHandler,Default_Handler
348 |
349 | .weak USART2_IRQHandler
350 | .thumb_set USART2_IRQHandler,Default_Handler
351 |
352 | .weak USART3_IRQHandler
353 | .thumb_set USART3_IRQHandler,Default_Handler
354 |
355 | .weak EXTI15_10_IRQHandler
356 | .thumb_set EXTI15_10_IRQHandler,Default_Handler
357 |
358 | .weak RTC_Alarm_IRQHandler
359 | .thumb_set RTC_Alarm_IRQHandler,Default_Handler
360 |
361 | .weak USBWakeUp_IRQHandler
362 | .thumb_set USBWakeUp_IRQHandler,Default_Handler
363 |
364 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
365 |
366 |
--------------------------------------------------------------------------------
/src/Drivers/CMSIS/Include/mpu_armv8.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | * @file mpu_armv8.h
3 | * @brief CMSIS MPU API for Armv8-M MPU
4 | * @version V5.0.4
5 | * @date 10. January 2018
6 | ******************************************************************************/
7 | /*
8 | * Copyright (c) 2017-2018 Arm Limited. All rights reserved.
9 | *
10 | * SPDX-License-Identifier: Apache-2.0
11 | *
12 | * Licensed under the Apache License, Version 2.0 (the License); you may
13 | * not use this file except in compliance with the License.
14 | * You may obtain a copy of the License at
15 | *
16 | * www.apache.org/licenses/LICENSE-2.0
17 | *
18 | * Unless required by applicable law or agreed to in writing, software
19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT
20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
21 | * See the License for the specific language governing permissions and
22 | * limitations under the License.
23 | */
24 |
25 | #if defined ( __ICCARM__ )
26 | #pragma system_include /* treat file as system include file for MISRA check */
27 | #elif defined (__clang__)
28 | #pragma clang system_header /* treat file as system include file */
29 | #endif
30 |
31 | #ifndef ARM_MPU_ARMV8_H
32 | #define ARM_MPU_ARMV8_H
33 |
34 | /** \brief Attribute for device memory (outer only) */
35 | #define ARM_MPU_ATTR_DEVICE ( 0U )
36 |
37 | /** \brief Attribute for non-cacheable, normal memory */
38 | #define ARM_MPU_ATTR_NON_CACHEABLE ( 4U )
39 |
40 | /** \brief Attribute for normal memory (outer and inner)
41 | * \param NT Non-Transient: Set to 1 for non-transient data.
42 | * \param WB Write-Back: Set to 1 to use write-back update policy.
43 | * \param RA Read Allocation: Set to 1 to use cache allocation on read miss.
44 | * \param WA Write Allocation: Set to 1 to use cache allocation on write miss.
45 | */
46 | #define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \
47 | (((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U))
48 |
49 | /** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */
50 | #define ARM_MPU_ATTR_DEVICE_nGnRnE (0U)
51 |
52 | /** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */
53 | #define ARM_MPU_ATTR_DEVICE_nGnRE (1U)
54 |
55 | /** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */
56 | #define ARM_MPU_ATTR_DEVICE_nGRE (2U)
57 |
58 | /** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */
59 | #define ARM_MPU_ATTR_DEVICE_GRE (3U)
60 |
61 | /** \brief Memory Attribute
62 | * \param O Outer memory attributes
63 | * \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes
64 | */
65 | #define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U)))
66 |
67 | /** \brief Normal memory non-shareable */
68 | #define ARM_MPU_SH_NON (0U)
69 |
70 | /** \brief Normal memory outer shareable */
71 | #define ARM_MPU_SH_OUTER (2U)
72 |
73 | /** \brief Normal memory inner shareable */
74 | #define ARM_MPU_SH_INNER (3U)
75 |
76 | /** \brief Memory access permissions
77 | * \param RO Read-Only: Set to 1 for read-only memory.
78 | * \param NP Non-Privileged: Set to 1 for non-privileged memory.
79 | */
80 | #define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U))
81 |
82 | /** \brief Region Base Address Register value
83 | * \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned.
84 | * \param SH Defines the Shareability domain for this memory region.
85 | * \param RO Read-Only: Set to 1 for a read-only memory region.
86 | * \param NP Non-Privileged: Set to 1 for a non-privileged memory region.
87 | * \oaram XN eXecute Never: Set to 1 for a non-executable memory region.
88 | */
89 | #define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \
90 | ((BASE & MPU_RBAR_BASE_Msk) | \
91 | ((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \
92 | ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \
93 | ((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk))
94 |
95 | /** \brief Region Limit Address Register value
96 | * \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended.
97 | * \param IDX The attribute index to be associated with this memory region.
98 | */
99 | #define ARM_MPU_RLAR(LIMIT, IDX) \
100 | ((LIMIT & MPU_RLAR_LIMIT_Msk) | \
101 | ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \
102 | (MPU_RLAR_EN_Msk))
103 |
104 | /**
105 | * Struct for a single MPU Region
106 | */
107 | typedef struct {
108 | uint32_t RBAR; /*!< Region Base Address Register value */
109 | uint32_t RLAR; /*!< Region Limit Address Register value */
110 | } ARM_MPU_Region_t;
111 |
112 | /** Enable the MPU.
113 | * \param MPU_Control Default access permissions for unconfigured regions.
114 | */
115 | __STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control)
116 | {
117 | __DSB();
118 | __ISB();
119 | MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
120 | #ifdef SCB_SHCSR_MEMFAULTENA_Msk
121 | SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
122 | #endif
123 | }
124 |
125 | /** Disable the MPU.
126 | */
127 | __STATIC_INLINE void ARM_MPU_Disable(void)
128 | {
129 | __DSB();
130 | __ISB();
131 | #ifdef SCB_SHCSR_MEMFAULTENA_Msk
132 | SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
133 | #endif
134 | MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk;
135 | }
136 |
137 | #ifdef MPU_NS
138 | /** Enable the Non-secure MPU.
139 | * \param MPU_Control Default access permissions for unconfigured regions.
140 | */
141 | __STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control)
142 | {
143 | __DSB();
144 | __ISB();
145 | MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
146 | #ifdef SCB_SHCSR_MEMFAULTENA_Msk
147 | SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
148 | #endif
149 | }
150 |
151 | /** Disable the Non-secure MPU.
152 | */
153 | __STATIC_INLINE void ARM_MPU_Disable_NS(void)
154 | {
155 | __DSB();
156 | __ISB();
157 | #ifdef SCB_SHCSR_MEMFAULTENA_Msk
158 | SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
159 | #endif
160 | MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk;
161 | }
162 | #endif
163 |
164 | /** Set the memory attribute encoding to the given MPU.
165 | * \param mpu Pointer to the MPU to be configured.
166 | * \param idx The attribute index to be set [0-7]
167 | * \param attr The attribute value to be set.
168 | */
169 | __STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr)
170 | {
171 | const uint8_t reg = idx / 4U;
172 | const uint32_t pos = ((idx % 4U) * 8U);
173 | const uint32_t mask = 0xFFU << pos;
174 |
175 | if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) {
176 | return; // invalid index
177 | }
178 |
179 | mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask));
180 | }
181 |
182 | /** Set the memory attribute encoding.
183 | * \param idx The attribute index to be set [0-7]
184 | * \param attr The attribute value to be set.
185 | */
186 | __STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr)
187 | {
188 | ARM_MPU_SetMemAttrEx(MPU, idx, attr);
189 | }
190 |
191 | #ifdef MPU_NS
192 | /** Set the memory attribute encoding to the Non-secure MPU.
193 | * \param idx The attribute index to be set [0-7]
194 | * \param attr The attribute value to be set.
195 | */
196 | __STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr)
197 | {
198 | ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr);
199 | }
200 | #endif
201 |
202 | /** Clear and disable the given MPU region of the given MPU.
203 | * \param mpu Pointer to MPU to be used.
204 | * \param rnr Region number to be cleared.
205 | */
206 | __STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr)
207 | {
208 | mpu->RNR = rnr;
209 | mpu->RLAR = 0U;
210 | }
211 |
212 | /** Clear and disable the given MPU region.
213 | * \param rnr Region number to be cleared.
214 | */
215 | __STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr)
216 | {
217 | ARM_MPU_ClrRegionEx(MPU, rnr);
218 | }
219 |
220 | #ifdef MPU_NS
221 | /** Clear and disable the given Non-secure MPU region.
222 | * \param rnr Region number to be cleared.
223 | */
224 | __STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr)
225 | {
226 | ARM_MPU_ClrRegionEx(MPU_NS, rnr);
227 | }
228 | #endif
229 |
230 | /** Configure the given MPU region of the given MPU.
231 | * \param mpu Pointer to MPU to be used.
232 | * \param rnr Region number to be configured.
233 | * \param rbar Value for RBAR register.
234 | * \param rlar Value for RLAR register.
235 | */
236 | __STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar)
237 | {
238 | mpu->RNR = rnr;
239 | mpu->RBAR = rbar;
240 | mpu->RLAR = rlar;
241 | }
242 |
243 | /** Configure the given MPU region.
244 | * \param rnr Region number to be configured.
245 | * \param rbar Value for RBAR register.
246 | * \param rlar Value for RLAR register.
247 | */
248 | __STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar)
249 | {
250 | ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar);
251 | }
252 |
253 | #ifdef MPU_NS
254 | /** Configure the given Non-secure MPU region.
255 | * \param rnr Region number to be configured.
256 | * \param rbar Value for RBAR register.
257 | * \param rlar Value for RLAR register.
258 | */
259 | __STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar)
260 | {
261 | ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar);
262 | }
263 | #endif
264 |
265 | /** Memcopy with strictly ordered memory access, e.g. for register targets.
266 | * \param dst Destination data is copied to.
267 | * \param src Source data is copied from.
268 | * \param len Amount of data words to be copied.
269 | */
270 | __STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len)
271 | {
272 | uint32_t i;
273 | for (i = 0U; i < len; ++i)
274 | {
275 | dst[i] = src[i];
276 | }
277 | }
278 |
279 | /** Load the given number of MPU regions from a table to the given MPU.
280 | * \param mpu Pointer to the MPU registers to be used.
281 | * \param rnr First region number to be configured.
282 | * \param table Pointer to the MPU configuration table.
283 | * \param cnt Amount of regions to be configured.
284 | */
285 | __STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
286 | {
287 | const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U;
288 | if (cnt == 1U) {
289 | mpu->RNR = rnr;
290 | orderedCpy(&(mpu->RBAR), &(table->RBAR), rowWordSize);
291 | } else {
292 | uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U);
293 | uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES;
294 |
295 | mpu->RNR = rnrBase;
296 | while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) {
297 | uint32_t c = MPU_TYPE_RALIASES - rnrOffset;
298 | orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize);
299 | table += c;
300 | cnt -= c;
301 | rnrOffset = 0U;
302 | rnrBase += MPU_TYPE_RALIASES;
303 | mpu->RNR = rnrBase;
304 | }
305 |
306 | orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize);
307 | }
308 | }
309 |
310 | /** Load the given number of MPU regions from a table.
311 | * \param rnr First region number to be configured.
312 | * \param table Pointer to the MPU configuration table.
313 | * \param cnt Amount of regions to be configured.
314 | */
315 | __STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
316 | {
317 | ARM_MPU_LoadEx(MPU, rnr, table, cnt);
318 | }
319 |
320 | #ifdef MPU_NS
321 | /** Load the given number of MPU regions from a table to the Non-secure MPU.
322 | * \param rnr First region number to be configured.
323 | * \param table Pointer to the MPU configuration table.
324 | * \param cnt Amount of regions to be configured.
325 | */
326 | __STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt)
327 | {
328 | ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt);
329 | }
330 | #endif
331 |
332 | #endif
333 |
334 |
--------------------------------------------------------------------------------
/src/Core/Src/stm32f1xx_hal_msp.c:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * @file stm32f1xx_hal_msp.c
5 | * @brief This file provides code for the MSP Initialization
6 | * and de-Initialization codes.
7 | ******************************************************************************
8 | * @attention
9 | *
10 | * © Copyright (c) 2021 STMicroelectronics.
11 | * All rights reserved.
12 | *
13 | * This software component is licensed by ST under BSD 3-Clause license,
14 | * the "License"; You may not use this file except in compliance with the
15 | * License. You may obtain a copy of the License at:
16 | * opensource.org/licenses/BSD-3-Clause
17 | *
18 | ******************************************************************************
19 | */
20 | /* USER CODE END Header */
21 |
22 | /* Includes ------------------------------------------------------------------*/
23 | #include "main.h"
24 | /* USER CODE BEGIN Includes */
25 |
26 | /* USER CODE END Includes */
27 |
28 | /* Private typedef -----------------------------------------------------------*/
29 | /* USER CODE BEGIN TD */
30 |
31 | /* USER CODE END TD */
32 |
33 | /* Private define ------------------------------------------------------------*/
34 | /* USER CODE BEGIN Define */
35 |
36 | /* USER CODE END Define */
37 |
38 | /* Private macro -------------------------------------------------------------*/
39 | /* USER CODE BEGIN Macro */
40 |
41 | /* USER CODE END Macro */
42 |
43 | /* Private variables ---------------------------------------------------------*/
44 | /* USER CODE BEGIN PV */
45 |
46 | /* USER CODE END PV */
47 |
48 | /* Private function prototypes -----------------------------------------------*/
49 | /* USER CODE BEGIN PFP */
50 |
51 | /* USER CODE END PFP */
52 |
53 | /* External functions --------------------------------------------------------*/
54 | /* USER CODE BEGIN ExternalFunctions */
55 |
56 | /* USER CODE END ExternalFunctions */
57 |
58 | /* USER CODE BEGIN 0 */
59 |
60 | /* USER CODE END 0 */
61 |
62 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
63 | /**
64 | * Initializes the Global MSP.
65 | */
66 | void HAL_MspInit(void)
67 | {
68 | /* USER CODE BEGIN MspInit 0 */
69 |
70 | /* USER CODE END MspInit 0 */
71 |
72 | __HAL_RCC_AFIO_CLK_ENABLE();
73 | __HAL_RCC_PWR_CLK_ENABLE();
74 |
75 | /* System interrupt init*/
76 |
77 | /** NOJTAG: JTAG-DP Disabled and SW-DP Enabled
78 | */
79 | __HAL_AFIO_REMAP_SWJ_NOJTAG();
80 |
81 | /* USER CODE BEGIN MspInit 1 */
82 |
83 | /* USER CODE END MspInit 1 */
84 | }
85 |
86 | /**
87 | * @brief I2C MSP Initialization
88 | * This function configures the hardware resources used in this example
89 | * @param hi2c: I2C handle pointer
90 | * @retval None
91 | */
92 | void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c)
93 | {
94 | GPIO_InitTypeDef GPIO_InitStruct = {0};
95 | if(hi2c->Instance==I2C1)
96 | {
97 | /* USER CODE BEGIN I2C1_MspInit 0 */
98 |
99 | /* USER CODE END I2C1_MspInit 0 */
100 |
101 | __HAL_RCC_GPIOB_CLK_ENABLE();
102 | /**I2C1 GPIO Configuration
103 | PB6 ------> I2C1_SCL
104 | PB7 ------> I2C1_SDA
105 | */
106 | GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
107 | GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
108 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
109 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
110 |
111 | /* Peripheral clock enable */
112 | __HAL_RCC_I2C1_CLK_ENABLE();
113 | /* USER CODE BEGIN I2C1_MspInit 1 */
114 |
115 | /* USER CODE END I2C1_MspInit 1 */
116 | }
117 |
118 | }
119 |
120 | /**
121 | * @brief I2C MSP De-Initialization
122 | * This function freeze the hardware resources used in this example
123 | * @param hi2c: I2C handle pointer
124 | * @retval None
125 | */
126 | void HAL_I2C_MspDeInit(I2C_HandleTypeDef* hi2c)
127 | {
128 | if(hi2c->Instance==I2C1)
129 | {
130 | /* USER CODE BEGIN I2C1_MspDeInit 0 */
131 |
132 | /* USER CODE END I2C1_MspDeInit 0 */
133 | /* Peripheral clock disable */
134 | __HAL_RCC_I2C1_CLK_DISABLE();
135 |
136 | /**I2C1 GPIO Configuration
137 | PB6 ------> I2C1_SCL
138 | PB7 ------> I2C1_SDA
139 | */
140 | HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6);
141 |
142 | HAL_GPIO_DeInit(GPIOB, GPIO_PIN_7);
143 |
144 | /* USER CODE BEGIN I2C1_MspDeInit 1 */
145 |
146 | /* USER CODE END I2C1_MspDeInit 1 */
147 | }
148 |
149 | }
150 |
151 | /**
152 | * @brief TIM_Base MSP Initialization
153 | * This function configures the hardware resources used in this example
154 | * @param htim_base: TIM_Base handle pointer
155 | * @retval None
156 | */
157 | void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base)
158 | {
159 | if(htim_base->Instance==TIM1)
160 | {
161 | /* USER CODE BEGIN TIM1_MspInit 0 */
162 |
163 | /* USER CODE END TIM1_MspInit 0 */
164 | /* Peripheral clock enable */
165 | __HAL_RCC_TIM1_CLK_ENABLE();
166 | /* USER CODE BEGIN TIM1_MspInit 1 */
167 |
168 | /* USER CODE END TIM1_MspInit 1 */
169 | }
170 | else if(htim_base->Instance==TIM2)
171 | {
172 | /* USER CODE BEGIN TIM2_MspInit 0 */
173 |
174 | /* USER CODE END TIM2_MspInit 0 */
175 | /* Peripheral clock enable */
176 | __HAL_RCC_TIM2_CLK_ENABLE();
177 | /* USER CODE BEGIN TIM2_MspInit 1 */
178 |
179 | /* USER CODE END TIM2_MspInit 1 */
180 | }
181 | else if(htim_base->Instance==TIM3)
182 | {
183 | /* USER CODE BEGIN TIM3_MspInit 0 */
184 |
185 | /* USER CODE END TIM3_MspInit 0 */
186 | /* Peripheral clock enable */
187 | __HAL_RCC_TIM3_CLK_ENABLE();
188 | /* USER CODE BEGIN TIM3_MspInit 1 */
189 |
190 | /* USER CODE END TIM3_MspInit 1 */
191 | }
192 |
193 | }
194 |
195 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
196 | {
197 | GPIO_InitTypeDef GPIO_InitStruct = {0};
198 | if(htim->Instance==TIM1)
199 | {
200 | /* USER CODE BEGIN TIM1_MspPostInit 0 */
201 |
202 | /* USER CODE END TIM1_MspPostInit 0 */
203 | __HAL_RCC_GPIOA_CLK_ENABLE();
204 | /**TIM1 GPIO Configuration
205 | PA8 ------> TIM1_CH1
206 | PA9 ------> TIM1_CH2
207 | PA10 ------> TIM1_CH3
208 | PA11 ------> TIM1_CH4
209 | */
210 | GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_10|GPIO_PIN_11;
211 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
212 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
213 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
214 |
215 | /* USER CODE BEGIN TIM1_MspPostInit 1 */
216 |
217 | /* USER CODE END TIM1_MspPostInit 1 */
218 | }
219 | else if(htim->Instance==TIM2)
220 | {
221 | /* USER CODE BEGIN TIM2_MspPostInit 0 */
222 |
223 | /* USER CODE END TIM2_MspPostInit 0 */
224 |
225 | __HAL_RCC_GPIOA_CLK_ENABLE();
226 | __HAL_RCC_GPIOB_CLK_ENABLE();
227 | /**TIM2 GPIO Configuration
228 | PA0-WKUP ------> TIM2_CH1
229 | PA1 ------> TIM2_CH2
230 | PB10 ------> TIM2_CH3
231 | PB11 ------> TIM2_CH4
232 | */
233 | GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1;
234 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
235 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
236 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
237 |
238 | GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_11;
239 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
240 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
241 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
242 |
243 | __HAL_AFIO_REMAP_TIM2_PARTIAL_2();
244 |
245 | /* USER CODE BEGIN TIM2_MspPostInit 1 */
246 |
247 | /* USER CODE END TIM2_MspPostInit 1 */
248 | }
249 | else if(htim->Instance==TIM3)
250 | {
251 | /* USER CODE BEGIN TIM3_MspPostInit 0 */
252 |
253 | /* USER CODE END TIM3_MspPostInit 0 */
254 |
255 | __HAL_RCC_GPIOA_CLK_ENABLE();
256 | __HAL_RCC_GPIOB_CLK_ENABLE();
257 | /**TIM3 GPIO Configuration
258 | PA6 ------> TIM3_CH1
259 | PA7 ------> TIM3_CH2
260 | PB0 ------> TIM3_CH3
261 | PB1 ------> TIM3_CH4
262 | */
263 | GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
264 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
265 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
266 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
267 |
268 | GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1;
269 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
270 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
271 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
272 |
273 | /* USER CODE BEGIN TIM3_MspPostInit 1 */
274 |
275 | /* USER CODE END TIM3_MspPostInit 1 */
276 | }
277 |
278 | }
279 | /**
280 | * @brief TIM_Base MSP De-Initialization
281 | * This function freeze the hardware resources used in this example
282 | * @param htim_base: TIM_Base handle pointer
283 | * @retval None
284 | */
285 | void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base)
286 | {
287 | if(htim_base->Instance==TIM1)
288 | {
289 | /* USER CODE BEGIN TIM1_MspDeInit 0 */
290 |
291 | /* USER CODE END TIM1_MspDeInit 0 */
292 | /* Peripheral clock disable */
293 | __HAL_RCC_TIM1_CLK_DISABLE();
294 | /* USER CODE BEGIN TIM1_MspDeInit 1 */
295 |
296 | /* USER CODE END TIM1_MspDeInit 1 */
297 | }
298 | else if(htim_base->Instance==TIM2)
299 | {
300 | /* USER CODE BEGIN TIM2_MspDeInit 0 */
301 |
302 | /* USER CODE END TIM2_MspDeInit 0 */
303 | /* Peripheral clock disable */
304 | __HAL_RCC_TIM2_CLK_DISABLE();
305 | /* USER CODE BEGIN TIM2_MspDeInit 1 */
306 |
307 | /* USER CODE END TIM2_MspDeInit 1 */
308 | }
309 | else if(htim_base->Instance==TIM3)
310 | {
311 | /* USER CODE BEGIN TIM3_MspDeInit 0 */
312 |
313 | /* USER CODE END TIM3_MspDeInit 0 */
314 | /* Peripheral clock disable */
315 | __HAL_RCC_TIM3_CLK_DISABLE();
316 | /* USER CODE BEGIN TIM3_MspDeInit 1 */
317 |
318 | /* USER CODE END TIM3_MspDeInit 1 */
319 | }
320 |
321 | }
322 |
323 | /**
324 | * @brief UART MSP Initialization
325 | * This function configures the hardware resources used in this example
326 | * @param huart: UART handle pointer
327 | * @retval None
328 | */
329 | void HAL_UART_MspInit(UART_HandleTypeDef* huart)
330 | {
331 | GPIO_InitTypeDef GPIO_InitStruct = {0};
332 | if(huart->Instance==USART2)
333 | {
334 | /* USER CODE BEGIN USART2_MspInit 0 */
335 |
336 | /* USER CODE END USART2_MspInit 0 */
337 | /* Peripheral clock enable */
338 | __HAL_RCC_USART2_CLK_ENABLE();
339 |
340 | __HAL_RCC_GPIOA_CLK_ENABLE();
341 | /**USART2 GPIO Configuration
342 | PA2 ------> USART2_TX
343 | PA3 ------> USART2_RX
344 | */
345 | GPIO_InitStruct.Pin = GPIO_PIN_2;
346 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
347 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
348 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
349 |
350 | GPIO_InitStruct.Pin = GPIO_PIN_3;
351 | GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
352 | GPIO_InitStruct.Pull = GPIO_NOPULL;
353 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
354 |
355 | /* USART2 interrupt Init */
356 | HAL_NVIC_SetPriority(USART2_IRQn, 0, 0);
357 | HAL_NVIC_EnableIRQ(USART2_IRQn);
358 | /* USER CODE BEGIN USART2_MspInit 1 */
359 |
360 | /* USER CODE END USART2_MspInit 1 */
361 | }
362 |
363 | }
364 |
365 | /**
366 | * @brief UART MSP De-Initialization
367 | * This function freeze the hardware resources used in this example
368 | * @param huart: UART handle pointer
369 | * @retval None
370 | */
371 | void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
372 | {
373 | if(huart->Instance==USART2)
374 | {
375 | /* USER CODE BEGIN USART2_MspDeInit 0 */
376 |
377 | /* USER CODE END USART2_MspDeInit 0 */
378 | /* Peripheral clock disable */
379 | __HAL_RCC_USART2_CLK_DISABLE();
380 |
381 | /**USART2 GPIO Configuration
382 | PA2 ------> USART2_TX
383 | PA3 ------> USART2_RX
384 | */
385 | HAL_GPIO_DeInit(GPIOA, GPIO_PIN_2|GPIO_PIN_3);
386 |
387 | /* USART2 interrupt DeInit */
388 | HAL_NVIC_DisableIRQ(USART2_IRQn);
389 | /* USER CODE BEGIN USART2_MspDeInit 1 */
390 |
391 | /* USER CODE END USART2_MspDeInit 1 */
392 | }
393 |
394 | }
395 |
396 | /* USER CODE BEGIN 1 */
397 |
398 | /* USER CODE END 1 */
399 |
400 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
401 |
--------------------------------------------------------------------------------
/src/Drivers/CMSIS/Include/mpu_armv7.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | * @file mpu_armv7.h
3 | * @brief CMSIS MPU API for Armv7-M MPU
4 | * @version V5.0.4
5 | * @date 10. January 2018
6 | ******************************************************************************/
7 | /*
8 | * Copyright (c) 2017-2018 Arm Limited. All rights reserved.
9 | *
10 | * SPDX-License-Identifier: Apache-2.0
11 | *
12 | * Licensed under the Apache License, Version 2.0 (the License); you may
13 | * not use this file except in compliance with the License.
14 | * You may obtain a copy of the License at
15 | *
16 | * www.apache.org/licenses/LICENSE-2.0
17 | *
18 | * Unless required by applicable law or agreed to in writing, software
19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT
20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
21 | * See the License for the specific language governing permissions and
22 | * limitations under the License.
23 | */
24 |
25 | #if defined ( __ICCARM__ )
26 | #pragma system_include /* treat file as system include file for MISRA check */
27 | #elif defined (__clang__)
28 | #pragma clang system_header /* treat file as system include file */
29 | #endif
30 |
31 | #ifndef ARM_MPU_ARMV7_H
32 | #define ARM_MPU_ARMV7_H
33 |
34 | #define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes
35 | #define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes
36 | #define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes
37 | #define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes
38 | #define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes
39 | #define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte
40 | #define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes
41 | #define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes
42 | #define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes
43 | #define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes
44 | #define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes
45 | #define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes
46 | #define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes
47 | #define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes
48 | #define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes
49 | #define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte
50 | #define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes
51 | #define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes
52 | #define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes
53 | #define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes
54 | #define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes
55 | #define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes
56 | #define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes
57 | #define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes
58 | #define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes
59 | #define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte
60 | #define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes
61 | #define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes
62 |
63 | #define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access
64 | #define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only
65 | #define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only
66 | #define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access
67 | #define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only
68 | #define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access
69 |
70 | /** MPU Region Base Address Register Value
71 | *
72 | * \param Region The region to be configured, number 0 to 15.
73 | * \param BaseAddress The base address for the region.
74 | */
75 | #define ARM_MPU_RBAR(Region, BaseAddress) \
76 | (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \
77 | ((Region) & MPU_RBAR_REGION_Msk) | \
78 | (MPU_RBAR_VALID_Msk))
79 |
80 | /**
81 | * MPU Memory Access Attributes
82 | *
83 | * \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral.
84 | * \param IsShareable Region is shareable between multiple bus masters.
85 | * \param IsCacheable Region is cacheable, i.e. its value may be kept in cache.
86 | * \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy.
87 | */
88 | #define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \
89 | ((((TypeExtField ) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \
90 | (((IsShareable ) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \
91 | (((IsCacheable ) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \
92 | (((IsBufferable ) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk))
93 |
94 | /**
95 | * MPU Region Attribute and Size Register Value
96 | *
97 | * \param DisableExec Instruction access disable bit, 1= disable instruction fetches.
98 | * \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode.
99 | * \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_.
100 | * \param SubRegionDisable Sub-region disable field.
101 | * \param Size Region size of the region to be configured, for example 4K, 8K.
102 | */
103 | #define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \
104 | ((((DisableExec ) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \
105 | (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \
106 | (((AccessAttributes) ) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk)))
107 |
108 | /**
109 | * MPU Region Attribute and Size Register Value
110 | *
111 | * \param DisableExec Instruction access disable bit, 1= disable instruction fetches.
112 | * \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode.
113 | * \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral.
114 | * \param IsShareable Region is shareable between multiple bus masters.
115 | * \param IsCacheable Region is cacheable, i.e. its value may be kept in cache.
116 | * \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy.
117 | * \param SubRegionDisable Sub-region disable field.
118 | * \param Size Region size of the region to be configured, for example 4K, 8K.
119 | */
120 | #define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \
121 | ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size)
122 |
123 | /**
124 | * MPU Memory Access Attribute for strongly ordered memory.
125 | * - TEX: 000b
126 | * - Shareable
127 | * - Non-cacheable
128 | * - Non-bufferable
129 | */
130 | #define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U)
131 |
132 | /**
133 | * MPU Memory Access Attribute for device memory.
134 | * - TEX: 000b (if non-shareable) or 010b (if shareable)
135 | * - Shareable or non-shareable
136 | * - Non-cacheable
137 | * - Bufferable (if shareable) or non-bufferable (if non-shareable)
138 | *
139 | * \param IsShareable Configures the device memory as shareable or non-shareable.
140 | */
141 | #define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U))
142 |
143 | /**
144 | * MPU Memory Access Attribute for normal memory.
145 | * - TEX: 1BBb (reflecting outer cacheability rules)
146 | * - Shareable or non-shareable
147 | * - Cacheable or non-cacheable (reflecting inner cacheability rules)
148 | * - Bufferable or non-bufferable (reflecting inner cacheability rules)
149 | *
150 | * \param OuterCp Configures the outer cache policy.
151 | * \param InnerCp Configures the inner cache policy.
152 | * \param IsShareable Configures the memory as shareable or non-shareable.
153 | */
154 | #define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) & 2U), ((InnerCp) & 1U))
155 |
156 | /**
157 | * MPU Memory Access Attribute non-cacheable policy.
158 | */
159 | #define ARM_MPU_CACHEP_NOCACHE 0U
160 |
161 | /**
162 | * MPU Memory Access Attribute write-back, write and read allocate policy.
163 | */
164 | #define ARM_MPU_CACHEP_WB_WRA 1U
165 |
166 | /**
167 | * MPU Memory Access Attribute write-through, no write allocate policy.
168 | */
169 | #define ARM_MPU_CACHEP_WT_NWA 2U
170 |
171 | /**
172 | * MPU Memory Access Attribute write-back, no write allocate policy.
173 | */
174 | #define ARM_MPU_CACHEP_WB_NWA 3U
175 |
176 |
177 | /**
178 | * Struct for a single MPU Region
179 | */
180 | typedef struct {
181 | uint32_t RBAR; //!< The region base address register value (RBAR)
182 | uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR
183 | } ARM_MPU_Region_t;
184 |
185 | /** Enable the MPU.
186 | * \param MPU_Control Default access permissions for unconfigured regions.
187 | */
188 | __STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control)
189 | {
190 | __DSB();
191 | __ISB();
192 | MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk;
193 | #ifdef SCB_SHCSR_MEMFAULTENA_Msk
194 | SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk;
195 | #endif
196 | }
197 |
198 | /** Disable the MPU.
199 | */
200 | __STATIC_INLINE void ARM_MPU_Disable(void)
201 | {
202 | __DSB();
203 | __ISB();
204 | #ifdef SCB_SHCSR_MEMFAULTENA_Msk
205 | SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk;
206 | #endif
207 | MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk;
208 | }
209 |
210 | /** Clear and disable the given MPU region.
211 | * \param rnr Region number to be cleared.
212 | */
213 | __STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr)
214 | {
215 | MPU->RNR = rnr;
216 | MPU->RASR = 0U;
217 | }
218 |
219 | /** Configure an MPU region.
220 | * \param rbar Value for RBAR register.
221 | * \param rsar Value for RSAR register.
222 | */
223 | __STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr)
224 | {
225 | MPU->RBAR = rbar;
226 | MPU->RASR = rasr;
227 | }
228 |
229 | /** Configure the given MPU region.
230 | * \param rnr Region number to be configured.
231 | * \param rbar Value for RBAR register.
232 | * \param rsar Value for RSAR register.
233 | */
234 | __STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr)
235 | {
236 | MPU->RNR = rnr;
237 | MPU->RBAR = rbar;
238 | MPU->RASR = rasr;
239 | }
240 |
241 | /** Memcopy with strictly ordered memory access, e.g. for register targets.
242 | * \param dst Destination data is copied to.
243 | * \param src Source data is copied from.
244 | * \param len Amount of data words to be copied.
245 | */
246 | __STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len)
247 | {
248 | uint32_t i;
249 | for (i = 0U; i < len; ++i)
250 | {
251 | dst[i] = src[i];
252 | }
253 | }
254 |
255 | /** Load the given number of MPU regions from a table.
256 | * \param table Pointer to the MPU configuration table.
257 | * \param cnt Amount of regions to be configured.
258 | */
259 | __STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt)
260 | {
261 | const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U;
262 | while (cnt > MPU_TYPE_RALIASES) {
263 | orderedCpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize);
264 | table += MPU_TYPE_RALIASES;
265 | cnt -= MPU_TYPE_RALIASES;
266 | }
267 | orderedCpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize);
268 | }
269 |
270 | #endif
271 |
--------------------------------------------------------------------------------
/src/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f1xx_hal.h
4 | * @author MCD Application Team
5 | * @brief This file contains all the functions prototypes for the HAL
6 | * module driver.
7 | ******************************************************************************
8 | * @attention
9 | *
10 | * © Copyright (c) 2017 STMicroelectronics.
11 | * All rights reserved.
12 | *
13 | * This software component is licensed by ST under BSD 3-Clause license,
14 | * the "License"; You may not use this file except in compliance with the
15 | * License. You may obtain a copy of the License at:
16 | * opensource.org/licenses/BSD-3-Clause
17 | *
18 | ******************************************************************************
19 | */
20 |
21 | /* Define to prevent recursive inclusion -------------------------------------*/
22 | #ifndef __STM32F1xx_HAL_H
23 | #define __STM32F1xx_HAL_H
24 |
25 | #ifdef __cplusplus
26 | extern "C" {
27 | #endif
28 |
29 | /* Includes ------------------------------------------------------------------*/
30 | #include "stm32f1xx_hal_conf.h"
31 |
32 | /** @addtogroup STM32F1xx_HAL_Driver
33 | * @{
34 | */
35 |
36 | /** @addtogroup HAL
37 | * @{
38 | */
39 |
40 | /* Exported constants --------------------------------------------------------*/
41 |
42 | /** @defgroup HAL_Exported_Constants HAL Exported Constants
43 | * @{
44 | */
45 |
46 | /** @defgroup HAL_TICK_FREQ Tick Frequency
47 | * @{
48 | */
49 | typedef enum
50 | {
51 | HAL_TICK_FREQ_10HZ = 100U,
52 | HAL_TICK_FREQ_100HZ = 10U,
53 | HAL_TICK_FREQ_1KHZ = 1U,
54 | HAL_TICK_FREQ_DEFAULT = HAL_TICK_FREQ_1KHZ
55 | } HAL_TickFreqTypeDef;
56 | /**
57 | * @}
58 | */
59 | /* Exported types ------------------------------------------------------------*/
60 | extern __IO uint32_t uwTick;
61 | extern uint32_t uwTickPrio;
62 | extern HAL_TickFreqTypeDef uwTickFreq;
63 |
64 | /**
65 | * @}
66 | */
67 | /* Exported macro ------------------------------------------------------------*/
68 | /** @defgroup HAL_Exported_Macros HAL Exported Macros
69 | * @{
70 | */
71 |
72 | /** @defgroup DBGMCU_Freeze_Unfreeze Freeze Unfreeze Peripherals in Debug mode
73 | * @brief Freeze/Unfreeze Peripherals in Debug mode
74 | * Note: On devices STM32F10xx8 and STM32F10xxB,
75 | * STM32F101xC/D/E and STM32F103xC/D/E,
76 | * STM32F101xF/G and STM32F103xF/G
77 | * STM32F10xx4 and STM32F10xx6
78 | * Debug registers DBGMCU_IDCODE and DBGMCU_CR are accessible only in
79 | * debug mode (not accessible by the user software in normal mode).
80 | * Refer to errata sheet of these devices for more details.
81 | * @{
82 | */
83 |
84 | /* Peripherals on APB1 */
85 | /**
86 | * @brief TIM2 Peripherals Debug mode
87 | */
88 | #define __HAL_DBGMCU_FREEZE_TIM2() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM2_STOP)
89 | #define __HAL_DBGMCU_UNFREEZE_TIM2() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM2_STOP)
90 |
91 | /**
92 | * @brief TIM3 Peripherals Debug mode
93 | */
94 | #define __HAL_DBGMCU_FREEZE_TIM3() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM3_STOP)
95 | #define __HAL_DBGMCU_UNFREEZE_TIM3() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM3_STOP)
96 |
97 | #if defined (DBGMCU_CR_DBG_TIM4_STOP)
98 | /**
99 | * @brief TIM4 Peripherals Debug mode
100 | */
101 | #define __HAL_DBGMCU_FREEZE_TIM4() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM4_STOP)
102 | #define __HAL_DBGMCU_UNFREEZE_TIM4() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM4_STOP)
103 | #endif
104 |
105 | #if defined (DBGMCU_CR_DBG_TIM5_STOP)
106 | /**
107 | * @brief TIM5 Peripherals Debug mode
108 | */
109 | #define __HAL_DBGMCU_FREEZE_TIM5() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM5_STOP)
110 | #define __HAL_DBGMCU_UNFREEZE_TIM5() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM5_STOP)
111 | #endif
112 |
113 | #if defined (DBGMCU_CR_DBG_TIM6_STOP)
114 | /**
115 | * @brief TIM6 Peripherals Debug mode
116 | */
117 | #define __HAL_DBGMCU_FREEZE_TIM6() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM6_STOP)
118 | #define __HAL_DBGMCU_UNFREEZE_TIM6() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM6_STOP)
119 | #endif
120 |
121 | #if defined (DBGMCU_CR_DBG_TIM7_STOP)
122 | /**
123 | * @brief TIM7 Peripherals Debug mode
124 | */
125 | #define __HAL_DBGMCU_FREEZE_TIM7() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM7_STOP)
126 | #define __HAL_DBGMCU_UNFREEZE_TIM7() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM7_STOP)
127 | #endif
128 |
129 | #if defined (DBGMCU_CR_DBG_TIM12_STOP)
130 | /**
131 | * @brief TIM12 Peripherals Debug mode
132 | */
133 | #define __HAL_DBGMCU_FREEZE_TIM12() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM12_STOP)
134 | #define __HAL_DBGMCU_UNFREEZE_TIM12() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM12_STOP)
135 | #endif
136 |
137 | #if defined (DBGMCU_CR_DBG_TIM13_STOP)
138 | /**
139 | * @brief TIM13 Peripherals Debug mode
140 | */
141 | #define __HAL_DBGMCU_FREEZE_TIM13() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM13_STOP)
142 | #define __HAL_DBGMCU_UNFREEZE_TIM13() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM13_STOP)
143 | #endif
144 |
145 | #if defined (DBGMCU_CR_DBG_TIM14_STOP)
146 | /**
147 | * @brief TIM14 Peripherals Debug mode
148 | */
149 | #define __HAL_DBGMCU_FREEZE_TIM14() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM14_STOP)
150 | #define __HAL_DBGMCU_UNFREEZE_TIM14() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM14_STOP)
151 | #endif
152 |
153 | /**
154 | * @brief WWDG Peripherals Debug mode
155 | */
156 | #define __HAL_DBGMCU_FREEZE_WWDG() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_WWDG_STOP)
157 | #define __HAL_DBGMCU_UNFREEZE_WWDG() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_WWDG_STOP)
158 |
159 | /**
160 | * @brief IWDG Peripherals Debug mode
161 | */
162 | #define __HAL_DBGMCU_FREEZE_IWDG() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_IWDG_STOP)
163 | #define __HAL_DBGMCU_UNFREEZE_IWDG() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_IWDG_STOP)
164 |
165 | /**
166 | * @brief I2C1 Peripherals Debug mode
167 | */
168 | #define __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_I2C1_SMBUS_TIMEOUT)
169 | #define __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_I2C1_SMBUS_TIMEOUT)
170 |
171 | #if defined (DBGMCU_CR_DBG_I2C2_SMBUS_TIMEOUT)
172 | /**
173 | * @brief I2C2 Peripherals Debug mode
174 | */
175 | #define __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_I2C2_SMBUS_TIMEOUT)
176 | #define __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_I2C2_SMBUS_TIMEOUT)
177 | #endif
178 |
179 | #if defined (DBGMCU_CR_DBG_CAN1_STOP)
180 | /**
181 | * @brief CAN1 Peripherals Debug mode
182 | */
183 | #define __HAL_DBGMCU_FREEZE_CAN1() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_CAN1_STOP)
184 | #define __HAL_DBGMCU_UNFREEZE_CAN1() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_CAN1_STOP)
185 | #endif
186 |
187 | #if defined (DBGMCU_CR_DBG_CAN2_STOP)
188 | /**
189 | * @brief CAN2 Peripherals Debug mode
190 | */
191 | #define __HAL_DBGMCU_FREEZE_CAN2() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_CAN2_STOP)
192 | #define __HAL_DBGMCU_UNFREEZE_CAN2() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_CAN2_STOP)
193 | #endif
194 |
195 | /* Peripherals on APB2 */
196 | #if defined (DBGMCU_CR_DBG_TIM1_STOP)
197 | /**
198 | * @brief TIM1 Peripherals Debug mode
199 | */
200 | #define __HAL_DBGMCU_FREEZE_TIM1() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM1_STOP)
201 | #define __HAL_DBGMCU_UNFREEZE_TIM1() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM1_STOP)
202 | #endif
203 |
204 | #if defined (DBGMCU_CR_DBG_TIM8_STOP)
205 | /**
206 | * @brief TIM8 Peripherals Debug mode
207 | */
208 | #define __HAL_DBGMCU_FREEZE_TIM8() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM8_STOP)
209 | #define __HAL_DBGMCU_UNFREEZE_TIM8() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM8_STOP)
210 | #endif
211 |
212 | #if defined (DBGMCU_CR_DBG_TIM9_STOP)
213 | /**
214 | * @brief TIM9 Peripherals Debug mode
215 | */
216 | #define __HAL_DBGMCU_FREEZE_TIM9() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM9_STOP)
217 | #define __HAL_DBGMCU_UNFREEZE_TIM9() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM9_STOP)
218 | #endif
219 |
220 | #if defined (DBGMCU_CR_DBG_TIM10_STOP)
221 | /**
222 | * @brief TIM10 Peripherals Debug mode
223 | */
224 | #define __HAL_DBGMCU_FREEZE_TIM10() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM10_STOP)
225 | #define __HAL_DBGMCU_UNFREEZE_TIM10() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM10_STOP)
226 | #endif
227 |
228 | #if defined (DBGMCU_CR_DBG_TIM11_STOP)
229 | /**
230 | * @brief TIM11 Peripherals Debug mode
231 | */
232 | #define __HAL_DBGMCU_FREEZE_TIM11() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM11_STOP)
233 | #define __HAL_DBGMCU_UNFREEZE_TIM11() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM11_STOP)
234 | #endif
235 |
236 |
237 | #if defined (DBGMCU_CR_DBG_TIM15_STOP)
238 | /**
239 | * @brief TIM15 Peripherals Debug mode
240 | */
241 | #define __HAL_DBGMCU_FREEZE_TIM15() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM15_STOP)
242 | #define __HAL_DBGMCU_UNFREEZE_TIM15() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM15_STOP)
243 | #endif
244 |
245 | #if defined (DBGMCU_CR_DBG_TIM16_STOP)
246 | /**
247 | * @brief TIM16 Peripherals Debug mode
248 | */
249 | #define __HAL_DBGMCU_FREEZE_TIM16() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM16_STOP)
250 | #define __HAL_DBGMCU_UNFREEZE_TIM16() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM16_STOP)
251 | #endif
252 |
253 | #if defined (DBGMCU_CR_DBG_TIM17_STOP)
254 | /**
255 | * @brief TIM17 Peripherals Debug mode
256 | */
257 | #define __HAL_DBGMCU_FREEZE_TIM17() SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM17_STOP)
258 | #define __HAL_DBGMCU_UNFREEZE_TIM17() CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_TIM17_STOP)
259 | #endif
260 |
261 | /**
262 | * @}
263 | */
264 |
265 | /** @defgroup HAL_Private_Macros HAL Private Macros
266 | * @{
267 | */
268 | #define IS_TICKFREQ(FREQ) (((FREQ) == HAL_TICK_FREQ_10HZ) || \
269 | ((FREQ) == HAL_TICK_FREQ_100HZ) || \
270 | ((FREQ) == HAL_TICK_FREQ_1KHZ))
271 | /**
272 | * @}
273 | */
274 |
275 | /* Exported functions --------------------------------------------------------*/
276 | /** @addtogroup HAL_Exported_Functions
277 | * @{
278 | */
279 | /** @addtogroup HAL_Exported_Functions_Group1
280 | * @{
281 | */
282 | /* Initialization and de-initialization functions ******************************/
283 | HAL_StatusTypeDef HAL_Init(void);
284 | HAL_StatusTypeDef HAL_DeInit(void);
285 | void HAL_MspInit(void);
286 | void HAL_MspDeInit(void);
287 | HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority);
288 | /**
289 | * @}
290 | */
291 |
292 | /** @addtogroup HAL_Exported_Functions_Group2
293 | * @{
294 | */
295 | /* Peripheral Control functions ************************************************/
296 | void HAL_IncTick(void);
297 | void HAL_Delay(uint32_t Delay);
298 | uint32_t HAL_GetTick(void);
299 | uint32_t HAL_GetTickPrio(void);
300 | HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq);
301 | HAL_TickFreqTypeDef HAL_GetTickFreq(void);
302 | void HAL_SuspendTick(void);
303 | void HAL_ResumeTick(void);
304 | uint32_t HAL_GetHalVersion(void);
305 | uint32_t HAL_GetREVID(void);
306 | uint32_t HAL_GetDEVID(void);
307 | uint32_t HAL_GetUIDw0(void);
308 | uint32_t HAL_GetUIDw1(void);
309 | uint32_t HAL_GetUIDw2(void);
310 | void HAL_DBGMCU_EnableDBGSleepMode(void);
311 | void HAL_DBGMCU_DisableDBGSleepMode(void);
312 | void HAL_DBGMCU_EnableDBGStopMode(void);
313 | void HAL_DBGMCU_DisableDBGStopMode(void);
314 | void HAL_DBGMCU_EnableDBGStandbyMode(void);
315 | void HAL_DBGMCU_DisableDBGStandbyMode(void);
316 | /**
317 | * @}
318 | */
319 |
320 | /**
321 | * @}
322 | */
323 |
324 | /**
325 | * @}
326 | */
327 | /* Private types -------------------------------------------------------------*/
328 | /* Private variables ---------------------------------------------------------*/
329 | /** @defgroup HAL_Private_Variables HAL Private Variables
330 | * @{
331 | */
332 | /**
333 | * @}
334 | */
335 | /* Private constants ---------------------------------------------------------*/
336 | /** @defgroup HAL_Private_Constants HAL Private Constants
337 | * @{
338 | */
339 | /**
340 | * @}
341 | */
342 | /* Private macros ------------------------------------------------------------*/
343 | /* Private functions ---------------------------------------------------------*/
344 | /**
345 | * @}
346 | */
347 |
348 | /**
349 | * @}
350 | */
351 |
352 | #ifdef __cplusplus
353 | }
354 | #endif
355 |
356 | #endif /* __STM32F1xx_HAL_H */
357 |
358 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
359 |
--------------------------------------------------------------------------------
/src/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_gpio.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f1xx_hal_gpio.h
4 | * @author MCD Application Team
5 | * @brief Header file of GPIO HAL module.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2016 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Define to prevent recursive inclusion -------------------------------------*/
21 | #ifndef STM32F1xx_HAL_GPIO_H
22 | #define STM32F1xx_HAL_GPIO_H
23 |
24 | #ifdef __cplusplus
25 | extern "C" {
26 | #endif
27 |
28 | /* Includes ------------------------------------------------------------------*/
29 | #include "stm32f1xx_hal_def.h"
30 |
31 | /** @addtogroup STM32F1xx_HAL_Driver
32 | * @{
33 | */
34 |
35 | /** @addtogroup GPIO
36 | * @{
37 | */
38 |
39 | /* Exported types ------------------------------------------------------------*/
40 | /** @defgroup GPIO_Exported_Types GPIO Exported Types
41 | * @{
42 | */
43 |
44 | /**
45 | * @brief GPIO Init structure definition
46 | */
47 | typedef struct
48 | {
49 | uint32_t Pin; /*!< Specifies the GPIO pins to be configured.
50 | This parameter can be any value of @ref GPIO_pins_define */
51 |
52 | uint32_t Mode; /*!< Specifies the operating mode for the selected pins.
53 | This parameter can be a value of @ref GPIO_mode_define */
54 |
55 | uint32_t Pull; /*!< Specifies the Pull-up or Pull-Down activation for the selected pins.
56 | This parameter can be a value of @ref GPIO_pull_define */
57 |
58 | uint32_t Speed; /*!< Specifies the speed for the selected pins.
59 | This parameter can be a value of @ref GPIO_speed_define */
60 | } GPIO_InitTypeDef;
61 |
62 | /**
63 | * @brief GPIO Bit SET and Bit RESET enumeration
64 | */
65 | typedef enum
66 | {
67 | GPIO_PIN_RESET = 0u,
68 | GPIO_PIN_SET
69 | } GPIO_PinState;
70 | /**
71 | * @}
72 | */
73 |
74 | /* Exported constants --------------------------------------------------------*/
75 |
76 | /** @defgroup GPIO_Exported_Constants GPIO Exported Constants
77 | * @{
78 | */
79 |
80 | /** @defgroup GPIO_pins_define GPIO pins define
81 | * @{
82 | */
83 | #define GPIO_PIN_0 ((uint16_t)0x0001) /* Pin 0 selected */
84 | #define GPIO_PIN_1 ((uint16_t)0x0002) /* Pin 1 selected */
85 | #define GPIO_PIN_2 ((uint16_t)0x0004) /* Pin 2 selected */
86 | #define GPIO_PIN_3 ((uint16_t)0x0008) /* Pin 3 selected */
87 | #define GPIO_PIN_4 ((uint16_t)0x0010) /* Pin 4 selected */
88 | #define GPIO_PIN_5 ((uint16_t)0x0020) /* Pin 5 selected */
89 | #define GPIO_PIN_6 ((uint16_t)0x0040) /* Pin 6 selected */
90 | #define GPIO_PIN_7 ((uint16_t)0x0080) /* Pin 7 selected */
91 | #define GPIO_PIN_8 ((uint16_t)0x0100) /* Pin 8 selected */
92 | #define GPIO_PIN_9 ((uint16_t)0x0200) /* Pin 9 selected */
93 | #define GPIO_PIN_10 ((uint16_t)0x0400) /* Pin 10 selected */
94 | #define GPIO_PIN_11 ((uint16_t)0x0800) /* Pin 11 selected */
95 | #define GPIO_PIN_12 ((uint16_t)0x1000) /* Pin 12 selected */
96 | #define GPIO_PIN_13 ((uint16_t)0x2000) /* Pin 13 selected */
97 | #define GPIO_PIN_14 ((uint16_t)0x4000) /* Pin 14 selected */
98 | #define GPIO_PIN_15 ((uint16_t)0x8000) /* Pin 15 selected */
99 | #define GPIO_PIN_All ((uint16_t)0xFFFF) /* All pins selected */
100 |
101 | #define GPIO_PIN_MASK 0x0000FFFFu /* PIN mask for assert test */
102 | /**
103 | * @}
104 | */
105 |
106 | /** @defgroup GPIO_mode_define GPIO mode define
107 | * @brief GPIO Configuration Mode
108 | * Elements values convention: 0xX0yz00YZ
109 | * - X : GPIO mode or EXTI Mode
110 | * - y : External IT or Event trigger detection
111 | * - z : IO configuration on External IT or Event
112 | * - Y : Output type (Push Pull or Open Drain)
113 | * - Z : IO Direction mode (Input, Output, Alternate or Analog)
114 | * @{
115 | */
116 | #define GPIO_MODE_INPUT 0x00000000u /*!< Input Floating Mode */
117 | #define GPIO_MODE_OUTPUT_PP 0x00000001u /*!< Output Push Pull Mode */
118 | #define GPIO_MODE_OUTPUT_OD 0x00000011u /*!< Output Open Drain Mode */
119 | #define GPIO_MODE_AF_PP 0x00000002u /*!< Alternate Function Push Pull Mode */
120 | #define GPIO_MODE_AF_OD 0x00000012u /*!< Alternate Function Open Drain Mode */
121 | #define GPIO_MODE_AF_INPUT GPIO_MODE_INPUT /*!< Alternate Function Input Mode */
122 |
123 | #define GPIO_MODE_ANALOG 0x00000003u /*!< Analog Mode */
124 |
125 | #define GPIO_MODE_IT_RISING 0x10110000u /*!< External Interrupt Mode with Rising edge trigger detection */
126 | #define GPIO_MODE_IT_FALLING 0x10210000u /*!< External Interrupt Mode with Falling edge trigger detection */
127 | #define GPIO_MODE_IT_RISING_FALLING 0x10310000u /*!< External Interrupt Mode with Rising/Falling edge trigger detection */
128 |
129 | #define GPIO_MODE_EVT_RISING 0x10120000u /*!< External Event Mode with Rising edge trigger detection */
130 | #define GPIO_MODE_EVT_FALLING 0x10220000u /*!< External Event Mode with Falling edge trigger detection */
131 | #define GPIO_MODE_EVT_RISING_FALLING 0x10320000u /*!< External Event Mode with Rising/Falling edge trigger detection */
132 |
133 | /**
134 | * @}
135 | */
136 |
137 | /** @defgroup GPIO_speed_define GPIO speed define
138 | * @brief GPIO Output Maximum frequency
139 | * @{
140 | */
141 | #define GPIO_SPEED_FREQ_LOW (GPIO_CRL_MODE0_1) /*!< Low speed */
142 | #define GPIO_SPEED_FREQ_MEDIUM (GPIO_CRL_MODE0_0) /*!< Medium speed */
143 | #define GPIO_SPEED_FREQ_HIGH (GPIO_CRL_MODE0) /*!< High speed */
144 |
145 | /**
146 | * @}
147 | */
148 |
149 | /** @defgroup GPIO_pull_define GPIO pull define
150 | * @brief GPIO Pull-Up or Pull-Down Activation
151 | * @{
152 | */
153 | #define GPIO_NOPULL 0x00000000u /*!< No Pull-up or Pull-down activation */
154 | #define GPIO_PULLUP 0x00000001u /*!< Pull-up activation */
155 | #define GPIO_PULLDOWN 0x00000002u /*!< Pull-down activation */
156 | /**
157 | * @}
158 | */
159 |
160 | /**
161 | * @}
162 | */
163 |
164 | /* Exported macro ------------------------------------------------------------*/
165 | /** @defgroup GPIO_Exported_Macros GPIO Exported Macros
166 | * @{
167 | */
168 |
169 | /**
170 | * @brief Checks whether the specified EXTI line flag is set or not.
171 | * @param __EXTI_LINE__: specifies the EXTI line flag to check.
172 | * This parameter can be GPIO_PIN_x where x can be(0..15)
173 | * @retval The new state of __EXTI_LINE__ (SET or RESET).
174 | */
175 | #define __HAL_GPIO_EXTI_GET_FLAG(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__))
176 |
177 | /**
178 | * @brief Clears the EXTI's line pending flags.
179 | * @param __EXTI_LINE__: specifies the EXTI lines flags to clear.
180 | * This parameter can be any combination of GPIO_PIN_x where x can be (0..15)
181 | * @retval None
182 | */
183 | #define __HAL_GPIO_EXTI_CLEAR_FLAG(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__))
184 |
185 | /**
186 | * @brief Checks whether the specified EXTI line is asserted or not.
187 | * @param __EXTI_LINE__: specifies the EXTI line to check.
188 | * This parameter can be GPIO_PIN_x where x can be(0..15)
189 | * @retval The new state of __EXTI_LINE__ (SET or RESET).
190 | */
191 | #define __HAL_GPIO_EXTI_GET_IT(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__))
192 |
193 | /**
194 | * @brief Clears the EXTI's line pending bits.
195 | * @param __EXTI_LINE__: specifies the EXTI lines to clear.
196 | * This parameter can be any combination of GPIO_PIN_x where x can be (0..15)
197 | * @retval None
198 | */
199 | #define __HAL_GPIO_EXTI_CLEAR_IT(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__))
200 |
201 | /**
202 | * @brief Generates a Software interrupt on selected EXTI line.
203 | * @param __EXTI_LINE__: specifies the EXTI line to check.
204 | * This parameter can be GPIO_PIN_x where x can be(0..15)
205 | * @retval None
206 | */
207 | #define __HAL_GPIO_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__))
208 | /**
209 | * @}
210 | */
211 |
212 | /* Include GPIO HAL Extension module */
213 | #include "stm32f1xx_hal_gpio_ex.h"
214 |
215 | /* Exported functions --------------------------------------------------------*/
216 | /** @addtogroup GPIO_Exported_Functions
217 | * @{
218 | */
219 |
220 | /** @addtogroup GPIO_Exported_Functions_Group1
221 | * @{
222 | */
223 | /* Initialization and de-initialization functions *****************************/
224 | void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init);
225 | void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin);
226 | /**
227 | * @}
228 | */
229 |
230 | /** @addtogroup GPIO_Exported_Functions_Group2
231 | * @{
232 | */
233 | /* IO operation functions *****************************************************/
234 | GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
235 | void HAL_GPIO_WritePin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState);
236 | void HAL_GPIO_TogglePin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
237 | HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
238 | void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin);
239 | void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin);
240 |
241 | /**
242 | * @}
243 | */
244 |
245 | /**
246 | * @}
247 | */
248 | /* Private types -------------------------------------------------------------*/
249 | /* Private variables ---------------------------------------------------------*/
250 | /* Private constants ---------------------------------------------------------*/
251 | /** @defgroup GPIO_Private_Constants GPIO Private Constants
252 | * @{
253 | */
254 |
255 | /**
256 | * @}
257 | */
258 |
259 | /* Private macros ------------------------------------------------------------*/
260 | /** @defgroup GPIO_Private_Macros GPIO Private Macros
261 | * @{
262 | */
263 | #define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET))
264 | #define IS_GPIO_PIN(PIN) (((((uint32_t)PIN) & GPIO_PIN_MASK ) != 0x00u) && ((((uint32_t)PIN) & ~GPIO_PIN_MASK) == 0x00u))
265 | #define IS_GPIO_MODE(MODE) (((MODE) == GPIO_MODE_INPUT) ||\
266 | ((MODE) == GPIO_MODE_OUTPUT_PP) ||\
267 | ((MODE) == GPIO_MODE_OUTPUT_OD) ||\
268 | ((MODE) == GPIO_MODE_AF_PP) ||\
269 | ((MODE) == GPIO_MODE_AF_OD) ||\
270 | ((MODE) == GPIO_MODE_IT_RISING) ||\
271 | ((MODE) == GPIO_MODE_IT_FALLING) ||\
272 | ((MODE) == GPIO_MODE_IT_RISING_FALLING) ||\
273 | ((MODE) == GPIO_MODE_EVT_RISING) ||\
274 | ((MODE) == GPIO_MODE_EVT_FALLING) ||\
275 | ((MODE) == GPIO_MODE_EVT_RISING_FALLING) ||\
276 | ((MODE) == GPIO_MODE_ANALOG))
277 | #define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_SPEED_FREQ_LOW) || \
278 | ((SPEED) == GPIO_SPEED_FREQ_MEDIUM) || ((SPEED) == GPIO_SPEED_FREQ_HIGH))
279 | #define IS_GPIO_PULL(PULL) (((PULL) == GPIO_NOPULL) || ((PULL) == GPIO_PULLUP) || \
280 | ((PULL) == GPIO_PULLDOWN))
281 | /**
282 | * @}
283 | */
284 |
285 | /* Private functions ---------------------------------------------------------*/
286 | /** @defgroup GPIO_Private_Functions GPIO Private Functions
287 | * @{
288 | */
289 |
290 | /**
291 | * @}
292 | */
293 |
294 | /**
295 | * @}
296 | */
297 |
298 | /**
299 | * @}
300 | */
301 |
302 | #ifdef __cplusplus
303 | }
304 | #endif
305 |
306 | #endif /* STM32F1xx_HAL_GPIO_H */
307 |
308 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
309 |
--------------------------------------------------------------------------------