├── Hardware ├── Message_usb.cpp ├── Hardware.hpp ├── board.h ├── Message_usart.cpp ├── Motor_PWM.cpp ├── Motor_PWM.hpp ├── Message_usb.hpp ├── LED_IO.cpp ├── Message_usart.hpp ├── Sensor_mpu9250.hpp ├── LED_IO.hpp ├── Sensor_mpu9250.cpp └── mpu9250.h ├── README.md ├── Common ├── common.hpp ├── base.hpp ├── common.cpp └── pid.hpp ├── MyFlight ├── interface.hpp ├── flight.cpp ├── hal.hpp ├── flight.hpp └── task.cpp ├── .gitignore └── Board ├── Core └── Src │ ├── main.c │ └── freertos.c ├── myflight.ioc └── MDK-ARM ├── startup_stm32f411xe.s └── myflight.uvprojx /Hardware/Message_usb.cpp: -------------------------------------------------------------------------------- 1 | #include "Message_usb.hpp" 2 | 3 | 4 | void mf::Message_usb::init(){ 5 | 6 | } -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # MyFlight 2 | 3 | ### Board--------板子相关 4 | ### Common-------基础设施 5 | ### Hardware-----硬件驱动 6 | ### MyFlight-----飞控相关 -------------------------------------------------------------------------------- /Common/common.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "base.hpp" 4 | 5 | namespace mf 6 | { 7 | void PostureCalculate(vec3f&, vec3f&, vec3f&, f32, f32); 8 | } -------------------------------------------------------------------------------- /MyFlight/interface.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | 4 | #include "stm32f4xx.h" 5 | #include "stm32f4xx_hal.h" 6 | 7 | #include "usbd_cdc_if.h" 8 | 9 | #include "cmsis_os2.h" -------------------------------------------------------------------------------- /Hardware/Hardware.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "Sensor_mpu9250.hpp" 4 | #include "Motor_PWM.hpp" 5 | #include "Message_usart.hpp" 6 | #include "Message_usb.hpp" 7 | #include "LED_IO.hpp" -------------------------------------------------------------------------------- /Hardware/board.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "stm32f4xx.h" 4 | #include "stm32f4xx_hal.h" 5 | 6 | #include "gpio.h" 7 | #include "i2c.h" 8 | #include "tim.h" 9 | #include "usart.h" 10 | #include "usbd_cdc_if.h" 11 | 12 | #include "arm_math.h" -------------------------------------------------------------------------------- /Hardware/Message_usart.cpp: -------------------------------------------------------------------------------- 1 | #include "Message_usart.hpp" 2 | 3 | mf::Message_usart::Message_usart(UART_HandleTypeDef* uart_):uart(uart_){ 4 | 5 | } 6 | 7 | void mf::Message_usart::init(){ 8 | HAL_UART_Receive_IT(&huart1, (uint8_t *)&(this->buff), 1); 9 | } 10 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | 2 | Board/Core/Inc/ 3 | Board/Core/Src/* 4 | !Board/Core/src/freertos.c 5 | !Board/Core/src/main.c 6 | 7 | Board/Drivers/ 8 | 9 | Board/MDK-ARM/* 10 | !Board/MDK-ARM/myflight.uvprojx 11 | !Board/MDK-ARM/startup_stm32f411xe.s 12 | 13 | Board/Middlewares/ 14 | 15 | Board/USB_Device 16 | 17 | 18 | Board/.mxproject 19 | 20 | .vscode -------------------------------------------------------------------------------- /Hardware/Motor_PWM.cpp: -------------------------------------------------------------------------------- 1 | #include "Motor_PWM.hpp" 2 | 3 | #include "interface.hpp" 4 | 5 | void mf::Motor_PWM::turn(f32 speed_) const { 6 | if(speed_ >= 0.0f){ 7 | *((u32*)tim) = (u32)(this->period * speed_); 8 | } 9 | } 10 | 11 | void mf::Motor_PWM::enabled(){ 12 | 13 | } 14 | 15 | void mf::Motor_PWM::disabled(){ 16 | 17 | } 18 | 19 | void mf::Motor_PWM::init() { 20 | 21 | } -------------------------------------------------------------------------------- /Common/base.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #define MYPI 3.141592653f 4 | 5 | using u8 = unsigned char; 6 | using s8 = char; 7 | using u16 = unsigned short; 8 | using s16 = short; 9 | using u32 = unsigned int; 10 | using s32 = int; 11 | using f32 = float; 12 | using f64 = double; 13 | 14 | 15 | template 16 | struct vec3{ 17 | f32 x, y, z; 18 | }; 19 | 20 | using vec3f = vec3; 21 | using vec3s = vec3; 22 | using vec3i = vec3; -------------------------------------------------------------------------------- /Common/common.cpp: -------------------------------------------------------------------------------- 1 | #include "common.hpp" 2 | 3 | #include "arm_math.h" 4 | 5 | void mf::PostureCalculate(vec3f& acc, vec3f& gyro, vec3f& out, f32 dt, f32 ki) 6 | { 7 | f32 kxz = acc.x / acc.z; 8 | f32 kyz = acc.y / acc.z; 9 | 10 | f32 gxi = gyro.x * dt; 11 | f32 gyi = gyro.y * dt; 12 | f32 gzi = gyro.z * dt; 13 | 14 | out.x = ( (out.x + gyro.x * dt) * ki) + ( atan(kxz) * (1 - ki) ); 15 | out.y = ( (out.y + gyro.y * dt) * ki) + ( atan(kyz) * (1 - ki) ); 16 | out.z = out.z + gyro.z * dt; 17 | } -------------------------------------------------------------------------------- /Hardware/Motor_PWM.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "hal.hpp" 4 | #include "board.h" 5 | 6 | namespace mf 7 | { 8 | 9 | class Motor_PWM : public mf::Motor{ 10 | 11 | s32 period; 12 | volatile u32* tim; 13 | 14 | public: 15 | 16 | explicit Motor_PWM(volatile u32* tim_, s32 period_):tim(tim_), period(period_){} 17 | 18 | void init() override; 19 | 20 | void enabled() override; 21 | 22 | void disabled() override; 23 | 24 | void turn(f32) const override; 25 | 26 | }; 27 | } -------------------------------------------------------------------------------- /Hardware/Message_usb.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "hal.hpp" 4 | #include "board.h" 5 | 6 | namespace mf{ 7 | 8 | class Message_usb : public mf::Message{ 9 | 10 | public: 11 | 12 | virtual void init() override; 13 | 14 | virtual s32 send(void* buff_, s32 len_) override { 15 | CDC_Transmit_FS((u8*)buff_, len_); 16 | return len_; 17 | } 18 | 19 | virtual s32 recv(void* buff_, s32 len_) override { 20 | return len_; 21 | } 22 | 23 | explicit Message_usb(){}; 24 | }; 25 | 26 | } -------------------------------------------------------------------------------- /Hardware/LED_IO.cpp: -------------------------------------------------------------------------------- 1 | #include "LED_IO.hpp" 2 | 3 | void mf::LED_IO_H::off() const 4 | { 5 | HAL_GPIO_WritePin(gpio, pin, GPIO_PIN_RESET); 6 | } 7 | 8 | void mf::LED_IO_H::on() const 9 | { 10 | HAL_GPIO_WritePin(gpio, pin, GPIO_PIN_SET); 11 | } 12 | 13 | void mf::LED_IO_H::reversal() const 14 | { 15 | HAL_GPIO_TogglePin(gpio, pin); 16 | } 17 | 18 | void mf::LED_IO_L::off() const 19 | { 20 | HAL_GPIO_WritePin(gpio, pin, GPIO_PIN_SET); 21 | } 22 | 23 | void mf::LED_IO_L::on() const 24 | { 25 | HAL_GPIO_WritePin(gpio, pin, GPIO_PIN_RESET); 26 | } 27 | 28 | void mf::LED_IO_L::reversal() const 29 | { 30 | HAL_GPIO_TogglePin(gpio, pin); 31 | } -------------------------------------------------------------------------------- /Hardware/Message_usart.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "hal.hpp" 4 | #include "board.h" 5 | 6 | namespace mf{ 7 | 8 | class Message_usart : public mf::Message{ 9 | 10 | UART_HandleTypeDef* uart; 11 | 12 | public: 13 | 14 | virtual void init() override; 15 | 16 | virtual s32 send(void* buff_, s32 len_) override { 17 | HAL_UART_Transmit(uart, (u8*)buff_, len_, 0xffff); 18 | return len_; 19 | } 20 | 21 | virtual s32 recv(void* buff_, s32 len_) override { 22 | HAL_UART_Receive_IT(uart, (u8*)buff_, len_); 23 | return len_; 24 | }; 25 | 26 | explicit Message_usart(UART_HandleTypeDef*); 27 | 28 | }; 29 | 30 | } -------------------------------------------------------------------------------- /Hardware/Sensor_mpu9250.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "hal.hpp" 4 | #include "board.h" 5 | 6 | namespace mf 7 | { 8 | class Sensor_mpu9250 : public mf::Sensor{ 9 | 10 | I2C_HandleTypeDef* hi2c; 11 | u16 addr; 12 | 13 | void updateOrgData(); 14 | void conversionData(); 15 | 16 | 17 | public: 18 | 19 | s16 org_ax, org_ay, org_az; 20 | s16 org_gx, org_gy, org_gz; 21 | 22 | vec3f acc; 23 | vec3f gyro; 24 | 25 | explicit Sensor_mpu9250(I2C_HandleTypeDef* hi2c_, u16 addr_); 26 | 27 | void init() override; 28 | 29 | void update(f32 dt_ = 0.0f) override; 30 | 31 | void debug(f32 dt); 32 | 33 | }; 34 | } 35 | -------------------------------------------------------------------------------- /Hardware/LED_IO.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "hal.hpp" 4 | #include "board.h" 5 | 6 | namespace mf 7 | { 8 | class LED_IO_H : public LED{ 9 | 10 | GPIO_TypeDef* gpio; 11 | u16 pin; 12 | 13 | public: 14 | 15 | explicit LED_IO_H(GPIO_TypeDef* gpio_, u16 pin_): gpio(gpio_), pin(pin_){} 16 | 17 | void off() const override; 18 | 19 | void on() const override; 20 | 21 | void reversal() const override; 22 | 23 | }; 24 | 25 | class LED_IO_L : public LED{ 26 | 27 | public: 28 | 29 | GPIO_TypeDef* gpio; 30 | u16 pin; 31 | 32 | explicit LED_IO_L(GPIO_TypeDef* gpio_, u16 pin_): gpio(gpio_), pin(pin_){} 33 | 34 | void off() const override; 35 | 36 | void on() const override; 37 | 38 | void reversal() const override; 39 | 40 | }; 41 | 42 | 43 | } -------------------------------------------------------------------------------- /Common/pid.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | namespace my { 4 | 5 | template 6 | class pid; 7 | 8 | template 9 | struct pid_pos 10 | { 11 | T kp; 12 | T ki; 13 | T kd; 14 | T deadband; 15 | T integral; 16 | T i_threshold; 17 | T error_last; 18 | 19 | public: 20 | 21 | explicit pid_pos(T kp_, T ki_, T kd_, T deadband_) : 22 | kp(kp_), 23 | ki(ki_), 24 | kd(ki_), 25 | deadband(deadband_), 26 | integral(0), 27 | i_threshold(0), 28 | error_last(0) { 29 | } 30 | 31 | }; 32 | 33 | template 34 | class pid 35 | { 36 | 37 | T abs_t(T& t) { 38 | return t >= 0 ? t : -t; 39 | } 40 | 41 | public: 42 | T out(const T& target_, const T& feedback_, my::pid_pos& pid_) { 43 | T error = target_ - feedback_; 44 | if (abs_t(error) <= pid_.deadband) { 45 | return 0; 46 | } 47 | if (pid_.integral <= pid_.i_threshold) { 48 | pid_.integral += error; 49 | } 50 | T result = pid_.kp * error + pid_.ki * pid_.integral + pid_.kd * (error - pid_.error_last); 51 | pid_.error_last = error; 52 | return result; 53 | } 54 | 55 | T operator() (const T& target_, const T& feedback_, my::pid_pos& pid_) { 56 | return this->out(target_, feedback_, pid_); 57 | } 58 | }; 59 | 60 | 61 | } 62 | -------------------------------------------------------------------------------- /MyFlight/flight.cpp: -------------------------------------------------------------------------------- 1 | #include "Flight.hpp" 2 | 3 | 4 | mf::Flight::Flight(): 5 | sensor(*new mf::Sensor_mpu9250(&hi2c1, 0XD2u)), 6 | motor1(*new mf::Motor_PWM(&(TIM2->CCR1), 1000)), 7 | motor2(*new mf::Motor_PWM(&(TIM2->CCR3), 1000)), 8 | motor3(*new mf::Motor_PWM(&(TIM4->CCR1), 1000)), 9 | motor4(*new mf::Motor_PWM(&(TIM4->CCR2), 1000)), 10 | message(*new mf::Message_usart(&huart1)), 11 | debug(*new mf::Message_usb()), 12 | led2(*new mf::LED_IO_L(GPIOA, GPIO_PIN_7)), 13 | led1(*new mf::LED_IO_L(GPIOA, GPIO_PIN_6)), 14 | led3(*new mf::LED_IO_H(GPIOB, GPIO_PIN_12)), 15 | led4(*new mf::LED_IO_L(GPIOC, GPIO_PIN_13)), 16 | led5(*new mf::LED_IO_L(GPIOC, GPIO_PIN_14)), 17 | pid_pitch_a(0.2f, 0.00f, 0.01f, 0.1f), 18 | pid_roll_a(0.2f, 0.00f, 0.01f, 0.1f), 19 | pid_yaw_a(0.2f, 0.00f, 0.01f, 0.1f) 20 | 21 | { 22 | this->status_pid = false; 23 | this->status_led1 = false; 24 | this->status_led2 = false; 25 | this->status_led3 = false; 26 | this->status_led4 = false; 27 | this->status_led5 = false; 28 | this->status_sendinfo = false; 29 | this->status_debug = false; 30 | this->status_flight = false; 31 | 32 | this->target_speed = 0.0f; 33 | this->target_yaw = 0.0f; 34 | this->target_pitch = 0.0f; 35 | this->target_roll = 0.0f; 36 | } 37 | 38 | 39 | mf::Flight flight; -------------------------------------------------------------------------------- /MyFlight/hal.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "base.hpp" 4 | 5 | namespace mf 6 | { 7 | class Sensor{ 8 | 9 | public: 10 | 11 | f32 yaw, 12 | roll, 13 | pitch, 14 | altitude, 15 | temperature, 16 | humidity, 17 | longitude, 18 | latitude; 19 | 20 | virtual void init() = 0; 21 | 22 | virtual void update(f32 dt_ = 0.0f) = 0; 23 | 24 | }; 25 | 26 | 27 | class Motor{ 28 | 29 | public: 30 | 31 | virtual void init() = 0; 32 | 33 | virtual void enabled() = 0; 34 | 35 | virtual void disabled() = 0; 36 | 37 | virtual void turn(f32) const = 0; 38 | 39 | }; 40 | 41 | 42 | class Message{ 43 | 44 | public: 45 | 46 | u8 buff; 47 | s8 buff_count; 48 | 49 | virtual void init() = 0; 50 | 51 | virtual s32 send(void*, s32) = 0; 52 | 53 | virtual s32 recv(void*, s32) = 0; 54 | 55 | virtual void handle(){}; 56 | 57 | virtual void ithandle(){}; 58 | 59 | }; 60 | 61 | 62 | class LED{ 63 | 64 | public: 65 | 66 | virtual void off() const = 0; 67 | 68 | virtual void on() const = 0; 69 | 70 | virtual void reversal() const = 0; 71 | 72 | }; 73 | } -------------------------------------------------------------------------------- /MyFlight/flight.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | 4 | #include "Hardware.hpp" 5 | #include "pid.hpp" 6 | #include "interface.hpp" 7 | #include "board.h" 8 | 9 | namespace mf 10 | { 11 | class Flight{ 12 | 13 | public: 14 | 15 | enum ORDER : u8{ 16 | 17 | ORDER_NULL = 0XFF, 18 | 19 | ORDER_PID=0xFE, 20 | ORDER_SENDINFO=0xFD, 21 | ORDER_DEBUG=0xFC, 22 | 23 | ORDER_LED1=249, 24 | ORDER_LED2=248, 25 | ORDER_LED3=247, 26 | ORDER_LED4=246, 27 | ORDER_LED5=245, 28 | 29 | ORDER_LEFT_Y_ZERO=25, 30 | ORDER_LEFT_X_ZERO=76, 31 | ORDER_RIGHT_Y_ZERO=127, 32 | ORDER_RIGHT_X_ZERO=178 33 | 34 | }; 35 | 36 | mf::Sensor& sensor; 37 | 38 | mf::Motor& motor1; 39 | mf::Motor& motor2; 40 | mf::Motor& motor3; 41 | mf::Motor& motor4; 42 | 43 | mf::Message& message; 44 | mf::Message& debug; 45 | 46 | mf::LED& led1; 47 | mf::LED& led2; 48 | mf::LED& led3; 49 | mf::LED& led4; 50 | mf::LED& led5; 51 | 52 | f32 speed_max; 53 | 54 | f32 target_roll, target_yaw, target_pitch, target_speed; 55 | 56 | bool status_pid; 57 | bool status_led1; 58 | bool status_led2; 59 | bool status_led3; 60 | bool status_led4; 61 | bool status_led5; 62 | bool status_sendinfo; 63 | bool status_debug; 64 | bool status_flight; 65 | 66 | my::pid_pos pid_roll_a; 67 | my::pid_pos pid_pitch_a; 68 | my::pid_pos pid_yaw_a; 69 | 70 | explicit Flight(); 71 | }; 72 | } 73 | 74 | extern mf::Flight flight; -------------------------------------------------------------------------------- /Hardware/Sensor_mpu9250.cpp: -------------------------------------------------------------------------------- 1 | #include "Sensor_mpu9250.hpp" 2 | 3 | #include "mpu9250.h" 4 | 5 | #include "common.hpp" 6 | 7 | typedef struct 8 | { 9 | unsigned char reg; 10 | unsigned char data; 11 | }element; 12 | 13 | static element commands[] = { 14 | {MPU_PWR_MGMT1_REG, 0x80u}, //复位 15 | {MPU_PWR_MGMT1_REG, 0x00u}, //唤醒 16 | {MPU_GYRO_CFG_REG, 0x18u}, //设置陀螺仪满量程 17 | {MPU_ACCEL_CFG_REG, 0x00u}, //设置加速度计满量程 18 | {MPU_SAMPLE_RATE_REG, 0x00u}, //设置采样率1000hz 19 | {MPU_CFG_REG, 0x05u}, //设置陀螺仪低通滤波器 20 | {MPU_ACCEL_CFG_REG2, 0x03u}, //设置加速度计低通滤波器 21 | {MPU_INT_EN_REG, 0x00u}, //关闭所有中断 22 | {MPU_FIFO_EN_REG, 0x00u}, //关闭FIFO 23 | {MPU_PWR_MGMT1_REG, 0x01u}, //选择X轴陀螺PLL作为时钟源 24 | {MPU_PWR_MGMT2_REG, 0x00u}, //使能工作 25 | }; 26 | 27 | mf::Sensor_mpu9250::Sensor_mpu9250(I2C_HandleTypeDef* hi2c_, u16 addr_):hi2c(hi2c_), addr(addr_){ 28 | 29 | } 30 | 31 | 32 | void mf::Sensor_mpu9250::init(){ 33 | 34 | int i = 0; 35 | for(; iorg_ax = (s16)buff[0] << 8 | buff[1]; 46 | this->org_ay = (s16)buff[2] << 8 | buff[3]; 47 | this->org_az = (s16)buff[4] << 8 | buff[5]; 48 | HAL_I2C_Mem_Read(hi2c,addr,MPU_GYRO_XOUTH_REG,I2C_MEMADD_SIZE_8BIT,buff,6,0xFFFF); 49 | this->org_gx = (s16)buff[0] << 8 | buff[1]; 50 | this->org_gy = (s16)buff[2] << 8 | buff[3]; 51 | this->org_gz = (s16)buff[4] << 8 | buff[5]; 52 | } 53 | 54 | void mf::Sensor_mpu9250::conversionData() 55 | { 56 | this->acc.x = this->org_ax / MPU_ACC_X_COM; 57 | this->acc.y = this->org_ay / MPU_ACC_X_COM; 58 | this->acc.z = this->org_az / MPU_ACC_X_COM; 59 | 60 | this->gyro.x = (this->org_gx / MPU_LSB_2000) / 180.0f * MYPI; 61 | this->gyro.y = (this->org_gy / MPU_LSB_2000) / 180.0f * MYPI; 62 | this->gyro.z = (this->org_gz / MPU_LSB_2000) / 180.0f * MYPI; 63 | } 64 | 65 | void mf::Sensor_mpu9250::update(f32 dt_){ 66 | 67 | this->updateOrgData(); 68 | 69 | this->conversionData(); 70 | 71 | vec3f out; 72 | 73 | out.x = this->roll; 74 | out.y = this->pitch; 75 | out.z = this->yaw; 76 | 77 | mf::PostureCalculate(this->acc, this->gyro, out, dt_, 0.25f); 78 | 79 | this->yaw = out.z; 80 | this->roll = out.x; 81 | this->pitch = out.y; 82 | 83 | // this->yaw += gyro.z; 84 | // this->roll += gyro.x; 85 | // this->pitch += gyro.y; 86 | } 87 | 88 | void mf::Sensor_mpu9250::debug(f32 dt) 89 | { 90 | this->updateOrgData(); 91 | this->conversionData(); 92 | 93 | this->yaw = atanf(acc.y / acc.z); 94 | } -------------------------------------------------------------------------------- /Hardware/mpu9250.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #define MPU9250_ADDR 0XD2u 4 | 5 | //MPU6500的内部寄存器 6 | #define MPU_SELF_TESTX_REG 0X0D //自检寄存器X 7 | #define MPU_SELF_TESTY_REG 0X0E //自检寄存器Y 8 | #define MPU_SELF_TESTZ_REG 0X0F //自检寄存器Z 9 | #define MPU_SELF_TESTA_REG 0X10 //自检寄存器A 10 | #define MPU_SAMPLE_RATE_REG 0X19 //采样频率分频器 11 | #define MPU_CFG_REG 0X1A //配置寄存器 12 | #define MPU_GYRO_CFG_REG 0X1B //陀螺仪配置寄存器 13 | #define MPU_ACCEL_CFG_REG 0X1C //加速度计配置寄存器 14 | #define MPU_ACCEL_CFG_REG2 0X1D //加速度计配置寄存器 15 | #define MPU_MOTION_DET_REG 0X1F //运动检测阀值设置寄存器 16 | #define MPU_FIFO_EN_REG 0X23 //FIFO使能寄存器 17 | #define MPU_I2CMST_CTRL_REG 0X24 //IIC主机控制寄存器 18 | #define MPU_I2CSLV0_ADDR_REG 0X25 //IIC从机0器件地址寄存器 19 | #define MPU_I2CSLV0_REG 0X26 //IIC从机0数据地址寄存器 20 | #define MPU_I2CSLV0_CTRL_REG 0X27 //IIC从机0控制寄存器 21 | #define MPU_I2CSLV1_ADDR_REG 0X28 //IIC从机1器件地址寄存器 22 | #define MPU_I2CSLV1_REG 0X29 //IIC从机1数据地址寄存器 23 | #define MPU_I2CSLV1_CTRL_REG 0X2A //IIC从机1控制寄存器 24 | #define MPU_I2CSLV2_ADDR_REG 0X2B //IIC从机2器件地址寄存器 25 | #define MPU_I2CSLV2_REG 0X2C //IIC从机2数据地址寄存器 26 | #define MPU_I2CSLV2_CTRL_REG 0X2D //IIC从机2控制寄存器 27 | #define MPU_I2CSLV3_ADDR_REG 0X2E //IIC从机3器件地址寄存器 28 | #define MPU_I2CSLV3_REG 0X2F //IIC从机3数据地址寄存器 29 | #define MPU_I2CSLV3_CTRL_REG 0X30 //IIC从机3控制寄存器 30 | #define MPU_I2CSLV4_ADDR_REG 0X31 //IIC从机4器件地址寄存器 31 | #define MPU_I2CSLV4_REG 0X32 //IIC从机4数据地址寄存器 32 | #define MPU_I2CSLV4_DO_REG 0X33 //IIC从机4写数据寄存器 33 | #define MPU_I2CSLV4_CTRL_REG 0X34 //IIC从机4控制寄存器 34 | #define MPU_I2CSLV4_DI_REG 0X35 //IIC从机4读数据寄存器 35 | 36 | #define MPU_I2CMST_STA_REG 0X36 //IIC主机状态寄存器 37 | #define MPU_INTBP_CFG_REG 0X37 //中断/旁路设置寄存器 38 | #define MPU_INT_EN_REG 0X38 //中断使能寄存器 39 | #define MPU_INT_STA_REG 0X3A //中断状态寄存器 40 | 41 | #define MPU_ACCEL_XOUTH_REG 0X3B //加速度值,X轴高8位寄存器 42 | #define MPU_ACCEL_XOUTL_REG 0X3C //加速度值,X轴低8位寄存器 43 | #define MPU_ACCEL_YOUTH_REG 0X3D //加速度值,Y轴高8位寄存器 44 | #define MPU_ACCEL_YOUTL_REG 0X3E //加速度值,Y轴低8位寄存器 45 | #define MPU_ACCEL_ZOUTH_REG 0X3F //加速度值,Z轴高8位寄存器 46 | #define MPU_ACCEL_ZOUTL_REG 0X40 //加速度值,Z轴低8位寄存器 47 | 48 | #define MPU_TEMP_OUTH_REG 0X41 //温度值高八位寄存器 49 | #define MPU_TEMP_OUTL_REG 0X42 //温度值低8位寄存器 50 | 51 | #define MPU_GYRO_XOUTH_REG 0X43 //陀螺仪值,X轴高8位寄存器 52 | #define MPU_GYRO_XOUTL_REG 0X44 //陀螺仪值,X轴低8位寄存器 53 | #define MPU_GYRO_YOUTH_REG 0X45 //陀螺仪值,Y轴高8位寄存器 54 | #define MPU_GYRO_YOUTL_REG 0X46 //陀螺仪值,Y轴低8位寄存器 55 | #define MPU_GYRO_ZOUTH_REG 0X47 //陀螺仪值,Z轴高8位寄存器 56 | #define MPU_GYRO_ZOUTL_REG 0X48 //陀螺仪值,Z轴低8位寄存器 57 | 58 | #define MPU_I2CSLV0_DO_REG 0X63 //IIC从机0数据寄存器 59 | #define MPU_I2CSLV1_DO_REG 0X64 //IIC从机1数据寄存器 60 | #define MPU_I2CSLV2_DO_REG 0X65 //IIC从机2数据寄存器 61 | #define MPU_I2CSLV3_DO_REG 0X66 //IIC从机3数据寄存器 62 | 63 | #define MPU_I2CMST_DELAY_REG 0X67 //IIC主机延时管理寄存器 64 | #define MPU_SIGPATH_RST_REG 0X68 //信号通道复位寄存器 65 | #define MPU_MDETECT_CTRL_REG 0X69 //运动检测控制寄存器 66 | #define MPU_USER_CTRL_REG 0X6A //用户控制寄存器 67 | #define MPU_PWR_MGMT1_REG 0X6B //电源管理寄存器1 68 | #define MPU_PWR_MGMT2_REG 0X6C //电源管理寄存器2 69 | #define MPU_FIFO_CNTH_REG 0X72 //FIFO计数寄存器高八位 70 | #define MPU_FIFO_CNTL_REG 0X73 //FIFO计数寄存器低八位 71 | #define MPU_FIFO_RW_REG 0X74 //FIFO读写寄存器 72 | #define MPU_DEVICE_ID_REG 0X75 //器件ID寄存 73 | 74 | #define MPU_LSB_2000 16.4f 75 | #define MPU_ACC_X_COM 16384.0f -------------------------------------------------------------------------------- /MyFlight/task.cpp: -------------------------------------------------------------------------------- 1 | #include "Flight.hpp" 2 | 3 | #include "cstring" 4 | #include "cstdio" 5 | 6 | using namespace mf; 7 | 8 | f32 debug_1 = 0.0f; 9 | 10 | 11 | extern "C" void StartTaskSensorMotor(void *argument) 12 | { 13 | flight.sensor.init(); 14 | flight.motor1.init(); 15 | flight.motor2.init(); 16 | flight.motor3.init(); 17 | flight.motor4.init(); 18 | 19 | f32 m1 = 0.0f, m2 = 0.0f, m3 = 0.0f, m4 = 0.0f; 20 | 21 | f32 roll = 0.0f, pitch = 0.0f, yaw = 0.0f; 22 | 23 | my::pid pid; 24 | 25 | flight.speed_max = 0.60f; 26 | 27 | while(true){ 28 | 29 | flight.sensor.update(0.002f); 30 | 31 | if(flight.status_pid){ 32 | 33 | roll = pid(0.0f, flight.sensor.roll, flight.pid_roll_a); 34 | pitch = pid(0.0f, flight.sensor.pitch, flight.pid_pitch_a); 35 | yaw = pid(0.0f, flight.sensor.yaw, flight.pid_yaw_a); 36 | 37 | m1 = flight.target_speed + roll - pitch; 38 | m2 = flight.target_speed + roll + pitch; 39 | m3 = flight.target_speed - roll + pitch; 40 | m4 = flight.target_speed - roll - pitch; 41 | 42 | if(m1 > flight.speed_max)m1 = flight.speed_max; 43 | if(m2 > flight.speed_max)m2 = flight.speed_max; 44 | if(m3 > flight.speed_max)m3 = flight.speed_max; 45 | if(m4 > flight.speed_max)m4 = flight.speed_max; 46 | } 47 | else{ 48 | m1 = 0.0f; 49 | m2 = 0.0f; 50 | m3 = 0.0f; 51 | m4 = 0.0f; 52 | } 53 | 54 | flight.motor1.turn(m1); 55 | flight.motor2.turn(m2); 56 | flight.motor3.turn(m3); 57 | flight.motor4.turn(m4); 58 | 59 | debug_1 = flight.target_speed; 60 | 61 | osDelay(2); 62 | } 63 | } 64 | 65 | 66 | extern "C" void StartTaskDebug(void *argument) 67 | { 68 | s8 str[50]; 69 | 70 | //mf::Sensor_mpu9250 sensor(&hi2c1, 0XD2u); 71 | 72 | while(true){ 73 | 74 | if(flight.status_debug){ 75 | 76 | std::sprintf(str,"%5.5f %5.5f %5.5f\r\n",flight.sensor.roll, flight.sensor.pitch, debug_1); 77 | 78 | flight.debug.send(str, std::strlen(str)); 79 | } 80 | 81 | osDelay(100); 82 | } 83 | } 84 | 85 | extern "C" void StartTaskLED(void *argument) 86 | { 87 | 88 | while(true){ 89 | 90 | if(flight.status_led1){ 91 | flight.led1.reversal(); 92 | } 93 | if(flight.status_led2){ 94 | flight.led2.reversal(); 95 | } 96 | if(flight.status_led3){ 97 | flight.led3.reversal(); 98 | } 99 | if(flight.status_led4){ 100 | flight.led4.reversal(); 101 | } 102 | if(flight.status_led5){ 103 | flight.led5.reversal(); 104 | } 105 | 106 | //flight.led4.reversal(); 107 | //flight.led5.reversal(); 108 | 109 | osDelay(100); 110 | } 111 | } 112 | 113 | extern "C" void StartTaskMessage(void* argument) 114 | { 115 | flight.message.init(); 116 | 117 | s8 str[50]; 118 | 119 | while(true){ 120 | 121 | if( flight.message.buff>=0 && flight.message.buff<=50){ 122 | 123 | flight.target_speed = (flight.message.buff - Flight::ORDER_LEFT_Y_ZERO) / 25.0f; 124 | 125 | }else if( flight.message.buff>=51 && flight.message.buff<=101){ 126 | 127 | flight.target_yaw = (flight.message.buff - Flight::ORDER_LEFT_X_ZERO) / 25.0f; 128 | 129 | }else if( flight.message.buff>=102 && flight.message.buff<=152){ 130 | 131 | flight.target_roll = (flight.message.buff - Flight::ORDER_RIGHT_Y_ZERO) / 25.0f; 132 | 133 | }else if( flight.message.buff>=153 && flight.message.buff<=203){ 134 | 135 | flight.target_pitch = (flight.message.buff - Flight::ORDER_RIGHT_X_ZERO) / 25.0f; 136 | 137 | }else if( flight.message.buff>=204 && flight.message.buff<=255 && flight.message.buff_count > 0){ 138 | 139 | switch(flight.message.buff){ 140 | 141 | case Flight::ORDER_LED1: 142 | flight.led1.reversal(); 143 | break; 144 | 145 | case Flight::ORDER_LED2: 146 | flight.led2.reversal(); 147 | break; 148 | 149 | case Flight::ORDER_LED3: 150 | flight.status_led3 = !flight.status_led3; 151 | break; 152 | 153 | case Flight::ORDER_LED4: 154 | flight.status_led4 = !flight.status_led4; 155 | break; 156 | 157 | /*case Flight::ORDER_LED5: 158 | flight.led5.reversal(); 159 | break;*/ 160 | 161 | case Flight::ORDER_SENDINFO: 162 | flight.status_sendinfo = !flight.status_sendinfo; 163 | break; 164 | 165 | case Flight::ORDER_PID: 166 | flight.status_pid = !flight.status_pid; 167 | break; 168 | 169 | case Flight::ORDER_DEBUG: 170 | flight.status_debug = !flight.status_debug; 171 | break; 172 | 173 | 174 | default: 175 | break; 176 | } 177 | 178 | --flight.message.buff_count; 179 | 180 | } 181 | 182 | if(flight.status_sendinfo){ 183 | sprintf(str, "roll: %2.2f, pitch: %2.2f, yaw: %2.2f\r\n", flight.sensor.roll, flight.sensor.pitch, flight.sensor.yaw); 184 | flight.message.send(str, std::strlen(str)); 185 | } 186 | 187 | osDelay(10); 188 | } 189 | } 190 | 191 | extern "C" void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) 192 | { 193 | if(huart->Instance == USART1){ 194 | 195 | ++flight.message.buff_count; 196 | 197 | HAL_UART_Receive_IT(&huart1, (uint8_t *)&flight.message.buff, 1); 198 | } 199 | } -------------------------------------------------------------------------------- /Board/Core/Src/main.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : main.c 5 | * @brief : Main program body 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2020 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | 21 | /* Includes ------------------------------------------------------------------*/ 22 | #include "main.h" 23 | #include "cmsis_os.h" 24 | #include "i2c.h" 25 | #include "tim.h" 26 | #include "usart.h" 27 | #include "usb_device.h" 28 | #include "gpio.h" 29 | 30 | /* Private includes ----------------------------------------------------------*/ 31 | /* USER CODE BEGIN Includes */ 32 | 33 | /* USER CODE END Includes */ 34 | 35 | /* Private typedef -----------------------------------------------------------*/ 36 | /* USER CODE BEGIN PTD */ 37 | 38 | /* USER CODE END PTD */ 39 | 40 | /* Private define ------------------------------------------------------------*/ 41 | /* USER CODE BEGIN PD */ 42 | /* USER CODE END PD */ 43 | 44 | /* Private macro -------------------------------------------------------------*/ 45 | /* USER CODE BEGIN PM */ 46 | 47 | /* USER CODE END PM */ 48 | 49 | /* Private variables ---------------------------------------------------------*/ 50 | 51 | /* USER CODE BEGIN PV */ 52 | 53 | /* USER CODE END PV */ 54 | 55 | /* Private function prototypes -----------------------------------------------*/ 56 | void SystemClock_Config(void); 57 | void MX_FREERTOS_Init(void); 58 | /* USER CODE BEGIN PFP */ 59 | 60 | /* USER CODE END PFP */ 61 | 62 | /* Private user code ---------------------------------------------------------*/ 63 | /* USER CODE BEGIN 0 */ 64 | 65 | /* USER CODE END 0 */ 66 | 67 | /** 68 | * @brief The application entry point. 69 | * @retval int 70 | */ 71 | int main(void) 72 | { 73 | /* USER CODE BEGIN 1 */ 74 | 75 | /* USER CODE END 1 */ 76 | 77 | /* MCU Configuration--------------------------------------------------------*/ 78 | 79 | /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ 80 | HAL_Init(); 81 | 82 | /* USER CODE BEGIN Init */ 83 | 84 | /* USER CODE END Init */ 85 | 86 | /* Configure the system clock */ 87 | SystemClock_Config(); 88 | 89 | /* USER CODE BEGIN SysInit */ 90 | 91 | /* USER CODE END SysInit */ 92 | 93 | /* Initialize all configured peripherals */ 94 | MX_GPIO_Init(); 95 | MX_I2C1_Init(); 96 | MX_TIM2_Init(); 97 | MX_TIM4_Init(); 98 | MX_USART1_UART_Init(); 99 | /* USER CODE BEGIN 2 */ 100 | 101 | HAL_TIM_PWM_Start(&htim2, TIM_CHANNEL_1); 102 | HAL_TIM_PWM_Start(&htim2, TIM_CHANNEL_3); 103 | HAL_TIM_PWM_Start(&htim4, TIM_CHANNEL_1); 104 | HAL_TIM_PWM_Start(&htim4, TIM_CHANNEL_2); 105 | 106 | /* USER CODE END 2 */ 107 | 108 | /* Init scheduler */ 109 | osKernelInitialize(); /* Call init function for freertos objects (in freertos.c) */ 110 | MX_FREERTOS_Init(); 111 | /* Start scheduler */ 112 | osKernelStart(); 113 | 114 | /* We should never get here as control is now taken by the scheduler */ 115 | /* Infinite loop */ 116 | /* USER CODE BEGIN WHILE */ 117 | while (1) 118 | { 119 | /* USER CODE END WHILE */ 120 | 121 | /* USER CODE BEGIN 3 */ 122 | } 123 | /* USER CODE END 3 */ 124 | } 125 | 126 | /** 127 | * @brief System Clock Configuration 128 | * @retval None 129 | */ 130 | void SystemClock_Config(void) 131 | { 132 | RCC_OscInitTypeDef RCC_OscInitStruct = {0}; 133 | RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; 134 | 135 | /** Configure the main internal regulator output voltage 136 | */ 137 | __HAL_RCC_PWR_CLK_ENABLE(); 138 | __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); 139 | /** Initializes the CPU, AHB and APB busses clocks 140 | */ 141 | RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; 142 | RCC_OscInitStruct.HSEState = RCC_HSE_ON; 143 | RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; 144 | RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; 145 | RCC_OscInitStruct.PLL.PLLM = 8; 146 | RCC_OscInitStruct.PLL.PLLN = 192; 147 | RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; 148 | RCC_OscInitStruct.PLL.PLLQ = 4; 149 | if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) 150 | { 151 | Error_Handler(); 152 | } 153 | /** Initializes the CPU, AHB and APB busses clocks 154 | */ 155 | RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK 156 | |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; 157 | RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; 158 | RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; 159 | RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; 160 | RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; 161 | 162 | if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3) != HAL_OK) 163 | { 164 | Error_Handler(); 165 | } 166 | } 167 | 168 | /* USER CODE BEGIN 4 */ 169 | 170 | /* USER CODE END 4 */ 171 | 172 | /** 173 | * @brief Period elapsed callback in non blocking mode 174 | * @note This function is called when TIM10 interrupt took place, inside 175 | * HAL_TIM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment 176 | * a global variable "uwTick" used as application time base. 177 | * @param htim : TIM handle 178 | * @retval None 179 | */ 180 | void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) 181 | { 182 | /* USER CODE BEGIN Callback 0 */ 183 | 184 | /* USER CODE END Callback 0 */ 185 | if (htim->Instance == TIM10) { 186 | HAL_IncTick(); 187 | } 188 | /* USER CODE BEGIN Callback 1 */ 189 | 190 | /* USER CODE END Callback 1 */ 191 | } 192 | 193 | /** 194 | * @brief This function is executed in case of error occurrence. 195 | * @retval None 196 | */ 197 | void Error_Handler(void) 198 | { 199 | /* USER CODE BEGIN Error_Handler_Debug */ 200 | /* User can add his own implementation to report the HAL error return state */ 201 | 202 | /* USER CODE END Error_Handler_Debug */ 203 | } 204 | 205 | #ifdef USE_FULL_ASSERT 206 | /** 207 | * @brief Reports the name of the source file and the source line number 208 | * where the assert_param error has occurred. 209 | * @param file: pointer to the source file name 210 | * @param line: assert_param error line source number 211 | * @retval None 212 | */ 213 | void assert_failed(uint8_t *file, uint32_t line) 214 | { 215 | /* USER CODE BEGIN 6 */ 216 | /* User can add his own implementation to report the file name and line number, 217 | tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */ 218 | /* USER CODE END 6 */ 219 | } 220 | #endif /* USE_FULL_ASSERT */ 221 | 222 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 223 | -------------------------------------------------------------------------------- /Board/Core/Src/freertos.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * File Name : freertos.c 5 | * Description : Code for freertos applications 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2020 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | 21 | /* Includes ------------------------------------------------------------------*/ 22 | #include "FreeRTOS.h" 23 | #include "task.h" 24 | #include "main.h" 25 | #include "cmsis_os.h" 26 | 27 | /* Private includes ----------------------------------------------------------*/ 28 | /* USER CODE BEGIN Includes */ 29 | 30 | /* USER CODE END Includes */ 31 | 32 | /* Private typedef -----------------------------------------------------------*/ 33 | /* USER CODE BEGIN PTD */ 34 | 35 | /* USER CODE END PTD */ 36 | 37 | /* Private define ------------------------------------------------------------*/ 38 | /* USER CODE BEGIN PD */ 39 | 40 | /* USER CODE END PD */ 41 | 42 | /* Private macro -------------------------------------------------------------*/ 43 | /* USER CODE BEGIN PM */ 44 | 45 | /* USER CODE END PM */ 46 | 47 | /* Private variables ---------------------------------------------------------*/ 48 | /* USER CODE BEGIN Variables */ 49 | 50 | /* USER CODE END Variables */ 51 | /* Definitions for defaultTask */ 52 | osThreadId_t defaultTaskHandle; 53 | const osThreadAttr_t defaultTask_attributes = { 54 | .name = "defaultTask", 55 | .priority = (osPriority_t) osPriorityLow, 56 | .stack_size = 128 * 4 57 | }; 58 | /* Definitions for TaskSensorMotor */ 59 | osThreadId_t TaskSensorMotorHandle; 60 | const osThreadAttr_t TaskSensorMotor_attributes = { 61 | .name = "TaskSensorMotor", 62 | .priority = (osPriority_t) osPriorityHigh, 63 | .stack_size = 1024 * 4 64 | }; 65 | /* Definitions for TaskDebug */ 66 | osThreadId_t TaskDebugHandle; 67 | const osThreadAttr_t TaskDebug_attributes = { 68 | .name = "TaskDebug", 69 | .priority = (osPriority_t) osPriorityLow, 70 | .stack_size = 512 * 4 71 | }; 72 | /* Definitions for TaskLED */ 73 | osThreadId_t TaskLEDHandle; 74 | const osThreadAttr_t TaskLED_attributes = { 75 | .name = "TaskLED", 76 | .priority = (osPriority_t) osPriorityLow, 77 | .stack_size = 512 * 4 78 | }; 79 | /* Definitions for TaskMessage */ 80 | osThreadId_t TaskMessageHandle; 81 | const osThreadAttr_t TaskMessage_attributes = { 82 | .name = "TaskMessage", 83 | .priority = (osPriority_t) osPriorityRealtime, 84 | .stack_size = 512 * 4 85 | }; 86 | 87 | /* Private function prototypes -----------------------------------------------*/ 88 | /* USER CODE BEGIN FunctionPrototypes */ 89 | 90 | /* USER CODE END FunctionPrototypes */ 91 | 92 | void StartDefaultTask(void *argument); 93 | void StartTaskSensorMotor(void *argument); 94 | void StartTaskDebug(void *argument); 95 | void StartTaskLED(void *argument); 96 | void StartTaskMessage(void *argument); 97 | 98 | extern void MX_USB_DEVICE_Init(void); 99 | void MX_FREERTOS_Init(void); /* (MISRA C 2004 rule 8.1) */ 100 | 101 | /** 102 | * @brief FreeRTOS initialization 103 | * @param None 104 | * @retval None 105 | */ 106 | void MX_FREERTOS_Init(void) { 107 | /* USER CODE BEGIN Init */ 108 | 109 | /* USER CODE END Init */ 110 | 111 | /* USER CODE BEGIN RTOS_MUTEX */ 112 | /* add mutexes, ... */ 113 | /* USER CODE END RTOS_MUTEX */ 114 | 115 | /* USER CODE BEGIN RTOS_SEMAPHORES */ 116 | /* add semaphores, ... */ 117 | /* USER CODE END RTOS_SEMAPHORES */ 118 | 119 | /* USER CODE BEGIN RTOS_TIMERS */ 120 | /* start timers, add new ones, ... */ 121 | /* USER CODE END RTOS_TIMERS */ 122 | 123 | /* USER CODE BEGIN RTOS_QUEUES */ 124 | /* add queues, ... */ 125 | /* USER CODE END RTOS_QUEUES */ 126 | 127 | /* Create the thread(s) */ 128 | /* creation of defaultTask */ 129 | defaultTaskHandle = osThreadNew(StartDefaultTask, NULL, &defaultTask_attributes); 130 | 131 | /* creation of TaskSensorMotor */ 132 | TaskSensorMotorHandle = osThreadNew(StartTaskSensorMotor, NULL, &TaskSensorMotor_attributes); 133 | 134 | /* creation of TaskDebug */ 135 | TaskDebugHandle = osThreadNew(StartTaskDebug, NULL, &TaskDebug_attributes); 136 | 137 | /* creation of TaskLED */ 138 | TaskLEDHandle = osThreadNew(StartTaskLED, NULL, &TaskLED_attributes); 139 | 140 | /* creation of TaskMessage */ 141 | TaskMessageHandle = osThreadNew(StartTaskMessage, NULL, &TaskMessage_attributes); 142 | 143 | /* USER CODE BEGIN RTOS_THREADS */ 144 | /* add threads, ... */ 145 | /* USER CODE END RTOS_THREADS */ 146 | 147 | } 148 | 149 | /* USER CODE BEGIN Header_StartDefaultTask */ 150 | /** 151 | * @brief Function implementing the defaultTask thread. 152 | * @param argument: Not used 153 | * @retval None 154 | */ 155 | /* USER CODE END Header_StartDefaultTask */ 156 | __weak void StartDefaultTask(void *argument) 157 | { 158 | /* init code for USB_DEVICE */ 159 | MX_USB_DEVICE_Init(); 160 | /* USER CODE BEGIN StartDefaultTask */ 161 | osThreadTerminate(defaultTaskHandle); 162 | /* Infinite loop */ 163 | for(;;) 164 | { 165 | osDelay(1); 166 | } 167 | /* USER CODE END StartDefaultTask */ 168 | } 169 | 170 | /* USER CODE BEGIN Header_StartTaskSensorMotor */ 171 | /** 172 | * @brief Function implementing the TaskSensorMotor thread. 173 | * @param argument: Not used 174 | * @retval None 175 | */ 176 | /* USER CODE END Header_StartTaskSensorMotor */ 177 | __weak void StartTaskSensorMotor(void *argument) 178 | { 179 | /* USER CODE BEGIN StartTaskSensorMotor */ 180 | /* Infinite loop */ 181 | for(;;) 182 | { 183 | osDelay(1); 184 | } 185 | /* USER CODE END StartTaskSensorMotor */ 186 | } 187 | 188 | /* USER CODE BEGIN Header_StartTaskDebug */ 189 | /** 190 | * @brief Function implementing the TaskDebug thread. 191 | * @param argument: Not used 192 | * @retval None 193 | */ 194 | /* USER CODE END Header_StartTaskDebug */ 195 | __weak void StartTaskDebug(void *argument) 196 | { 197 | /* USER CODE BEGIN StartTaskDebug */ 198 | /* Infinite loop */ 199 | for(;;) 200 | { 201 | osDelay(1); 202 | } 203 | /* USER CODE END StartTaskDebug */ 204 | } 205 | 206 | /* USER CODE BEGIN Header_StartTaskLED */ 207 | /** 208 | * @brief Function implementing the TaskLED thread. 209 | * @param argument: Not used 210 | * @retval None 211 | */ 212 | /* USER CODE END Header_StartTaskLED */ 213 | __weak void StartTaskLED(void *argument) 214 | { 215 | /* USER CODE BEGIN StartTaskLED */ 216 | /* Infinite loop */ 217 | for(;;) 218 | { 219 | osDelay(1); 220 | } 221 | /* USER CODE END StartTaskLED */ 222 | } 223 | 224 | /* USER CODE BEGIN Header_StartTaskMessage */ 225 | /** 226 | * @brief Function implementing the TaskMessage thread. 227 | * @param argument: Not used 228 | * @retval None 229 | */ 230 | /* USER CODE END Header_StartTaskMessage */ 231 | __weak void StartTaskMessage(void *argument) 232 | { 233 | /* USER CODE BEGIN StartTaskMessage */ 234 | /* Infinite loop */ 235 | for(;;) 236 | { 237 | osDelay(1); 238 | } 239 | /* USER CODE END StartTaskMessage */ 240 | } 241 | 242 | /* Private application code --------------------------------------------------*/ 243 | /* USER CODE BEGIN Application */ 244 | 245 | /* USER CODE END Application */ 246 | 247 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 248 | -------------------------------------------------------------------------------- /Board/myflight.ioc: -------------------------------------------------------------------------------- 1 | #MicroXplorer Configuration settings - do not modify 2 | FREERTOS.FootprintOK=true 3 | FREERTOS.IPParameters=Tasks01,FootprintOK,configENABLE_FPU 4 | FREERTOS.Tasks01=defaultTask,8,128,StartDefaultTask,As weak,NULL,Dynamic,NULL,NULL;TaskSensorMotor,40,1024,StartTaskSensorMotor,As weak,NULL,Dynamic,NULL,NULL;TaskDebug,8,512,StartTaskDebug,As weak,NULL,Dynamic,NULL,NULL;TaskLED,8,512,StartTaskLED,As weak,NULL,Dynamic,NULL,NULL;TaskMessage,48,512,StartTaskMessage,As weak,NULL,Dynamic,NULL,NULL 5 | FREERTOS.configENABLE_FPU=1 6 | File.Version=6 7 | GPIO.groupedBy=Group By Peripherals 8 | I2C1.I2C_Mode=I2C_Standard 9 | I2C1.IPParameters=I2C_Mode 10 | KeepUserPlacement=false 11 | Mcu.Family=STM32F4 12 | Mcu.IP0=FREERTOS 13 | Mcu.IP1=I2C1 14 | Mcu.IP2=NVIC 15 | Mcu.IP3=RCC 16 | Mcu.IP4=SYS 17 | Mcu.IP5=TIM2 18 | Mcu.IP6=TIM4 19 | Mcu.IP7=USART1 20 | Mcu.IP8=USB_DEVICE 21 | Mcu.IP9=USB_OTG_FS 22 | Mcu.IPNb=10 23 | Mcu.Name=STM32F411C(C-E)Ux 24 | Mcu.Package=UFQFPN48 25 | Mcu.Pin0=PC13-ANTI_TAMP 26 | Mcu.Pin1=PC14-OSC32_IN 27 | Mcu.Pin10=PA12 28 | Mcu.Pin11=PA15 29 | Mcu.Pin12=PB3 30 | Mcu.Pin13=PB6 31 | Mcu.Pin14=PB7 32 | Mcu.Pin15=PB8 33 | Mcu.Pin16=PB9 34 | Mcu.Pin17=VP_FREERTOS_VS_CMSIS_V2 35 | Mcu.Pin18=VP_SYS_VS_tim10 36 | Mcu.Pin19=VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS 37 | Mcu.Pin2=PH0 - OSC_IN 38 | Mcu.Pin3=PH1 - OSC_OUT 39 | Mcu.Pin4=PA5 40 | Mcu.Pin5=PA6 41 | Mcu.Pin6=PA7 42 | Mcu.Pin7=PB10 43 | Mcu.Pin8=PB12 44 | Mcu.Pin9=PA11 45 | Mcu.PinsNb=20 46 | Mcu.ThirdPartyNb=0 47 | Mcu.UserConstants= 48 | Mcu.UserName=STM32F411CEUx 49 | MxCube.Version=5.6.1 50 | MxDb.Version=DB.5.0.60 51 | NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false 52 | NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false 53 | NVIC.ForceEnableDMAVector=true 54 | NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false 55 | NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false 56 | NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false 57 | NVIC.OTG_FS_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true 58 | NVIC.PendSV_IRQn=true\:15\:0\:false\:false\:false\:true\:false\:false 59 | NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4 60 | NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:false\:false\:false\:false 61 | NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:false\:true\:false\:false 62 | NVIC.TIM1_UP_TIM10_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true 63 | NVIC.TimeBase=TIM1_UP_TIM10_IRQn 64 | NVIC.TimeBaseIP=TIM10 65 | NVIC.USART1_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true 66 | NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false 67 | PA11.Mode=Device_Only 68 | PA11.Signal=USB_OTG_FS_DM 69 | PA12.Mode=Device_Only 70 | PA12.Signal=USB_OTG_FS_DP 71 | PA15.Locked=true 72 | PA15.Mode=Asynchronous 73 | PA15.Signal=USART1_TX 74 | PA5.Locked=true 75 | PA5.Signal=S_TIM2_CH1_ETR 76 | PA6.GPIOParameters=GPIO_Speed,PinState,GPIO_PuPd,GPIO_ModeDefaultOutputPP 77 | PA6.GPIO_ModeDefaultOutputPP=GPIO_MODE_OUTPUT_PP 78 | PA6.GPIO_PuPd=GPIO_PULLDOWN 79 | PA6.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH 80 | PA6.Locked=true 81 | PA6.PinState=GPIO_PIN_SET 82 | PA6.Signal=GPIO_Output 83 | PA7.GPIOParameters=GPIO_Speed,PinState,GPIO_PuPd,GPIO_ModeDefaultOutputPP 84 | PA7.GPIO_ModeDefaultOutputPP=GPIO_MODE_OUTPUT_PP 85 | PA7.GPIO_PuPd=GPIO_PULLDOWN 86 | PA7.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH 87 | PA7.Locked=true 88 | PA7.PinState=GPIO_PIN_SET 89 | PA7.Signal=GPIO_Output 90 | PB10.Locked=true 91 | PB10.Signal=S_TIM2_CH3 92 | PB12.GPIOParameters=GPIO_Speed,PinState,GPIO_PuPd,GPIO_ModeDefaultOutputPP 93 | PB12.GPIO_ModeDefaultOutputPP=GPIO_MODE_OUTPUT_PP 94 | PB12.GPIO_PuPd=GPIO_PULLDOWN 95 | PB12.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH 96 | PB12.Locked=true 97 | PB12.PinState=GPIO_PIN_RESET 98 | PB12.Signal=GPIO_Output 99 | PB3.Locked=true 100 | PB3.Mode=Asynchronous 101 | PB3.Signal=USART1_RX 102 | PB6.Signal=S_TIM4_CH1 103 | PB7.Signal=S_TIM4_CH2 104 | PB8.Locked=true 105 | PB8.Mode=I2C 106 | PB8.Signal=I2C1_SCL 107 | PB9.Locked=true 108 | PB9.Mode=I2C 109 | PB9.Signal=I2C1_SDA 110 | PC13-ANTI_TAMP.GPIOParameters=PinState,GPIO_PuPd,GPIO_ModeDefaultOutputPP 111 | PC13-ANTI_TAMP.GPIO_ModeDefaultOutputPP=GPIO_MODE_OUTPUT_PP 112 | PC13-ANTI_TAMP.GPIO_PuPd=GPIO_PULLDOWN 113 | PC13-ANTI_TAMP.Locked=true 114 | PC13-ANTI_TAMP.PinState=GPIO_PIN_SET 115 | PC13-ANTI_TAMP.Signal=GPIO_Output 116 | PC14-OSC32_IN.GPIOParameters=PinState,GPIO_PuPd,GPIO_ModeDefaultOutputPP 117 | PC14-OSC32_IN.GPIO_ModeDefaultOutputPP=GPIO_MODE_OUTPUT_PP 118 | PC14-OSC32_IN.GPIO_PuPd=GPIO_PULLDOWN 119 | PC14-OSC32_IN.Locked=true 120 | PC14-OSC32_IN.PinState=GPIO_PIN_SET 121 | PC14-OSC32_IN.Signal=GPIO_Output 122 | PH0\ -\ OSC_IN.Mode=HSE-External-Oscillator 123 | PH0\ -\ OSC_IN.Signal=RCC_OSC_IN 124 | PH1\ -\ OSC_OUT.Mode=HSE-External-Oscillator 125 | PH1\ -\ OSC_OUT.Signal=RCC_OSC_OUT 126 | PinOutPanel.RotationAngle=0 127 | ProjectManager.AskForMigrate=true 128 | ProjectManager.BackupPrevious=false 129 | ProjectManager.CompilerOptimize=6 130 | ProjectManager.ComputerToolchain=false 131 | ProjectManager.CoupleFile=true 132 | ProjectManager.CustomerFirmwarePackage= 133 | ProjectManager.DefaultFWLocation=true 134 | ProjectManager.DeletePrevious=true 135 | ProjectManager.DeviceId=STM32F411CEUx 136 | ProjectManager.FirmwarePackage=STM32Cube FW_F4 V1.25.0 137 | ProjectManager.FreePins=false 138 | ProjectManager.HalAssertFull=false 139 | ProjectManager.HeapSize=0x3000 140 | ProjectManager.KeepUserCode=true 141 | ProjectManager.LastFirmware=true 142 | ProjectManager.LibraryCopy=1 143 | ProjectManager.MainLocation=Core/Src 144 | ProjectManager.NoMain=false 145 | ProjectManager.PreviousToolchain= 146 | ProjectManager.ProjectBuild=false 147 | ProjectManager.ProjectFileName=myflight.ioc 148 | ProjectManager.ProjectName=myflight 149 | ProjectManager.StackSize=0x800 150 | ProjectManager.TargetToolchain=MDK-ARM V5.27 151 | ProjectManager.ToolChainLocation= 152 | ProjectManager.UnderRoot=false 153 | ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_I2C1_Init-I2C1-false-HAL-true,4-MX_TIM2_Init-TIM2-false-HAL-true,5-MX_TIM4_Init-TIM4-false-HAL-true,6-MX_USART1_UART_Init-USART1-false-HAL-true,7-MX_USB_DEVICE_Init-USB_DEVICE-false-HAL-false 154 | RCC.48MHZClocksFreq_Value=48000000 155 | RCC.AHBFreq_Value=96000000 156 | RCC.APB1CLKDivider=RCC_HCLK_DIV2 157 | RCC.APB1Freq_Value=48000000 158 | RCC.APB1TimFreq_Value=96000000 159 | RCC.APB2Freq_Value=96000000 160 | RCC.APB2TimFreq_Value=96000000 161 | RCC.CortexFreq_Value=96000000 162 | RCC.EthernetFreq_Value=96000000 163 | RCC.FCLKCortexFreq_Value=96000000 164 | RCC.FamilyName=M 165 | RCC.HCLKFreq_Value=96000000 166 | RCC.HSE_VALUE=8000000 167 | RCC.HSI_VALUE=16000000 168 | RCC.I2SClocksFreq_Value=48000000 169 | RCC.IPParameters=48MHZClocksFreq_Value,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,EthernetFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2SClocksFreq_Value,LSE_VALUE,LSI_VALUE,PLLCLKFreq_Value,PLLM,PLLQCLKFreq_Value,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOInputMFreq_Value,VCOOutputFreq_Value,VcooutputI2S 170 | RCC.LSE_VALUE=32768 171 | RCC.LSI_VALUE=32000 172 | RCC.PLLCLKFreq_Value=96000000 173 | RCC.PLLM=8 174 | RCC.PLLQCLKFreq_Value=48000000 175 | RCC.RTCFreq_Value=32000 176 | RCC.RTCHSEDivFreq_Value=4000000 177 | RCC.SYSCLKFreq_VALUE=96000000 178 | RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK 179 | RCC.VCOI2SOutputFreq_Value=96000000 180 | RCC.VCOInputFreq_Value=1000000 181 | RCC.VCOInputMFreq_Value=500000 182 | RCC.VCOOutputFreq_Value=192000000 183 | RCC.VcooutputI2S=48000000 184 | SH.S_TIM2_CH1_ETR.0=TIM2_CH1,PWM Generation1 CH1 185 | SH.S_TIM2_CH1_ETR.ConfNb=1 186 | SH.S_TIM2_CH3.0=TIM2_CH3,PWM Generation3 CH3 187 | SH.S_TIM2_CH3.ConfNb=1 188 | SH.S_TIM4_CH1.0=TIM4_CH1,PWM Generation1 CH1 189 | SH.S_TIM4_CH1.ConfNb=1 190 | SH.S_TIM4_CH2.0=TIM4_CH2,PWM Generation2 CH2 191 | SH.S_TIM4_CH2.ConfNb=1 192 | TIM2.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1 193 | TIM2.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3 194 | TIM2.IPParameters=Channel-PWM Generation3 CH3,Channel-PWM Generation1 CH1,Prescaler,Period 195 | TIM2.Period=1000 196 | TIM2.Prescaler=96-1 197 | TIM4.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1 198 | TIM4.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2 199 | TIM4.IPParameters=Channel-PWM Generation2 CH2,Channel-PWM Generation1 CH1,Prescaler,Period 200 | TIM4.Period=1000 201 | TIM4.Prescaler=96 202 | USART1.BaudRate=921600 203 | USART1.IPParameters=VirtualMode,BaudRate 204 | USART1.VirtualMode=VM_ASYNC 205 | USB_DEVICE.CLASS_NAME_FS=CDC 206 | USB_DEVICE.IPParameters=VirtualMode,VirtualModeFS,CLASS_NAME_FS 207 | USB_DEVICE.VirtualMode=Cdc 208 | USB_DEVICE.VirtualModeFS=Cdc_FS 209 | USB_OTG_FS.IPParameters=VirtualMode 210 | USB_OTG_FS.VirtualMode=Device_Only 211 | VP_FREERTOS_VS_CMSIS_V2.Mode=CMSIS_V2 212 | VP_FREERTOS_VS_CMSIS_V2.Signal=FREERTOS_VS_CMSIS_V2 213 | VP_SYS_VS_tim10.Mode=TIM10 214 | VP_SYS_VS_tim10.Signal=SYS_VS_tim10 215 | VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS.Mode=CDC_FS 216 | VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS.Signal=USB_DEVICE_VS_USB_DEVICE_CDC_FS 217 | board=custom 218 | -------------------------------------------------------------------------------- /Board/MDK-ARM/startup_stm32f411xe.s: -------------------------------------------------------------------------------- 1 | ;******************************************************************************* 2 | ;* File Name : startup_stm32f411xe.s 3 | ;* Author : MCD Application Team 4 | ;* Description : STM32F411xExx devices vector table for MDK-ARM toolchain. 5 | ;* This module performs: 6 | ;* - Set the initial SP 7 | ;* - Set the initial PC == Reset_Handler 8 | ;* - Set the vector table entries with the exceptions ISR address 9 | ;* - Branches to __main in the C library (which eventually 10 | ;* calls main()). 11 | ;* After Reset the CortexM4 processor is in Thread mode, 12 | ;* priority is Privileged, and the Stack is set to Main. 13 | ;******************************************************************************** 14 | ;* @attention 15 | ;* 16 | ;*

© Copyright (c) 2017 STMicroelectronics. 17 | ;* All rights reserved.

18 | ;* 19 | ;* This software component is licensed by ST under BSD 3-Clause license, 20 | ;* the "License"; You may not use this file except in compliance with the 21 | ;* License. You may obtain a copy of the License at: 22 | ;* opensource.org/licenses/BSD-3-Clause 23 | ;* 24 | ;******************************************************************************* 25 | ;* <<< Use Configuration Wizard in Context Menu >>> 26 | ; 27 | ; Amount of memory (in bytes) allocated for Stack 28 | ; Tailor this value to your application needs 29 | ; Stack Configuration 30 | ; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> 31 | ; 32 | 33 | Stack_Size EQU 0x800 34 | 35 | AREA STACK, NOINIT, READWRITE, ALIGN=3 36 | Stack_Mem SPACE Stack_Size 37 | __initial_sp 38 | 39 | 40 | ; Heap Configuration 41 | ; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> 42 | ; 43 | 44 | Heap_Size EQU 0x3000 45 | 46 | AREA HEAP, NOINIT, READWRITE, ALIGN=3 47 | __heap_base 48 | Heap_Mem SPACE Heap_Size 49 | __heap_limit 50 | 51 | PRESERVE8 52 | THUMB 53 | 54 | 55 | ; Vector Table Mapped to Address 0 at Reset 56 | AREA RESET, DATA, READONLY 57 | EXPORT __Vectors 58 | EXPORT __Vectors_End 59 | EXPORT __Vectors_Size 60 | 61 | __Vectors DCD __initial_sp ; Top of Stack 62 | DCD Reset_Handler ; Reset Handler 63 | DCD NMI_Handler ; NMI Handler 64 | DCD HardFault_Handler ; Hard Fault Handler 65 | DCD MemManage_Handler ; MPU Fault Handler 66 | DCD BusFault_Handler ; Bus Fault Handler 67 | DCD UsageFault_Handler ; Usage Fault Handler 68 | DCD 0 ; Reserved 69 | DCD 0 ; Reserved 70 | DCD 0 ; Reserved 71 | DCD 0 ; Reserved 72 | DCD SVC_Handler ; SVCall Handler 73 | DCD DebugMon_Handler ; Debug Monitor Handler 74 | DCD 0 ; Reserved 75 | DCD PendSV_Handler ; PendSV Handler 76 | DCD SysTick_Handler ; SysTick Handler 77 | 78 | ; External Interrupts 79 | DCD WWDG_IRQHandler ; Window WatchDog 80 | DCD PVD_IRQHandler ; PVD through EXTI Line detection 81 | DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line 82 | DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line 83 | DCD FLASH_IRQHandler ; FLASH 84 | DCD RCC_IRQHandler ; RCC 85 | DCD EXTI0_IRQHandler ; EXTI Line0 86 | DCD EXTI1_IRQHandler ; EXTI Line1 87 | DCD EXTI2_IRQHandler ; EXTI Line2 88 | DCD EXTI3_IRQHandler ; EXTI Line3 89 | DCD EXTI4_IRQHandler ; EXTI Line4 90 | DCD DMA1_Stream0_IRQHandler ; DMA1 Stream 0 91 | DCD DMA1_Stream1_IRQHandler ; DMA1 Stream 1 92 | DCD DMA1_Stream2_IRQHandler ; DMA1 Stream 2 93 | DCD DMA1_Stream3_IRQHandler ; DMA1 Stream 3 94 | DCD DMA1_Stream4_IRQHandler ; DMA1 Stream 4 95 | DCD DMA1_Stream5_IRQHandler ; DMA1 Stream 5 96 | DCD DMA1_Stream6_IRQHandler ; DMA1 Stream 6 97 | DCD ADC_IRQHandler ; ADC1, ADC2 and ADC3s 98 | DCD 0 ; Reserved 99 | DCD 0 ; Reserved 100 | DCD 0 ; Reserved 101 | DCD 0 ; Reserved 102 | DCD EXTI9_5_IRQHandler ; External Line[9:5]s 103 | DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 104 | DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 105 | DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 106 | DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare 107 | DCD TIM2_IRQHandler ; TIM2 108 | DCD TIM3_IRQHandler ; TIM3 109 | DCD TIM4_IRQHandler ; TIM4 110 | DCD I2C1_EV_IRQHandler ; I2C1 Event 111 | DCD I2C1_ER_IRQHandler ; I2C1 Error 112 | DCD I2C2_EV_IRQHandler ; I2C2 Event 113 | DCD I2C2_ER_IRQHandler ; I2C2 Error 114 | DCD SPI1_IRQHandler ; SPI1 115 | DCD SPI2_IRQHandler ; SPI2 116 | DCD USART1_IRQHandler ; USART1 117 | DCD USART2_IRQHandler ; USART2 118 | DCD 0 ; Reserved 119 | DCD EXTI15_10_IRQHandler ; External Line[15:10]s 120 | DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line 121 | DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line 122 | DCD 0 ; Reserved 123 | DCD 0 ; Reserved 124 | DCD 0 ; Reserved 125 | DCD 0 ; Reserved 126 | DCD DMA1_Stream7_IRQHandler ; DMA1 Stream7 127 | DCD 0 ; Reserved 128 | DCD SDIO_IRQHandler ; SDIO 129 | DCD TIM5_IRQHandler ; TIM5 130 | DCD SPI3_IRQHandler ; SPI3 131 | DCD 0 ; Reserved 132 | DCD 0 ; Reserved 133 | DCD 0 ; Reserved 134 | DCD 0 ; Reserved 135 | DCD DMA2_Stream0_IRQHandler ; DMA2 Stream 0 136 | DCD DMA2_Stream1_IRQHandler ; DMA2 Stream 1 137 | DCD DMA2_Stream2_IRQHandler ; DMA2 Stream 2 138 | DCD DMA2_Stream3_IRQHandler ; DMA2 Stream 3 139 | DCD DMA2_Stream4_IRQHandler ; DMA2 Stream 4 140 | DCD 0 ; Reserved 141 | DCD 0 ; Reserved 142 | DCD 0 ; Reserved 143 | DCD 0 ; Reserved 144 | DCD 0 ; Reserved 145 | DCD 0 ; Reserved 146 | DCD OTG_FS_IRQHandler ; USB OTG FS 147 | DCD DMA2_Stream5_IRQHandler ; DMA2 Stream 5 148 | DCD DMA2_Stream6_IRQHandler ; DMA2 Stream 6 149 | DCD DMA2_Stream7_IRQHandler ; DMA2 Stream 7 150 | DCD USART6_IRQHandler ; USART6 151 | DCD I2C3_EV_IRQHandler ; I2C3 event 152 | DCD I2C3_ER_IRQHandler ; I2C3 error 153 | DCD 0 ; Reserved 154 | DCD 0 ; Reserved 155 | DCD 0 ; Reserved 156 | DCD 0 ; Reserved 157 | DCD 0 ; Reserved 158 | DCD 0 ; Reserved 159 | DCD 0 ; Reserved 160 | DCD FPU_IRQHandler ; FPU 161 | DCD 0 ; Reserved 162 | DCD 0 ; Reserved 163 | DCD SPI4_IRQHandler ; SPI4 164 | DCD SPI5_IRQHandler ; SPI5 165 | 166 | __Vectors_End 167 | 168 | __Vectors_Size EQU __Vectors_End - __Vectors 169 | 170 | AREA |.text|, CODE, READONLY 171 | 172 | ; Reset handler 173 | Reset_Handler PROC 174 | EXPORT Reset_Handler [WEAK] 175 | IMPORT SystemInit 176 | IMPORT __main 177 | 178 | LDR R0, =SystemInit 179 | BLX R0 180 | LDR R0, =__main 181 | BX R0 182 | ENDP 183 | 184 | ; Dummy Exception Handlers (infinite loops which can be modified) 185 | 186 | NMI_Handler PROC 187 | EXPORT NMI_Handler [WEAK] 188 | B . 189 | ENDP 190 | HardFault_Handler\ 191 | PROC 192 | EXPORT HardFault_Handler [WEAK] 193 | B . 194 | ENDP 195 | MemManage_Handler\ 196 | PROC 197 | EXPORT MemManage_Handler [WEAK] 198 | B . 199 | ENDP 200 | BusFault_Handler\ 201 | PROC 202 | EXPORT BusFault_Handler [WEAK] 203 | B . 204 | ENDP 205 | UsageFault_Handler\ 206 | PROC 207 | EXPORT UsageFault_Handler [WEAK] 208 | B . 209 | ENDP 210 | SVC_Handler PROC 211 | EXPORT SVC_Handler [WEAK] 212 | B . 213 | ENDP 214 | DebugMon_Handler\ 215 | PROC 216 | EXPORT DebugMon_Handler [WEAK] 217 | B . 218 | ENDP 219 | PendSV_Handler PROC 220 | EXPORT PendSV_Handler [WEAK] 221 | B . 222 | ENDP 223 | SysTick_Handler PROC 224 | EXPORT SysTick_Handler [WEAK] 225 | B . 226 | ENDP 227 | 228 | Default_Handler PROC 229 | 230 | EXPORT WWDG_IRQHandler [WEAK] 231 | EXPORT PVD_IRQHandler [WEAK] 232 | EXPORT TAMP_STAMP_IRQHandler [WEAK] 233 | EXPORT RTC_WKUP_IRQHandler [WEAK] 234 | EXPORT FLASH_IRQHandler [WEAK] 235 | EXPORT RCC_IRQHandler [WEAK] 236 | EXPORT EXTI0_IRQHandler [WEAK] 237 | EXPORT EXTI1_IRQHandler [WEAK] 238 | EXPORT EXTI2_IRQHandler [WEAK] 239 | EXPORT EXTI3_IRQHandler [WEAK] 240 | EXPORT EXTI4_IRQHandler [WEAK] 241 | EXPORT DMA1_Stream0_IRQHandler [WEAK] 242 | EXPORT DMA1_Stream1_IRQHandler [WEAK] 243 | EXPORT DMA1_Stream2_IRQHandler [WEAK] 244 | EXPORT DMA1_Stream3_IRQHandler [WEAK] 245 | EXPORT DMA1_Stream4_IRQHandler [WEAK] 246 | EXPORT DMA1_Stream5_IRQHandler [WEAK] 247 | EXPORT DMA1_Stream6_IRQHandler [WEAK] 248 | EXPORT ADC_IRQHandler [WEAK] 249 | EXPORT EXTI9_5_IRQHandler [WEAK] 250 | EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] 251 | EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] 252 | EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] 253 | EXPORT TIM1_CC_IRQHandler [WEAK] 254 | EXPORT TIM2_IRQHandler [WEAK] 255 | EXPORT TIM3_IRQHandler [WEAK] 256 | EXPORT TIM4_IRQHandler [WEAK] 257 | EXPORT I2C1_EV_IRQHandler [WEAK] 258 | EXPORT I2C1_ER_IRQHandler [WEAK] 259 | EXPORT I2C2_EV_IRQHandler [WEAK] 260 | EXPORT I2C2_ER_IRQHandler [WEAK] 261 | EXPORT SPI1_IRQHandler [WEAK] 262 | EXPORT SPI2_IRQHandler [WEAK] 263 | EXPORT USART1_IRQHandler [WEAK] 264 | EXPORT USART2_IRQHandler [WEAK] 265 | EXPORT EXTI15_10_IRQHandler [WEAK] 266 | EXPORT RTC_Alarm_IRQHandler [WEAK] 267 | EXPORT OTG_FS_WKUP_IRQHandler [WEAK] 268 | EXPORT DMA1_Stream7_IRQHandler [WEAK] 269 | EXPORT SDIO_IRQHandler [WEAK] 270 | EXPORT TIM5_IRQHandler [WEAK] 271 | EXPORT SPI3_IRQHandler [WEAK] 272 | EXPORT DMA2_Stream0_IRQHandler [WEAK] 273 | EXPORT DMA2_Stream1_IRQHandler [WEAK] 274 | EXPORT DMA2_Stream2_IRQHandler [WEAK] 275 | EXPORT DMA2_Stream3_IRQHandler [WEAK] 276 | EXPORT DMA2_Stream4_IRQHandler [WEAK] 277 | EXPORT OTG_FS_IRQHandler [WEAK] 278 | EXPORT DMA2_Stream5_IRQHandler [WEAK] 279 | EXPORT DMA2_Stream6_IRQHandler [WEAK] 280 | EXPORT DMA2_Stream7_IRQHandler [WEAK] 281 | EXPORT USART6_IRQHandler [WEAK] 282 | EXPORT I2C3_EV_IRQHandler [WEAK] 283 | EXPORT I2C3_ER_IRQHandler [WEAK] 284 | EXPORT FPU_IRQHandler [WEAK] 285 | EXPORT SPI4_IRQHandler [WEAK] 286 | EXPORT SPI5_IRQHandler [WEAK] 287 | 288 | WWDG_IRQHandler 289 | PVD_IRQHandler 290 | TAMP_STAMP_IRQHandler 291 | RTC_WKUP_IRQHandler 292 | FLASH_IRQHandler 293 | RCC_IRQHandler 294 | EXTI0_IRQHandler 295 | EXTI1_IRQHandler 296 | EXTI2_IRQHandler 297 | EXTI3_IRQHandler 298 | EXTI4_IRQHandler 299 | DMA1_Stream0_IRQHandler 300 | DMA1_Stream1_IRQHandler 301 | DMA1_Stream2_IRQHandler 302 | DMA1_Stream3_IRQHandler 303 | DMA1_Stream4_IRQHandler 304 | DMA1_Stream5_IRQHandler 305 | DMA1_Stream6_IRQHandler 306 | ADC_IRQHandler 307 | EXTI9_5_IRQHandler 308 | TIM1_BRK_TIM9_IRQHandler 309 | TIM1_UP_TIM10_IRQHandler 310 | TIM1_TRG_COM_TIM11_IRQHandler 311 | TIM1_CC_IRQHandler 312 | TIM2_IRQHandler 313 | TIM3_IRQHandler 314 | TIM4_IRQHandler 315 | I2C1_EV_IRQHandler 316 | I2C1_ER_IRQHandler 317 | I2C2_EV_IRQHandler 318 | I2C2_ER_IRQHandler 319 | SPI1_IRQHandler 320 | SPI2_IRQHandler 321 | USART1_IRQHandler 322 | USART2_IRQHandler 323 | EXTI15_10_IRQHandler 324 | RTC_Alarm_IRQHandler 325 | OTG_FS_WKUP_IRQHandler 326 | DMA1_Stream7_IRQHandler 327 | SDIO_IRQHandler 328 | TIM5_IRQHandler 329 | SPI3_IRQHandler 330 | DMA2_Stream0_IRQHandler 331 | DMA2_Stream1_IRQHandler 332 | DMA2_Stream2_IRQHandler 333 | DMA2_Stream3_IRQHandler 334 | DMA2_Stream4_IRQHandler 335 | OTG_FS_IRQHandler 336 | DMA2_Stream5_IRQHandler 337 | DMA2_Stream6_IRQHandler 338 | DMA2_Stream7_IRQHandler 339 | USART6_IRQHandler 340 | I2C3_EV_IRQHandler 341 | I2C3_ER_IRQHandler 342 | FPU_IRQHandler 343 | SPI4_IRQHandler 344 | SPI5_IRQHandler 345 | 346 | B . 347 | 348 | ENDP 349 | 350 | ALIGN 351 | 352 | ;******************************************************************************* 353 | ; User Stack and Heap initialization 354 | ;******************************************************************************* 355 | IF :DEF:__MICROLIB 356 | 357 | EXPORT __initial_sp 358 | EXPORT __heap_base 359 | EXPORT __heap_limit 360 | 361 | ELSE 362 | 363 | IMPORT __use_two_region_memory 364 | EXPORT __user_initial_stackheap 365 | 366 | __user_initial_stackheap 367 | 368 | LDR R0, = Heap_Mem 369 | LDR R1, =(Stack_Mem + Stack_Size) 370 | LDR R2, = (Heap_Mem + Heap_Size) 371 | LDR R3, = Stack_Mem 372 | BX LR 373 | 374 | ALIGN 375 | 376 | ENDIF 377 | 378 | END 379 | 380 | ;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** 381 | -------------------------------------------------------------------------------- /Board/MDK-ARM/myflight.uvprojx: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 2.1 5 | 6 |
### uVision Project, (C) Keil Software
7 | 8 | 9 | 10 | myflight 11 | 0x4 12 | ARM-ADS 13 | 6140000::V6.14::ARMCLANG 14 | 1 15 | 16 | 17 | STM32F411CEUx 18 | STMicroelectronics 19 | Keil.STM32F4xx_DFP.2.13.0 20 | http://www.keil.com/pack 21 | IRAM(0x20000000-0x2001FFFF) IROM(0x8000000-0x807FFFF) CLOCK(25000000) FPU2 CPUTYPE("Cortex-M4") 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | $$Device:STM32F411CEUx$CMSIS\SVD\STM32F411xx.svd 37 | 0 38 | 0 39 | 40 | 41 | 42 | 43 | 44 | 45 | 0 46 | 0 47 | 0 48 | 0 49 | 1 50 | 51 | myflight\ 52 | myflight 53 | 1 54 | 0 55 | 1 56 | 1 57 | 1 58 | 59 | 1 60 | 0 61 | 0 62 | 63 | 0 64 | 0 65 | 66 | 67 | 0 68 | 0 69 | 0 70 | 0 71 | 72 | 73 | 0 74 | 0 75 | 76 | 77 | 0 78 | 0 79 | 0 80 | 0 81 | 82 | 83 | 0 84 | 0 85 | 86 | 87 | 0 88 | 0 89 | 0 90 | 0 91 | 92 | 0 93 | 94 | 95 | 96 | 0 97 | 0 98 | 0 99 | 0 100 | 0 101 | 1 102 | 0 103 | 0 104 | 0 105 | 0 106 | 3 107 | 108 | 109 | 0 110 | 111 | 112 | SARMCM3.DLL 113 | -REMAP -MPU 114 | DCM.DLL 115 | -pCM4 116 | SARMCM3.DLL 117 | -MPU 118 | TCM.DLL 119 | -pCM4 120 | 121 | 122 | 123 | 1 124 | 0 125 | 0 126 | 0 127 | 16 128 | 129 | 130 | 131 | 132 | 1 133 | 0 134 | 0 135 | 1 136 | 1 137 | 4107 138 | 139 | 1 140 | STLink\ST-LINKIII-KEIL_SWO.dll 141 | 142 | 143 | 144 | 145 | 146 | 0 147 | 148 | 149 | 150 | 0 151 | 1 152 | 1 153 | 1 154 | 1 155 | 1 156 | 1 157 | 1 158 | 0 159 | 1 160 | 1 161 | 0 162 | 1 163 | 1 164 | 0 165 | 0 166 | 1 167 | 1 168 | 1 169 | 1 170 | 1 171 | 1 172 | 1 173 | 1 174 | 1 175 | 0 176 | 0 177 | "Cortex-M4" 178 | 179 | 0 180 | 0 181 | 0 182 | 1 183 | 1 184 | 0 185 | 0 186 | 2 187 | 0 188 | 0 189 | 0 190 | 0 191 | 8 192 | 0 193 | 0 194 | 0 195 | 0 196 | 3 197 | 3 198 | 0 199 | 0 200 | 0 201 | 0 202 | 0 203 | 0 204 | 0 205 | 0 206 | 0 207 | 0 208 | 1 209 | 0 210 | 0 211 | 0 212 | 0 213 | 1 214 | 0 215 | 216 | 217 | 0 218 | 0x0 219 | 0x0 220 | 221 | 222 | 0 223 | 0x0 224 | 0x0 225 | 226 | 227 | 0 228 | 0x0 229 | 0x0 230 | 231 | 232 | 0 233 | 0x0 234 | 0x0 235 | 236 | 237 | 0 238 | 0x0 239 | 0x0 240 | 241 | 242 | 0 243 | 0x0 244 | 0x0 245 | 246 | 247 | 0 248 | 0x20000000 249 | 0x20000 250 | 251 | 252 | 1 253 | 0x8000000 254 | 0x80000 255 | 256 | 257 | 0 258 | 0x0 259 | 0x0 260 | 261 | 262 | 1 263 | 0x0 264 | 0x0 265 | 266 | 267 | 1 268 | 0x0 269 | 0x0 270 | 271 | 272 | 1 273 | 0x0 274 | 0x0 275 | 276 | 277 | 1 278 | 0x8000000 279 | 0x80000 280 | 281 | 282 | 1 283 | 0x0 284 | 0x0 285 | 286 | 287 | 0 288 | 0x0 289 | 0x0 290 | 291 | 292 | 0 293 | 0x0 294 | 0x0 295 | 296 | 297 | 0 298 | 0x0 299 | 0x0 300 | 301 | 302 | 0 303 | 0x20000000 304 | 0x20000 305 | 306 | 307 | 0 308 | 0x0 309 | 0x0 310 | 311 | 312 | 313 | 314 | 315 | 1 316 | 7 317 | 0 318 | 0 319 | 1 320 | 0 321 | 0 322 | 0 323 | 0 324 | 0 325 | 3 326 | 0 327 | 0 328 | 1 329 | 0 330 | 0 331 | 3 332 | 3 333 | 1 334 | 1 335 | 0 336 | 0 337 | 0 338 | 339 | 340 | USE_HAL_DRIVER,STM32F411xE 341 | 342 | ../Core/Inc; ../Drivers/STM32F4xx_HAL_Driver/Inc; ../Drivers/STM32F4xx_HAL_Driver/Inc/Legacy; ../Middlewares/Third_Party/FreeRTOS/Source/include; ../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2; ../Middlewares/Third_Party/FreeRTOS/Source/portable/RVDS/ARM_CM4F; ../Drivers/CMSIS/Device/ST/STM32F4xx/Include; ../Drivers/CMSIS/Include; ..\..\Hardware; ..\..\MyFlight; ..\..\Common; ../USB_DEVICE/App; ../USB_DEVICE/Target; ../Middlewares/ST/STM32_USB_Device_Library/Core/Inc; ../Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc 343 | 344 | 345 | 346 | 1 347 | 0 348 | 0 349 | 0 350 | 0 351 | 0 352 | 0 353 | 0 354 | 0 355 | 4 356 | 357 | 358 | 359 | 360 | ..\Core\Inc 361 | 362 | 363 | 364 | 1 365 | 0 366 | 0 367 | 0 368 | 1 369 | 0 370 | 0x08000000 371 | 0x20000000 372 | 373 | 374 | 375 | 376 | 377 | 378 | 379 | 380 | 381 | 382 | 383 | 384 | Application/MDK-ARM 385 | 386 | 387 | startup_stm32f411xe.s 388 | 2 389 | startup_stm32f411xe.s 390 | 391 | 392 | 393 | 394 | Application/User/Core 395 | 396 | 397 | main.c 398 | 1 399 | ../Core/Src/main.c 400 | 401 | 402 | gpio.c 403 | 1 404 | ../Core/Src/gpio.c 405 | 406 | 407 | freertos.c 408 | 1 409 | ../Core/Src/freertos.c 410 | 411 | 412 | i2c.c 413 | 1 414 | ../Core/Src/i2c.c 415 | 416 | 417 | tim.c 418 | 1 419 | ../Core/Src/tim.c 420 | 421 | 422 | usart.c 423 | 1 424 | ../Core/Src/usart.c 425 | 426 | 427 | stm32f4xx_it.c 428 | 1 429 | ../Core/Src/stm32f4xx_it.c 430 | 431 | 432 | stm32f4xx_hal_msp.c 433 | 1 434 | ../Core/Src/stm32f4xx_hal_msp.c 435 | 436 | 437 | stm32f4xx_hal_timebase_tim.c 438 | 1 439 | ../Core/Src/stm32f4xx_hal_timebase_tim.c 440 | 441 | 442 | 443 | 444 | Drivers/STM32F4xx_HAL_Driver 445 | 446 | 447 | stm32f4xx_hal_pcd.c 448 | 1 449 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c 450 | 451 | 452 | stm32f4xx_hal_pcd_ex.c 453 | 1 454 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c 455 | 456 | 457 | stm32f4xx_ll_usb.c 458 | 1 459 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c 460 | 461 | 462 | stm32f4xx_hal_rcc.c 463 | 1 464 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c 465 | 466 | 467 | stm32f4xx_hal_rcc_ex.c 468 | 1 469 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c 470 | 471 | 472 | stm32f4xx_hal_flash.c 473 | 1 474 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c 475 | 476 | 477 | stm32f4xx_hal_flash_ex.c 478 | 1 479 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c 480 | 481 | 482 | stm32f4xx_hal_flash_ramfunc.c 483 | 1 484 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c 485 | 486 | 487 | stm32f4xx_hal_gpio.c 488 | 1 489 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c 490 | 491 | 492 | stm32f4xx_hal_dma_ex.c 493 | 1 494 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c 495 | 496 | 497 | stm32f4xx_hal_dma.c 498 | 1 499 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c 500 | 501 | 502 | stm32f4xx_hal_pwr.c 503 | 1 504 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c 505 | 506 | 507 | stm32f4xx_hal_pwr_ex.c 508 | 1 509 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c 510 | 511 | 512 | stm32f4xx_hal_cortex.c 513 | 1 514 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c 515 | 516 | 517 | stm32f4xx_hal.c 518 | 1 519 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c 520 | 521 | 522 | stm32f4xx_hal_exti.c 523 | 1 524 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c 525 | 526 | 527 | stm32f4xx_hal_i2c.c 528 | 1 529 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c 530 | 531 | 532 | stm32f4xx_hal_i2c_ex.c 533 | 1 534 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c 535 | 536 | 537 | stm32f4xx_hal_tim.c 538 | 1 539 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c 540 | 541 | 542 | stm32f4xx_hal_tim_ex.c 543 | 1 544 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c 545 | 546 | 547 | stm32f4xx_hal_uart.c 548 | 1 549 | ../Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c 550 | 551 | 552 | 553 | 554 | Drivers/CMSIS 555 | 556 | 557 | system_stm32f4xx.c 558 | 1 559 | ../Core/Src/system_stm32f4xx.c 560 | 561 | 562 | 563 | 564 | Middlewares/FreeRTOS 565 | 566 | 567 | croutine.c 568 | 1 569 | ../Middlewares/Third_Party/FreeRTOS/Source/croutine.c 570 | 571 | 572 | event_groups.c 573 | 1 574 | ../Middlewares/Third_Party/FreeRTOS/Source/event_groups.c 575 | 576 | 577 | list.c 578 | 1 579 | ../Middlewares/Third_Party/FreeRTOS/Source/list.c 580 | 581 | 582 | queue.c 583 | 1 584 | ../Middlewares/Third_Party/FreeRTOS/Source/queue.c 585 | 586 | 587 | stream_buffer.c 588 | 1 589 | ../Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c 590 | 591 | 592 | tasks.c 593 | 1 594 | ../Middlewares/Third_Party/FreeRTOS/Source/tasks.c 595 | 596 | 597 | timers.c 598 | 1 599 | ../Middlewares/Third_Party/FreeRTOS/Source/timers.c 600 | 601 | 602 | cmsis_os2.c 603 | 1 604 | ../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c 605 | 606 | 607 | heap_4.c 608 | 1 609 | ../Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c 610 | 611 | 612 | port.c 613 | 1 614 | ../Middlewares/Third_Party/FreeRTOS/Source/portable/RVDS/ARM_CM4F/port.c 615 | 616 | 617 | 618 | 619 | Application/User/USB_DEVICE/App 620 | 621 | 622 | usb_device.c 623 | 1 624 | ../USB_DEVICE/App/usb_device.c 625 | 626 | 627 | usbd_desc.c 628 | 1 629 | ../USB_DEVICE/App/usbd_desc.c 630 | 631 | 632 | usbd_cdc_if.c 633 | 1 634 | ../USB_DEVICE/App/usbd_cdc_if.c 635 | 636 | 637 | 638 | 639 | Application/User/USB_DEVICE/Target 640 | 641 | 642 | usbd_conf.c 643 | 1 644 | ../USB_DEVICE/Target/usbd_conf.c 645 | 646 | 647 | 648 | 649 | Middlewares/USB_Device_Library 650 | 651 | 652 | usbd_core.c 653 | 1 654 | ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c 655 | 656 | 657 | usbd_ctlreq.c 658 | 1 659 | ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c 660 | 661 | 662 | usbd_ioreq.c 663 | 1 664 | ../Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c 665 | 666 | 667 | usbd_cdc.c 668 | 1 669 | ../Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c 670 | 671 | 672 | 673 | 674 | Common 675 | 676 | 677 | base.hpp 678 | 5 679 | ..\..\Common\base.hpp 680 | 681 | 682 | common.cpp 683 | 8 684 | ..\..\Common\common.cpp 685 | 686 | 687 | common.hpp 688 | 5 689 | ..\..\Common\common.hpp 690 | 691 | 692 | pid.hpp 693 | 5 694 | ..\..\Common\pid.hpp 695 | 696 | 697 | 698 | 699 | Hardware 700 | 701 | 702 | board.h 703 | 5 704 | ..\..\Hardware\board.h 705 | 706 | 707 | Hardware.hpp 708 | 5 709 | ..\..\Hardware\Hardware.hpp 710 | 711 | 712 | LED_IO.cpp 713 | 8 714 | ..\..\Hardware\LED_IO.cpp 715 | 716 | 717 | LED_IO.hpp 718 | 5 719 | ..\..\Hardware\LED_IO.hpp 720 | 721 | 722 | Motor_PWM.cpp 723 | 8 724 | ..\..\Hardware\Motor_PWM.cpp 725 | 726 | 727 | Motor_PWM.hpp 728 | 5 729 | ..\..\Hardware\Motor_PWM.hpp 730 | 731 | 732 | mpu9250.h 733 | 5 734 | ..\..\Hardware\mpu9250.h 735 | 736 | 737 | Sensor_mpu9250.cpp 738 | 8 739 | ..\..\Hardware\Sensor_mpu9250.cpp 740 | 741 | 742 | Sensor_mpu9250.hpp 743 | 5 744 | ..\..\Hardware\Sensor_mpu9250.hpp 745 | 746 | 747 | Message_usart.cpp 748 | 8 749 | ..\..\Hardware\Message_usart.cpp 750 | 751 | 752 | Message_usart.hpp 753 | 5 754 | ..\..\Hardware\Message_usart.hpp 755 | 756 | 757 | Message_usb.cpp 758 | 8 759 | ..\..\Hardware\Message_usb.cpp 760 | 761 | 762 | Message_usb.hpp 763 | 5 764 | ..\..\Hardware\Message_usb.hpp 765 | 766 | 767 | 768 | 769 | MyFlight 770 | 771 | 772 | hal.hpp 773 | 5 774 | ..\..\MyFlight\hal.hpp 775 | 776 | 777 | interface.hpp 778 | 5 779 | ..\..\MyFlight\interface.hpp 780 | 781 | 782 | task.cpp 783 | 8 784 | ..\..\MyFlight\task.cpp 785 | 786 | 787 | Flight.cpp 788 | 8 789 | ..\..\MyFlight\Flight.cpp 790 | 791 | 792 | Flight.hpp 793 | 5 794 | ..\..\MyFlight\Flight.hpp 795 | 796 | 797 | 798 | 799 | ::CMSIS 800 | 801 | 802 | 803 | 804 | 805 | 806 | 807 | 808 | 809 | 810 | 811 | 812 | 813 | 814 | 815 | 816 | 817 | 818 | 819 | 820 | 821 | 822 | 823 | 824 | 825 | 826 | 827 | <Project Info> 828 | 829 | 830 | 831 | 832 | 833 | 0 834 | 1 835 | 836 | 837 | 838 | 839 |
840 | --------------------------------------------------------------------------------