├── .gitattributes ├── Drivers ├── CMSIS │ ├── Device │ │ └── ST │ │ │ └── STM32H7xx │ │ │ └── Include │ │ │ ├── stm32h7xx.h │ │ │ └── system_stm32h7xx.h │ └── Include │ │ ├── cmsis_version.h │ │ └── tz_context.h └── STM32H7xx_HAL_Driver │ ├── Inc │ ├── stm32h7xx_hal_spi_ex.h │ ├── stm32h7xx_hal_def.h │ └── stm32h7xx_hal_hsem.h │ └── Src │ └── stm32h7xx_hal_spi_ex.c ├── .settings ├── stm32cubeide.project.prefs ├── org.eclipse.cdt.core.prefs └── language.settings.xml ├── .gitignore ├── Core ├── Src │ ├── common │ │ ├── time_utils.cpp │ │ ├── time_utils.h │ │ ├── lowpass_filter.cpp │ │ ├── lowpass_filter.hpp │ │ ├── base_classes │ │ │ ├── Sensor.cpp │ │ │ ├── Sensor.hpp │ │ │ ├── BLDCDriver.hpp │ │ │ ├── CurrentSense.cpp │ │ │ ├── CurrentSense.hpp │ │ │ └── FOCMotor.cpp │ │ ├── pid.hpp │ │ ├── defaults.h │ │ ├── foc_utils.h │ │ ├── pid.cpp │ │ └── foc_utils.cpp │ ├── current_sense │ │ ├── hardware_api.h │ │ ├── hardware_api.cpp │ │ ├── InlineCurrentSense.hpp │ │ └── InlineCurrentSense.cpp │ ├── SimpleFOC.hpp │ ├── motor_drivers │ │ ├── BLDCDriver3PWM.hpp │ │ └── BLDCDriver3PWM.cpp │ ├── stm32h7xx_hal_msp.c │ ├── sensors │ │ ├── MagneticSensorSPI.hpp │ │ ├── MagneticSensorSPI.cpp │ │ ├── Encoder.hpp │ │ └── Encoder.cpp │ ├── sysmem.c │ ├── syscalls.c │ ├── BLDCMotor.hpp │ ├── spi.c │ ├── gpio.c │ ├── adc.c │ ├── tim.c │ └── stm32h7xx_it.c └── Inc │ ├── gpio.h │ ├── spi.h │ ├── adc.h │ ├── tim.h │ ├── stm32h7xx_it.h │ └── main.h ├── LICENSE ├── STM32_SimpleFOC_InlineCurrentSense.cfg ├── .project ├── STM32CubeIDE ├── Application │ └── User │ │ └── Core │ │ ├── sysmem.c │ │ └── syscalls.c ├── STM32H743ZITX_FLASH.ld ├── STM32H743ZITX_RAM.ld └── .project ├── README.md ├── Notes ├── STM32H743ZITX_RAM.ld ├── STM32H743ZITX_FLASH.ld └── STM32_SimpleFOC_InlineCurrentSense.launch /.gitattributes: -------------------------------------------------------------------------------- 1 | # Auto detect text files and perform LF normalization 2 | * text=auto 3 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32H7xx/Include/stm32h7xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ngalin/STM32_SimpleFOC_InlineCurrentSense/HEAD/Drivers/CMSIS/Device/ST/STM32H7xx/Include/stm32h7xx.h -------------------------------------------------------------------------------- /.settings/stm32cubeide.project.prefs: -------------------------------------------------------------------------------- 1 | 2F62501ED4689FB349E356AB974DBE57=05488FB562B314415892C0E29C0AD2A7 2 | 8DF89ED150041C4CBC7CB9A9CAA90856=05488FB562B314415892C0E29C0AD2A7 3 | DC22A860405A8BF2F2C095E5B6529F12=6DF979B751C120663785242C4964B6DB 4 | eclipse.preferences.version=1 5 | -------------------------------------------------------------------------------- /.settings/org.eclipse.cdt.core.prefs: -------------------------------------------------------------------------------- 1 | doxygen/doxygen_new_line_after_brief=true 2 | doxygen/doxygen_use_brief_tag=false 3 | doxygen/doxygen_use_javadoc_tags=true 4 | doxygen/doxygen_use_pre_tag=false 5 | doxygen/doxygen_use_structural_commands=false 6 | eclipse.preferences.version=1 7 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Prerequisites 2 | *.d 3 | 4 | # Compiled Object files 5 | *.slo 6 | *.lo 7 | *.o 8 | *.obj 9 | 10 | # Precompiled Headers 11 | *.gch 12 | *.pch 13 | 14 | # Compiled Dynamic libraries 15 | *.so 16 | *.dylib 17 | *.dll 18 | 19 | # Fortran module files 20 | *.mod 21 | *.smod 22 | 23 | # Compiled Static libraries 24 | *.lai 25 | *.la 26 | *.a 27 | *.lib 28 | 29 | # Executables 30 | *.exe 31 | *.out 32 | *.app 33 | *.elf 34 | *.launch 35 | *.xml 36 | -------------------------------------------------------------------------------- /Core/Src/common/time_utils.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * time_utils.cpp 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/common/time_utils.cpp 6 | */ 7 | 8 | #include "time_utils.h" 9 | #include "stm32h7xx_hal.h" 10 | 11 | // function buffering delay() 12 | void _delay(unsigned long ms){ 13 | HAL_Delay(ms); 14 | } 15 | 16 | // function buffering _micros() 17 | unsigned long _micros(void){ 18 | //return HAL_GetTick()*1000; //get microseconds 19 | return TIM2->CNT; //counter should be set to 1MHz frequency 20 | } 21 | 22 | -------------------------------------------------------------------------------- /Core/Src/common/time_utils.h: -------------------------------------------------------------------------------- 1 | /* 2 | * time_utils.h 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/common/time_utils.h 6 | */ 7 | 8 | #ifndef TIME_UTILS_H_ 9 | #define TIME_UTILS_H_ 10 | 11 | 12 | 13 | /** 14 | * Function implementing delay() function in milliseconds 15 | * - blocking function 16 | * - hardware specific 17 | * @param ms number of milliseconds to wait 18 | */ 19 | void _delay(unsigned long ms); 20 | 21 | /** 22 | * Function implementing timestamp getting function in microseconds 23 | * hardware specific 24 | */ 25 | unsigned long _micros(void); 26 | 27 | #endif /* TIME_UTILS_H_ */ 28 | -------------------------------------------------------------------------------- /Core/Src/common/lowpass_filter.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * lowpass_filter.cpp 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/common/lowpass_filter.cpp 6 | */ 7 | 8 | #include "lowpass_filter.hpp" 9 | 10 | LowPassFilter::LowPassFilter(float time_constant) 11 | : Tf(time_constant) 12 | , y_prev(0.0f) 13 | { 14 | timestamp_prev = _micros(); 15 | } 16 | 17 | 18 | float LowPassFilter::operator() (float x) 19 | { 20 | unsigned long timestamp = _micros(); 21 | float dt = (timestamp - timestamp_prev)*1e-6f; 22 | 23 | if (dt <= 0.0f || dt > 0.5f) //FIXME, without equals sign at dt < 0.0f the algo won't start. 24 | dt = 1e-3f; 25 | 26 | float alpha = Tf/(Tf + dt); 27 | float y = alpha*y_prev + (1.0f - alpha)*x; 28 | 29 | y_prev = y; 30 | timestamp_prev = timestamp; 31 | return y; 32 | } 33 | -------------------------------------------------------------------------------- /Core/Src/common/lowpass_filter.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * lowpass_filter.hpp 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/common/lowpass_filter.h 6 | */ 7 | 8 | #ifndef LOWPASS_FILTER_HPP_ 9 | #define LOWPASS_FILTER_HPP_ 10 | 11 | 12 | #include "time_utils.h" 13 | #include "foc_utils.h" 14 | 15 | /** 16 | * Low pass filter class 17 | */ 18 | class LowPassFilter 19 | { 20 | public: 21 | /** 22 | * @param Tf - Low pass filter time constant 23 | */ 24 | LowPassFilter(float Tf); 25 | ~LowPassFilter() = default; 26 | 27 | float operator() (float x); 28 | float Tf; //!< Low pass filter time constant 29 | 30 | protected: 31 | unsigned long timestamp_prev; //!< Last execution timestamp 32 | float y_prev; //!< filtered value in previous execution step 33 | }; 34 | 35 | #endif /* LOWPASS_FILTER_HPP_ */ 36 | -------------------------------------------------------------------------------- /Core/Src/current_sense/hardware_api.h: -------------------------------------------------------------------------------- 1 | /* 2 | * hardware_api.h 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/current_sense/hardware_api.h 6 | */ 7 | 8 | #ifndef HARDWARE_API_H_ 9 | #define HARDWARE_API_H_ 10 | 11 | #include "../common/foc_utils.h" 12 | #include "../common/time_utils.h" 13 | 14 | /** 15 | * function reading an ADC value and returning the read voltage 16 | * 17 | * @param pinA - the arduino pin to be read (it has to be ADC pin) 18 | */ 19 | float _readADCVoltage(const int pinA); 20 | 21 | /** 22 | * function converting ADC reading to voltage 23 | * 24 | */ 25 | float _ADCValueToVoltage(int raw_adc); 26 | 27 | /** 28 | * function assigning ADC pins 29 | * 30 | * @param pinA - adc pin A 31 | * @param pinB - adc pin B 32 | * @param pinC - adc pin C 33 | */ 34 | void _configureADC(const int pinA,const int pinB,const int pinC = NOT_SET); 35 | 36 | #endif /* HARDWARE_API_H_ */ 37 | -------------------------------------------------------------------------------- /Core/Src/current_sense/hardware_api.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * hardware_api.cpp 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/current_sense/hardware_specific/generic_mcu.cpp 6 | */ 7 | 8 | #include "hardware_api.h" 9 | #include "main.h" 10 | 11 | #define _ADC_VOLTAGE 3.3 12 | #define _ADC_RESOLUTION 65536.0 13 | 14 | // adc counts to voltage conversion ratio 15 | // some optimizing for faster execution 16 | #define _ADC_CONV ( (_ADC_VOLTAGE) / (_ADC_RESOLUTION) ) 17 | 18 | // function reading an ADC value and returning the read voltage 19 | float _readADCVoltage(const int pin){ 20 | int raw_adc; 21 | if (pin == phaseA) { 22 | raw_adc = _readADCVoltage_pinA(); 23 | } 24 | if (pin == phaseB) { 25 | raw_adc = _readADCVoltage_pinB(); 26 | } 27 | return raw_adc * _ADC_CONV; 28 | } 29 | 30 | float _ADCValueToVoltage(int raw_adc) { 31 | return raw_adc * _ADC_CONV; 32 | } 33 | //// function assigning input pins to ADC 34 | //void _configureADC(const int pinA,const int pinB){ 35 | // pinA = phaseA; 36 | // pinB = phaseB; 37 | //} 38 | 39 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2021 NGalin 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /Core/Src/SimpleFOC.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * SimpleFOC.hpp 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/SimpleFOC.h 6 | */ 7 | 8 | #ifndef SRC_SIMPLEFOC_HPP_ 9 | #define SRC_SIMPLEFOC_HPP_ 10 | 11 | /*! 12 | * @file SimpleFOC.h ported from "https://github.com/simplefoc/Arduino-FOC/blob/v2.1" 13 | * 14 | * @mainpage Simple Field Oriented Control BLDC motor control library 15 | * 16 | * @section intro_sec Introduction 17 | * This version only supports a single STM32 MCU development board at the moment. See README for the 18 | * required pin configuration to support SimpleFOCShield v2.0.2 19 | * 20 | * @section dependencies Supported Hardware 21 | * - Motors 22 | * - BLDC motors 23 | * - Drivers 24 | * - BLDC drivers 25 | * - Position sensors 26 | * - Encoders 27 | * - Open-loop control 28 | * - Microcontrollers 29 | * - STM32H743ZI2 30 | */ 31 | 32 | 33 | #include "BLDCMotor.hpp" 34 | #include "sensors/Encoder.hpp" 35 | #include "sensors/MagneticSensorSPI.hpp" 36 | #include "motor_drivers/BLDCDriver3PWM.hpp" 37 | #include "current_sense/InlineCurrentSense.hpp" 38 | 39 | 40 | 41 | 42 | #endif /* SRC_SIMPLEFOC_HPP_ */ 43 | -------------------------------------------------------------------------------- /STM32_SimpleFOC_InlineCurrentSense.cfg: -------------------------------------------------------------------------------- 1 | # This is an NUCLEO-H743ZI2 board with a single STM32H743ZITx 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 0x8000 10 | 11 | transport select "dapdirect_swd" 12 | 13 | set CHIPNAME STM32H743ZITx 14 | set BOARDNAME NUCLEO-H743ZI2 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 | set DUAL_BANK 1 38 | 39 | 40 | # BCTM CPU variables 41 | 42 | source [find target/stm32h7x.cfg] 43 | 44 | #SWV trace 45 | tpiu config disable 46 | -------------------------------------------------------------------------------- /Core/Src/common/base_classes/Sensor.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Sensor.cpp 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/common/base_classes/Sensor.cpp 6 | */ 7 | 8 | #include "Sensor.hpp" 9 | 10 | #include "../foc_utils.h" 11 | #include "../time_utils.h" 12 | 13 | /** 14 | * returns 0 if it does need search for absolute zero 15 | * 0 - magnetic sensor (& encoder with index which is found) 16 | * 1 - encoder with index (with index not found yet) 17 | */ 18 | int Sensor::needsSearch(){ 19 | return 0; 20 | } 21 | 22 | /** get current angular velocity (rad/s)*/ 23 | float Sensor::getVelocity(){ 24 | 25 | // calculate sample time 26 | unsigned long now_us = _micros(); 27 | float Ts = (now_us - velocity_calc_timestamp)*1e-6; 28 | // quick fix for strange cases (micros overflow) 29 | if(Ts <= 0 || Ts > 0.5) Ts = 1e-3; 30 | 31 | // current angle 32 | float angle_c = getAngle(); 33 | // velocity calculation 34 | float vel = (angle_c - angle_prev)/Ts; 35 | 36 | // save variables for future pass 37 | angle_prev = angle_c; 38 | velocity_calc_timestamp = now_us; 39 | return vel; 40 | } 41 | 42 | void Sensor::setAngle(float angle_value) { 43 | angle_prev = angle_value; 44 | } 45 | -------------------------------------------------------------------------------- /Core/Src/common/pid.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * pid.hpp 3 | * 4 | * Created on: 23 Mar 2021 5 | * Ported from: https://github.com/simplefoc/Arduino-FOC/blob/v2.1/src/common/pid.h 6 | */ 7 | 8 | 9 | #ifndef PID_HPP_ 10 | #define PID_HPP_ 11 | 12 | 13 | 14 | #include "time_utils.h" 15 | #include "foc_utils.h" 16 | 17 | /** 18 | * PID controller class 19 | */ 20 | class PIDController 21 | { 22 | public: 23 | /** 24 | * 25 | * @param P - Proportional gain 26 | * @param I - Integral gain 27 | * @param D - Derivative gain 28 | * @param ramp - Maximum speed of change of the output value 29 | * @param limit - Maximum output value 30 | */ 31 | PIDController(float P, float I, float D, float ramp, float limit); 32 | ~PIDController() = default; 33 | 34 | float operator() (float error); 35 | 36 | float P; //!< Proportional gain 37 | float I; //!< Integral gain 38 | float D; //!< Derivative gain 39 | float output_ramp; //!< Maximum speed of change of the output value 40 | float limit; //!< Maximum output value 41 | 42 | protected: 43 | float integral_prev; //!< last integral component value 44 | float error_prev; //!< last tracking error value 45 | unsigned long timestamp_prev; //!< Last execution timestamp 46 | float output_prev; //!< last pid output value 47 | float Ts; //!