├── 1.Hardware └── Ctrl-FOC-Lite │ ├── Ctrl-FOC-Lite.PcbDoc │ ├── Ctrl-FOC-Lite.PrjPCB │ ├── Ctrl-FOC-Lite.PrjPCBStructure │ ├── Main.SchDoc │ └── __Previews │ └── Main.SchDocPreview ├── 2.Firmware ├── STM32_HAL_version │ └── Ctrl-FOC-Lite-fw │ │ ├── .cproject │ │ ├── .gitignore │ │ ├── .idea │ │ ├── .gitignore │ │ ├── .name │ │ ├── Ctrl-FOC-Lite-fw2.iml │ │ ├── deployment.xml │ │ ├── inspectionProfiles │ │ │ └── Project_Default.xml │ │ ├── misc.xml │ │ ├── modules.xml │ │ ├── serialmonitor_settings.xml │ │ └── vcs.xml │ │ ├── .mxproject │ │ ├── .project │ │ ├── CMakeLists.txt │ │ ├── CMakeLists_template.txt │ │ ├── Core │ │ ├── Inc │ │ │ ├── adc.h │ │ │ ├── can.h │ │ │ ├── dma.h │ │ │ ├── gpio.h │ │ │ ├── main.h │ │ │ ├── spi.h │ │ │ ├── stm32f1xx_hal_conf.h │ │ │ ├── stm32f1xx_it.h │ │ │ ├── tim.h │ │ │ └── usart.h │ │ └── Src │ │ │ ├── adc.c │ │ │ ├── can.c │ │ │ ├── dma.c │ │ │ ├── gpio.c │ │ │ ├── main.c │ │ │ ├── spi.c │ │ │ ├── stm32f1xx_hal_msp.c │ │ │ ├── stm32f1xx_it.c │ │ │ ├── syscalls.c │ │ │ ├── system_stm32f1xx.c │ │ │ ├── tim.c │ │ │ └── usart.c │ │ ├── Ctrl-FOC-Lite-fw.ioc │ │ ├── Ctrl-FOC-Lite-fw.xml │ │ ├── Ctrl │ │ ├── Sensor │ │ │ └── Encoder │ │ │ │ ├── Instances │ │ │ │ ├── encoder_as5047.cpp │ │ │ │ └── encoder_as5047.h │ │ │ │ ├── encoder_base.cpp │ │ │ │ └── encoder_base.h │ │ ├── Signal │ │ │ ├── button_base.cpp │ │ │ ├── button_base.h │ │ │ ├── io_signal_base.cpp │ │ │ └── io_signal_base.h │ │ └── Utils │ │ │ ├── defaults.h │ │ │ ├── foc_utils.cpp │ │ │ ├── foc_utils.h │ │ │ ├── lowpass_filter.cpp │ │ │ ├── lowpass_filter.h │ │ │ ├── pid.cpp │ │ │ └── pid.h │ │ ├── Drivers │ │ ├── CMSIS │ │ │ ├── Device │ │ │ │ └── ST │ │ │ │ │ └── STM32F1xx │ │ │ │ │ └── Include │ │ │ │ │ ├── stm32f103xb.h │ │ │ │ │ ├── stm32f1xx.h │ │ │ │ │ └── system_stm32f1xx.h │ │ │ └── Include │ │ │ │ ├── cmsis_armcc.h │ │ │ │ ├── cmsis_armclang.h │ │ │ │ ├── cmsis_compiler.h │ │ │ │ ├── cmsis_gcc.h │ │ │ │ ├── cmsis_iccarm.h │ │ │ │ ├── cmsis_version.h │ │ │ │ ├── core_armv8mbl.h │ │ │ │ ├── core_armv8mml.h │ │ │ │ ├── core_cm0.h │ │ │ │ ├── core_cm0plus.h │ │ │ │ ├── core_cm1.h │ │ │ │ ├── core_cm23.h │ │ │ │ ├── core_cm3.h │ │ │ │ ├── core_cm33.h │ │ │ │ ├── core_cm4.h │ │ │ │ ├── core_cm7.h │ │ │ │ ├── core_sc000.h │ │ │ │ ├── core_sc300.h │ │ │ │ ├── mpu_armv7.h │ │ │ │ ├── mpu_armv8.h │ │ │ │ └── tz_context.h │ │ └── STM32F1xx_HAL_Driver │ │ │ ├── Inc │ │ │ ├── Legacy │ │ │ │ └── stm32_hal_legacy.h │ │ │ ├── stm32f1xx_hal.h │ │ │ ├── stm32f1xx_hal_adc.h │ │ │ ├── stm32f1xx_hal_adc_ex.h │ │ │ ├── stm32f1xx_hal_can.h │ │ │ ├── stm32f1xx_hal_cortex.h │ │ │ ├── stm32f1xx_hal_def.h │ │ │ ├── stm32f1xx_hal_dma.h │ │ │ ├── stm32f1xx_hal_dma_ex.h │ │ │ ├── stm32f1xx_hal_exti.h │ │ │ ├── stm32f1xx_hal_flash.h │ │ │ ├── stm32f1xx_hal_flash_ex.h │ │ │ ├── stm32f1xx_hal_gpio.h │ │ │ ├── stm32f1xx_hal_gpio_ex.h │ │ │ ├── stm32f1xx_hal_pwr.h │ │ │ ├── stm32f1xx_hal_rcc.h │ │ │ ├── stm32f1xx_hal_rcc_ex.h │ │ │ ├── stm32f1xx_hal_spi.h │ │ │ ├── stm32f1xx_hal_tim.h │ │ │ ├── stm32f1xx_hal_tim_ex.h │ │ │ └── stm32f1xx_hal_uart.h │ │ │ └── Src │ │ │ ├── stm32f1xx_hal.c │ │ │ ├── stm32f1xx_hal_adc.c │ │ │ ├── stm32f1xx_hal_adc_ex.c │ │ │ ├── stm32f1xx_hal_can.c │ │ │ ├── stm32f1xx_hal_cortex.c │ │ │ ├── stm32f1xx_hal_dma.c │ │ │ ├── stm32f1xx_hal_exti.c │ │ │ ├── stm32f1xx_hal_flash.c │ │ │ ├── stm32f1xx_hal_flash_ex.c │ │ │ ├── stm32f1xx_hal_gpio.c │ │ │ ├── stm32f1xx_hal_gpio_ex.c │ │ │ ├── stm32f1xx_hal_pwr.c │ │ │ ├── stm32f1xx_hal_rcc.c │ │ │ ├── stm32f1xx_hal_rcc_ex.c │ │ │ ├── stm32f1xx_hal_spi.c │ │ │ ├── stm32f1xx_hal_tim.c │ │ │ ├── stm32f1xx_hal_tim_ex.c │ │ │ └── stm32f1xx_hal_uart.c │ │ ├── Platform │ │ ├── Sensor │ │ │ └── Encoder │ │ │ │ ├── encoder_as5047_stm32.cpp │ │ │ │ └── encoder_as5047_stm32.h │ │ ├── Signal │ │ │ ├── button_stm32.cpp │ │ │ └── button_stm32.h │ │ └── Utils │ │ │ ├── Memory │ │ │ ├── eeprom_interface.h │ │ │ ├── emulated_eeprom.cpp │ │ │ └── emulated_eeprom.h │ │ │ ├── retarget.c │ │ │ ├── retarget.h │ │ │ ├── st_hardware.c │ │ │ ├── st_hardware.h │ │ │ ├── time_utils.cpp │ │ │ └── time_utils.h │ │ ├── STM32F103CBTx_FLASH.ld │ │ ├── UserApp │ │ ├── common_inc.h │ │ ├── configurations.h │ │ ├── main.cpp │ │ └── protocols │ │ │ ├── interface_can.cpp │ │ │ └── interface_uart.cpp │ │ ├── startup │ │ └── startup_stm32f103xb.s │ │ └── stlink.cfg └── SimpleFOC_version │ └── Ctrl-FOC-Lite-fw │ ├── .gitignore │ ├── .idea │ ├── .gitignore │ ├── Ctrl-FOC-Lite-fw.iml │ ├── SimpleFOC-fw.iml │ ├── deployment.xml │ ├── misc.xml │ ├── modules.xml │ ├── serialmonitor_settings.xml │ └── vcs.xml │ ├── CMakeLists.txt │ ├── Ctrl-FOC-Lite-fw.ioc │ ├── include │ └── README │ ├── lib │ ├── Arduino-FOC │ │ ├── .github │ │ │ └── workflows │ │ │ │ └── ccpp.yml │ │ ├── LICENSE │ │ ├── README.md │ │ ├── examples │ │ │ ├── hardware_specific_examples │ │ │ │ ├── Bluepill_examples │ │ │ │ │ ├── encoder │ │ │ │ │ │ └── bluepill_position_control │ │ │ │ │ │ │ └── bluepill_position_control.ino │ │ │ │ │ └── magnetic_sensor │ │ │ │ │ │ └── bluepill_position_control │ │ │ │ │ │ └── bluepill_position_control.ino │ │ │ │ ├── DRV8302_driver │ │ │ │ │ ├── 3pwm_example │ │ │ │ │ │ └── encoder │ │ │ │ │ │ │ └── full_control_serial │ │ │ │ │ │ │ └── full_control_serial.ino │ │ │ │ │ └── 6pwm_example │ │ │ │ │ │ └── encoder │ │ │ │ │ │ └── full_control_serial │ │ │ │ │ │ └── full_control_serial.ino │ │ │ │ ├── ESP32 │ │ │ │ │ ├── encoder │ │ │ │ │ │ └── esp32_position_control │ │ │ │ │ │ │ └── esp32_position_control.ino │ │ │ │ │ └── magnetic_sensor │ │ │ │ │ │ └── esp32_position_control │ │ │ │ │ │ └── esp32_position_control.ino │ │ │ │ ├── HMBGC_example │ │ │ │ │ ├── position_control │ │ │ │ │ │ └── position_control.ino │ │ │ │ │ └── voltage_control │ │ │ │ │ │ └── voltage_control.ino │ │ │ │ ├── SAMD_examples │ │ │ │ │ ├── README.md │ │ │ │ │ └── nano33IoT │ │ │ │ │ │ └── nano33IoT_velocity_control │ │ │ │ │ │ └── nano33IoT_velocity_control.ino │ │ │ │ ├── SimpleFOC-PowerShield │ │ │ │ │ └── version_v02 │ │ │ │ │ │ └── single_full_control_example │ │ │ │ │ │ └── single_full_control_example.ino │ │ │ │ └── SimpleFOCShield │ │ │ │ │ ├── version_v1 │ │ │ │ │ ├── double_full_control_example │ │ │ │ │ │ └── double_full_control_example.ino │ │ │ │ │ └── single_full_control_example │ │ │ │ │ │ └── single_full_control_example.ino │ │ │ │ │ └── version_v2 │ │ │ │ │ ├── double_full_control_example │ │ │ │ │ └── double_full_control_example.ino │ │ │ │ │ └── single_full_control_example │ │ │ │ │ └── single_full_control_example.ino │ │ │ ├── motion_control │ │ │ │ ├── open_loop_motor_control │ │ │ │ │ ├── open_loop_position_example │ │ │ │ │ │ └── open_loop_position_example.ino │ │ │ │ │ └── open_loop_velocity_example │ │ │ │ │ │ └── open_loop_velocity_example.ino │ │ │ │ ├── position_motion_control │ │ │ │ │ ├── encoder │ │ │ │ │ │ └── angle_control │ │ │ │ │ │ │ └── angle_control.ino │ │ │ │ │ ├── hall_sensor │ │ │ │ │ │ └── angle_control │ │ │ │ │ │ │ └── angle_control.ino │ │ │ │ │ └── magnetic_sensor │ │ │ │ │ │ └── angle_control │ │ │ │ │ │ └── angle_control.ino │ │ │ │ ├── torque_control │ │ │ │ │ ├── encoder │ │ │ │ │ │ ├── current_control │ │ │ │ │ │ │ └── current_control.ino │ │ │ │ │ │ └── voltage_control │ │ │ │ │ │ │ └── voltage_control.ino │ │ │ │ │ ├── hall_sensor │ │ │ │ │ │ └── voltage_control │ │ │ │ │ │ │ └── voltage_control.ino │ │ │ │ │ └── magnetic_sensor │ │ │ │ │ │ └── voltage_control │ │ │ │ │ │ └── voltage_control.ino │ │ │ │ └── velocity_motion_control │ │ │ │ │ ├── encoder │ │ │ │ │ └── velocity_control │ │ │ │ │ │ └── velocity_control.ino │ │ │ │ │ ├── hall_sensor │ │ │ │ │ └── velocity_control.ino │ │ │ │ │ └── magnetic_sensor │ │ │ │ │ └── velocity_control │ │ │ │ │ └── velocity_control.ino │ │ │ ├── motor_commands_serial_examples │ │ │ │ ├── encoder │ │ │ │ │ └── full_control_serial │ │ │ │ │ │ └── full_control_serial.ino │ │ │ │ ├── hall_sensor │ │ │ │ │ └── full_control_serial │ │ │ │ │ │ └── full_control_serial.ino │ │ │ │ └── magnetic_sensor │ │ │ │ │ └── full_control_serial │ │ │ │ │ └── full_control_serial.ino │ │ │ ├── osc_control_examples │ │ │ │ ├── README.md │ │ │ │ ├── osc_esp32_3pwm │ │ │ │ │ ├── layout1.touchosc │ │ │ │ │ └── osc_esp32_3pwm.ino │ │ │ │ ├── osc_esp32_fullcontrol │ │ │ │ │ ├── osc_esp32_fullcontrol.ino │ │ │ │ │ ├── osc_fullcontrol.pd │ │ │ │ │ └── ssid.h_rename_me │ │ │ │ └── osc_fullcontrol_screenshot.png │ │ │ └── utils │ │ │ │ ├── calibration │ │ │ │ ├── alignment_and_cogging_test │ │ │ │ │ └── alignment_and_cogging_test.ino │ │ │ │ ├── find_pole_pair_number │ │ │ │ │ ├── encoder │ │ │ │ │ │ └── find_pole_pairs_number │ │ │ │ │ │ │ └── find_pole_pairs_number.ino │ │ │ │ │ └── magnetic_sensor │ │ │ │ │ │ └── find_pole_pairs_number │ │ │ │ │ │ └── find_pole_pairs_number.ino │ │ │ │ └── find_sensor_offset_and_direction │ │ │ │ │ └── find_sensor_offset_and_direction.ino │ │ │ │ ├── communication_test │ │ │ │ ├── commander │ │ │ │ │ ├── commander_extend_example │ │ │ │ │ │ └── commander_extend_example.ino │ │ │ │ │ ├── commander_no_serial │ │ │ │ │ │ └── commander_no_serial.ino │ │ │ │ │ └── commander_tune_custom_loop │ │ │ │ │ │ └── commander_tune_custom_loop.ino │ │ │ │ └── step_dir │ │ │ │ │ ├── step_dir_listener_simple │ │ │ │ │ └── step_dir_listener_simple.ino │ │ │ │ │ ├── step_dir_listener_software_interrupt │ │ │ │ │ └── step_dir_listener_software_interrupt.ino │ │ │ │ │ └── step_dir_motor_example │ │ │ │ │ └── step_dir_motor_example.ino │ │ │ │ ├── current_sense_test │ │ │ │ └── inline_current_sense_test │ │ │ │ │ └── inline_current_sense_test.ino │ │ │ │ ├── driver_standalone_test │ │ │ │ ├── bldc_driver_3pwm_standalone │ │ │ │ │ └── bldc_driver_3pwm_standalone.ino │ │ │ │ ├── bldc_driver_6pwm_standalone │ │ │ │ │ └── bldc_driver_6pwm_standalone.ino │ │ │ │ ├── stepper_driver_2pwm_standalone │ │ │ │ │ └── stepper_driver_2pwm_standalone.ino │ │ │ │ └── stepper_driver_4pwm_standalone │ │ │ │ │ └── stepper_driver_4pwm_standalone.ino │ │ │ │ └── sensor_test │ │ │ │ ├── encoder │ │ │ │ ├── encoder_example │ │ │ │ │ └── encoder_example.ino │ │ │ │ └── encoder_software_interrupts_example │ │ │ │ │ └── encoder_software_interrupts_example.ino │ │ │ │ ├── hall_sensors │ │ │ │ ├── hall_sensor_example │ │ │ │ │ └── hall_sensor_example.ino │ │ │ │ └── hall_sensor_software_interrupts_example │ │ │ │ │ └── hall_sensors_software_interrupt_example.ino │ │ │ │ └── magnetic_sensors │ │ │ │ ├── magnetic_sensor_analog_example │ │ │ │ ├── find_raw_min_max │ │ │ │ │ └── find_raw_min_max.ino │ │ │ │ └── magnetic_sensor_analog │ │ │ │ │ └── magnetic_sensor_analog.ino │ │ │ │ ├── magnetic_sensor_i2c_dual_bus_examples │ │ │ │ ├── esp32_i2c_dual_bus_example │ │ │ │ │ └── esp32_i2c_dual_bus_example.ino │ │ │ │ └── stm32_i2c_dual_bus_example │ │ │ │ │ └── stm32_i2c_dual_bus_example.ino │ │ │ │ ├── magnetic_sensor_i2c_example │ │ │ │ └── magnetic_sensor_i2c_example.ino │ │ │ │ ├── magnetic_sensor_pwm_example │ │ │ │ ├── find_raw_min_max │ │ │ │ │ └── find_raw_min_max.ino │ │ │ │ ├── magnetic_sensor_pwm │ │ │ │ │ └── magnetic_sensor_pwm.ino │ │ │ │ └── magnetic_sensor_pwm_software_interrupt │ │ │ │ │ └── magnetic_sensor_pwm_software_interrupt.ino │ │ │ │ ├── magnetic_sensor_spi_alt_example │ │ │ │ └── magnetic_sensor_spi_alt_example.ino │ │ │ │ └── magnetic_sensor_spi_example │ │ │ │ └── magnetic_sensor_spi_example.ino │ │ ├── keywords.txt │ │ ├── library.properties │ │ └── src │ │ │ ├── BLDCMotor.cpp │ │ │ ├── BLDCMotor.h │ │ │ ├── SimpleFOC.h │ │ │ ├── StepperMotor.cpp │ │ │ ├── StepperMotor.h │ │ │ ├── common │ │ │ ├── base_classes │ │ │ │ ├── BLDCDriver.h │ │ │ │ ├── CurrentSense.cpp │ │ │ │ ├── CurrentSense.h │ │ │ │ ├── FOCMotor.cpp │ │ │ │ ├── FOCMotor.h │ │ │ │ ├── Sensor.cpp │ │ │ │ ├── Sensor.h │ │ │ │ └── StepperDriver.h │ │ │ ├── defaults.h │ │ │ ├── foc_utils.cpp │ │ │ ├── foc_utils.h │ │ │ ├── lowpass_filter.cpp │ │ │ ├── lowpass_filter.h │ │ │ ├── pid.cpp │ │ │ ├── pid.h │ │ │ ├── time_utils.cpp │ │ │ └── time_utils.h │ │ │ ├── communication │ │ │ ├── Commander.cpp │ │ │ ├── Commander.h │ │ │ ├── StepDirListener.cpp │ │ │ ├── StepDirListener.h │ │ │ └── commands.h │ │ │ ├── current_sense │ │ │ ├── InlineCurrentSense.cpp │ │ │ ├── InlineCurrentSense.h │ │ │ ├── hardware_api.h │ │ │ └── hardware_specific │ │ │ │ └── generic_mcu.cpp │ │ │ ├── drivers │ │ │ ├── BLDCDriver3PWM.cpp │ │ │ ├── BLDCDriver3PWM.h │ │ │ ├── BLDCDriver6PWM.cpp │ │ │ ├── BLDCDriver6PWM.h │ │ │ ├── StepperDriver2PWM.cpp │ │ │ ├── StepperDriver2PWM.h │ │ │ ├── StepperDriver4PWM.cpp │ │ │ ├── StepperDriver4PWM.h │ │ │ ├── hardware_api.h │ │ │ └── hardware_specific │ │ │ │ ├── atmega2560_mcu.cpp │ │ │ │ ├── atmega328_mcu.cpp │ │ │ │ ├── due_mcu.cpp │ │ │ │ ├── esp32_mcu.cpp │ │ │ │ ├── generic_mcu.cpp │ │ │ │ ├── rp2040_mcu.cpp │ │ │ │ ├── samd21_mcu.cpp │ │ │ │ ├── samd51_mcu.cpp │ │ │ │ ├── samd_mcu.cpp │ │ │ │ ├── samd_mcu.h │ │ │ │ ├── stm32_mcu.cpp │ │ │ │ └── teensy_mcu.cpp │ │ │ └── sensors │ │ │ ├── Encoder.cpp │ │ │ ├── Encoder.h │ │ │ ├── HallSensor.cpp │ │ │ ├── HallSensor.h │ │ │ ├── MagneticSensorAnalog.cpp │ │ │ ├── MagneticSensorAnalog.h │ │ │ ├── MagneticSensorI2C.cpp │ │ │ ├── MagneticSensorI2C.h │ │ │ ├── MagneticSensorPWM.cpp │ │ │ ├── MagneticSensorPWM.h │ │ │ ├── MagneticSensorSPI.cpp │ │ │ └── MagneticSensorSPI.h │ ├── README │ └── STM32_Examples │ │ ├── STM32_Examples.h │ │ ├── examples │ │ ├── Analog │ │ │ ├── AnalogInOutSerial │ │ │ │ └── AnalogInOutSerial.ino │ │ │ ├── AnalogInSerial │ │ │ │ └── AnalogInSerial.ino │ │ │ ├── AnalogInput │ │ │ │ └── AnalogInput.ino │ │ │ ├── Calibration │ │ │ │ └── Calibration.ino │ │ │ ├── Fading │ │ │ │ └── Fading.ino │ │ │ └── Smoothing │ │ │ │ └── Smoothing.ino │ │ ├── Communication │ │ │ ├── ASCIITable │ │ │ │ └── ASCIITable.ino │ │ │ ├── Dimmer │ │ │ │ └── Dimmer.ino │ │ │ ├── Graph │ │ │ │ └── Graph.ino │ │ │ ├── MIDI │ │ │ │ └── Midi.ino │ │ │ ├── PhysicalPixel │ │ │ │ └── PhysicalPixel.ino │ │ │ ├── SerialCallResponse │ │ │ │ └── SerialCallResponse.ino │ │ │ ├── SerialCallResponseASCII │ │ │ │ └── SerialCallResponseASCII.ino │ │ │ ├── SerialPassthrough │ │ │ │ └── SerialPassthrough.ino │ │ │ ├── USB-uart-w-signals │ │ │ │ ├── USB-uart-w-signals.ino │ │ │ │ └── readme.md │ │ │ └── VirtualColorMixer │ │ │ │ └── VirtualColorMixer.ino │ │ ├── Control │ │ │ ├── Arrays │ │ │ │ └── Arrays.ino │ │ │ ├── ForLoopIteration │ │ │ │ └── ForLoopIteration.ino │ │ │ ├── IfStatementConditional │ │ │ │ └── IfStatementConditional.ino │ │ │ ├── WhileStatementConditional │ │ │ │ └── WhileStatementConditional.ino │ │ │ ├── switchCase │ │ │ │ └── switchCase.ino │ │ │ └── switchCase2 │ │ │ │ └── switchCase2.ino │ │ ├── Digital │ │ │ ├── Blink │ │ │ │ └── Blink.ino │ │ │ ├── BlinkWithoutDelay │ │ │ │ └── BlinkWithoutDelay.ino │ │ │ ├── Button │ │ │ │ └── Button.ino │ │ │ ├── Debounce │ │ │ │ └── Debounce.ino │ │ │ ├── MapleMorse │ │ │ │ └── MapleMorse.ino │ │ │ └── StateChangeDetection │ │ │ │ └── StateChangeDetection.ino │ │ ├── Display │ │ │ ├── RowColumnScanning │ │ │ │ └── RowColumnScanning.ino │ │ │ └── barGraph │ │ │ │ └── barGraph.ino │ │ ├── General │ │ │ ├── Blink │ │ │ │ └── Blink.ino │ │ │ ├── BlinkNcount │ │ │ │ └── BlinkNcount.ino │ │ │ ├── FadingOnboard │ │ │ │ └── FadingOnboard.ino │ │ │ ├── IntegerInput │ │ │ │ └── IntegerInput.ino │ │ │ ├── IntegerInput_FloatOutput │ │ │ │ └── IntegerInput_FloatOutput.ino │ │ │ ├── InternalTempSensor │ │ │ │ └── InternalTempSensor.ino │ │ │ ├── PrimeNos │ │ │ │ └── PrimeNos.ino │ │ │ ├── PrimeNos2 │ │ │ │ └── PrimeNos2.ino │ │ │ ├── PrimeNos3 │ │ │ │ └── PrimeNos3.ino │ │ │ ├── Print_Binary │ │ │ │ └── Print_Binary.ino │ │ │ ├── Print_Float │ │ │ │ └── Print_Float.ino │ │ │ ├── Print_HEX │ │ │ │ └── Print_HEX.ino │ │ │ ├── SerialReadUntil │ │ │ │ └── SerialReadUntil.ino │ │ │ ├── StringEx_Parsing │ │ │ │ └── StringEx_Parsing.ino │ │ │ ├── USB_ASCII │ │ │ │ └── USB_ASCII.ino │ │ │ └── strtol_DecEquivalents │ │ │ │ └── strtol_DecEquivalents.ino │ │ ├── Sensors │ │ │ ├── HardTimerAsEncoder │ │ │ │ └── HardTimerAsEncoder.ino │ │ │ ├── HardwareTimerOnePulseMode │ │ │ │ └── HardwareTimerOnePulseMode.ino │ │ │ ├── HardwareTimerPWMInput │ │ │ │ └── HardwareTimerPWMInput.ino │ │ │ └── Knock │ │ │ │ └── Knock.ino │ │ └── Stubs │ │ │ ├── AnalogReadPWMWrite │ │ │ └── AnalogReadPWMWrite.ino │ │ │ ├── AnalogReadSerial │ │ │ └── AnalogReadSerial.ino │ │ │ ├── BareMinumum │ │ │ └── BareMinumum.ino │ │ │ ├── DigitalReadSerial │ │ │ └── DigitalReadSerial.ino │ │ │ ├── DigitalReadWrite │ │ │ └── DigitalReadWrite.ino │ │ │ └── HelloWorld │ │ │ └── HelloWorld.ino │ │ ├── keywords.txt │ │ └── library.properties │ ├── platformio.ini │ ├── src │ └── main.cpp │ └── test │ └── README ├── 4.Docs ├── 1.Datasheets │ ├── AS5047P-Datasheet.pdf │ ├── MT6816_Rev.1.3.pdf │ ├── STM32 Nucleo │ │ ├── MB1136C_schematic_layout │ │ │ ├── Connectors.SchDoc │ │ │ ├── MB1136.PcbDoc │ │ │ ├── MB1136.PrjPCB │ │ │ ├── MB1136.SCHLIB │ │ │ ├── MB1136.SchDoc │ │ │ ├── MB1136.pdf │ │ │ ├── MCU_64.SchDoc │ │ │ ├── Nucleo_64_mechanic_revC.PcbDoc │ │ │ ├── ST_LINK_V2-1.SCHDOC │ │ │ └── __Previews │ │ │ │ ├── Connectors.SchDocPreview │ │ │ │ ├── MB1136.PcbDocPreview │ │ │ │ ├── MB1136.SchDocPreview │ │ │ │ ├── MCU_64.SchDocPreview │ │ │ │ ├── Nucleo_64_mechanic_revC.PcbDocPreview │ │ │ │ └── ST_LINK_V2-1.SCHDOCPreview │ │ ├── PinMap1.png │ │ ├── PinMap2.png │ │ └── STM32 Nucleo-64 boards.pdf │ ├── drv8301.pdf │ ├── drv8302.pdf │ ├── drv8313.pdf │ ├── ina240.pdf │ ├── me3116.pdf │ ├── stm32f103cb.pdf │ └── tl431.pdf └── 2.Images │ ├── img1.jpg │ ├── img2.jpg │ └── img3.jpg └── README.md /1.Hardware/Ctrl-FOC-Lite/Ctrl-FOC-Lite.PcbDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/1.Hardware/Ctrl-FOC-Lite/Ctrl-FOC-Lite.PcbDoc -------------------------------------------------------------------------------- /1.Hardware/Ctrl-FOC-Lite/Ctrl-FOC-Lite.PrjPCBStructure: -------------------------------------------------------------------------------- 1 | Record=TopLevelDocument|FileName=Main.SchDoc|SheetNumber=1 2 | -------------------------------------------------------------------------------- /1.Hardware/Ctrl-FOC-Lite/Main.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/1.Hardware/Ctrl-FOC-Lite/Main.SchDoc -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.gitignore: -------------------------------------------------------------------------------- 1 | cmake-build-*/ 2 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/.gitignore: -------------------------------------------------------------------------------- 1 | # Default ignored files 2 | /shelf/ 3 | /workspace.xml 4 | # Editor-based HTTP Client requests 5 | /httpRequests/ 6 | # Datasource local storage ignored files 7 | /dataSources/ 8 | /dataSources.local.xml 9 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/.name: -------------------------------------------------------------------------------- 1 | Ctrl-FOC-Lite-fw -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/Ctrl-FOC-Lite-fw2.iml: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/deployment.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/inspectionProfiles/Project_Default.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 6 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/misc.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/modules.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/serialmonitor_settings.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.idea/vcs.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/.project: -------------------------------------------------------------------------------- 1 | 2 | 3 | Ctrl-FOC-Lite-fw 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 | org.eclipse.cdt.core.cnature 23 | org.eclipse.cdt.managedbuilder.core.managedBuildNature 24 | org.eclipse.cdt.managedbuilder.core.ScannerConfigNature 25 | fr.ac6.mcu.ide.core.MCUProjectNature 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Core/Inc/adc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file adc.h 4 | * @brief This file contains all the function prototypes for 5 | * the adc.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2022 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __ADC_H__ 21 | #define __ADC_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern ADC_HandleTypeDef hadc1; 35 | 36 | /* USER CODE BEGIN Private defines */ 37 | 38 | /* USER CODE END Private defines */ 39 | 40 | void MX_ADC1_Init(void); 41 | 42 | /* USER CODE BEGIN Prototypes */ 43 | extern uint16_t adcData[2]; 44 | 45 | /* USER CODE END Prototypes */ 46 | 47 | #ifdef __cplusplus 48 | } 49 | #endif 50 | 51 | #endif /* __ADC_H__ */ 52 | 53 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 54 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Core/Inc/can.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file can.h 4 | * @brief This file contains all the function prototypes for 5 | * the can.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2022 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __CAN_H__ 21 | #define __CAN_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern CAN_HandleTypeDef hcan; 35 | 36 | /* USER CODE BEGIN Private defines */ 37 | 38 | /* USER CODE END Private defines */ 39 | 40 | void MX_CAN_Init(void); 41 | 42 | /* USER CODE BEGIN Prototypes */ 43 | 44 | /* USER CODE END Prototypes */ 45 | 46 | #ifdef __cplusplus 47 | } 48 | #endif 49 | 50 | #endif /* __CAN_H__ */ 51 | 52 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 53 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Core/Inc/dma.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file dma.h 4 | * @brief This file contains all the function prototypes for 5 | * the dma.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2022 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __DMA_H__ 21 | #define __DMA_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* DMA memory to memory transfer handles -------------------------------------*/ 31 | 32 | /* USER CODE BEGIN Includes */ 33 | 34 | /* USER CODE END Includes */ 35 | 36 | /* USER CODE BEGIN Private defines */ 37 | 38 | /* USER CODE END Private defines */ 39 | 40 | void MX_DMA_Init(void); 41 | 42 | /* USER CODE BEGIN Prototypes */ 43 | 44 | /* USER CODE END Prototypes */ 45 | 46 | #ifdef __cplusplus 47 | } 48 | #endif 49 | 50 | #endif /* __DMA_H__ */ 51 | 52 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 53 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Core/Inc/gpio.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file gpio.h 4 | * @brief This file contains all the function prototypes for 5 | * the gpio.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2022 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __GPIO_H__ 21 | #define __GPIO_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | /* USER CODE BEGIN Private defines */ 35 | 36 | /* USER CODE END Private defines */ 37 | 38 | void MX_GPIO_Init(void); 39 | 40 | /* USER CODE BEGIN Prototypes */ 41 | 42 | /* USER CODE END Prototypes */ 43 | 44 | #ifdef __cplusplus 45 | } 46 | #endif 47 | #endif /*__ GPIO_H__ */ 48 | 49 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 50 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Core/Inc/spi.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file spi.h 4 | * @brief This file contains all the function prototypes for 5 | * the spi.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2022 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __SPI_H__ 21 | #define __SPI_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern SPI_HandleTypeDef hspi1; 35 | 36 | /* USER CODE BEGIN Private defines */ 37 | 38 | /* USER CODE END Private defines */ 39 | 40 | void MX_SPI1_Init(void); 41 | 42 | /* USER CODE BEGIN Prototypes */ 43 | 44 | /* USER CODE END Prototypes */ 45 | 46 | #ifdef __cplusplus 47 | } 48 | #endif 49 | 50 | #endif /* __SPI_H__ */ 51 | 52 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 53 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/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 DMA1_Channel1_IRQHandler(void); 60 | void DMA1_Channel6_IRQHandler(void); 61 | void DMA1_Channel7_IRQHandler(void); 62 | void ADC1_2_IRQHandler(void); 63 | void USB_LP_CAN1_RX0_IRQHandler(void); 64 | void USART2_IRQHandler(void); 65 | /* USER CODE BEGIN EFP */ 66 | 67 | /* USER CODE END EFP */ 68 | 69 | #ifdef __cplusplus 70 | } 71 | #endif 72 | 73 | #endif /* __STM32F1xx_IT_H */ 74 | 75 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 76 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Core/Inc/tim.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file tim.h 4 | * @brief This file contains all the function prototypes for 5 | * the tim.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2022 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __TIM_H__ 21 | #define __TIM_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern TIM_HandleTypeDef htim1; 35 | extern TIM_HandleTypeDef htim3; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_TIM1_Init(void); 42 | void MX_TIM3_Init(void); 43 | 44 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); 45 | 46 | /* USER CODE BEGIN Prototypes */ 47 | 48 | /* USER CODE END Prototypes */ 49 | 50 | #ifdef __cplusplus 51 | } 52 | #endif 53 | 54 | #endif /* __TIM_H__ */ 55 | 56 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 57 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Core/Inc/usart.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usart.h 4 | * @brief This file contains all the function prototypes for 5 | * the usart.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2022 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __USART_H__ 21 | #define __USART_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern UART_HandleTypeDef huart2; 35 | 36 | /* USER CODE BEGIN Private defines */ 37 | #define BUFFER_SIZE 128 38 | 39 | extern DMA_HandleTypeDef hdma_usart2_rx; 40 | extern DMA_HandleTypeDef hdma_usart2_tx; 41 | extern volatile uint8_t rxLen; 42 | extern uint8_t rx_buffer[BUFFER_SIZE]; 43 | /* USER CODE END Private defines */ 44 | 45 | void MX_USART2_UART_Init(void); 46 | 47 | /* USER CODE BEGIN Prototypes */ 48 | extern void (*OnRecvEnd)(uint8_t *data, uint16_t len); 49 | void Uart_SetRxCpltCallBack(void(*xerc)(uint8_t *, uint16_t)); 50 | /* USER CODE END Prototypes */ 51 | 52 | #ifdef __cplusplus 53 | } 54 | #endif 55 | 56 | #endif /* __USART_H__ */ 57 | 58 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 59 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Core/Src/dma.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file dma.c 4 | * @brief This file provides code for the configuration 5 | * of all the requested memory to memory DMA transfers. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2022 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 | /* Includes ------------------------------------------------------------------*/ 21 | #include "dma.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | /*----------------------------------------------------------------------------*/ 28 | /* Configure DMA */ 29 | /*----------------------------------------------------------------------------*/ 30 | 31 | /* USER CODE BEGIN 1 */ 32 | 33 | /* USER CODE END 1 */ 34 | 35 | /** 36 | * Enable DMA controller clock 37 | */ 38 | void MX_DMA_Init(void) 39 | { 40 | 41 | /* DMA controller clock enable */ 42 | __HAL_RCC_DMA1_CLK_ENABLE(); 43 | 44 | /* DMA interrupt init */ 45 | /* DMA1_Channel1_IRQn interrupt configuration */ 46 | HAL_NVIC_SetPriority(DMA1_Channel1_IRQn, 0, 0); 47 | HAL_NVIC_EnableIRQ(DMA1_Channel1_IRQn); 48 | /* DMA1_Channel6_IRQn interrupt configuration */ 49 | HAL_NVIC_SetPriority(DMA1_Channel6_IRQn, 3, 0); 50 | HAL_NVIC_EnableIRQ(DMA1_Channel6_IRQn); 51 | /* DMA1_Channel7_IRQn interrupt configuration */ 52 | HAL_NVIC_SetPriority(DMA1_Channel7_IRQn, 3, 0); 53 | HAL_NVIC_EnableIRQ(DMA1_Channel7_IRQn); 54 | 55 | } 56 | 57 | /* USER CODE BEGIN 2 */ 58 | 59 | /* USER CODE END 2 */ 60 | 61 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 62 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl-FOC-Lite-fw.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Ctrl-FOC-Lite-fw 5 | STM32F103CBTx 6 | SWD 7 | ST-LinkV2-1 8 | 9 | 10 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Sensor/Encoder/Instances/encoder_as5047.cpp: -------------------------------------------------------------------------------- 1 | #include "encoder_as5047.h" 2 | #include "spi.h" 3 | 4 | 5 | EncoderAS5047Base::EncoderAS5047Base() 6 | { 7 | angle_register = 0x3FFF; 8 | cpr = 16384; 9 | bit_resolution = 14; 10 | data_start_bit = 13; 11 | command_rw_bit = 14; 12 | command_parity_bit = 15; 13 | } 14 | 15 | 16 | void EncoderAS5047Base::Init() 17 | { 18 | SpiInit(); 19 | InitVars(); 20 | } 21 | 22 | 23 | float EncoderAS5047Base::GetSensorAngle() 24 | { 25 | return ((float) GetRawData() / (float) cpr) * _2PI; 26 | } 27 | 28 | 29 | uint16_t EncoderAS5047Base::GetRawData() 30 | { 31 | uint16_t command = angle_register; 32 | 33 | if (command_rw_bit > 0) 34 | { 35 | command = angle_register | (1 << command_rw_bit); 36 | } 37 | if (command_parity_bit > 0) 38 | { 39 | //Add a parity bit on the the MSB 40 | command |= ((uint16_t) SpiCalcEvenParity(command) << command_parity_bit); 41 | } 42 | 43 | SpiTransmitAndRead16Bits(command); 44 | // the minimum time possible in plain arduino. 350ns is the required time for AMS sensors, 80ns for MA730, MA702 45 | delayMicroseconds(1); 46 | uint16_t register_value = SpiTransmitAndRead16Bits(0x00); 47 | 48 | //this should shift data to the rightmost bits of the word 49 | register_value = register_value >> (1 + data_start_bit - bit_resolution); 50 | const static uint16_t data_mask = 0xFFFF >> (16 - bit_resolution); 51 | 52 | // Return the data, stripping the non data (e.g parity) bits 53 | return register_value & data_mask; 54 | } 55 | 56 | 57 | uint8_t EncoderAS5047Base::SpiCalcEvenParity(uint16_t value) 58 | { 59 | uint8_t cnt = 0; 60 | uint8_t i; 61 | 62 | for (i = 0; i < 16; i++) 63 | { 64 | if (value & 0x1) cnt++; 65 | value >>= 1; 66 | } 67 | 68 | return cnt & 0x1; 69 | } 70 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Sensor/Encoder/Instances/encoder_as5047.h: -------------------------------------------------------------------------------- 1 | #ifndef MAGNETICSENSORSPI_LIB_H 2 | #define MAGNETICSENSORSPI_LIB_H 3 | 4 | #include "Ctrl/Sensor/Encoder/encoder_base.h" 5 | #include "Ctrl/Utils/foc_utils.h" 6 | 7 | 8 | class EncoderAS5047Base : public EncoderBase 9 | { 10 | public: 11 | EncoderAS5047Base(); 12 | 13 | void Init(); 14 | 15 | 16 | private: 17 | uint16_t GetRawData(); 18 | uint8_t SpiCalcEvenParity(uint16_t value); 19 | 20 | uint8_t bit_resolution; //!< the number of bites of angle data 21 | uint16_t cpr; //!< Maximum range of the magnetic sensor 22 | // spi variables 23 | uint16_t angle_register; //!< SPI angle register to read 24 | uint8_t command_parity_bit; //!< the bit where parity flag is stored in command 25 | uint8_t command_rw_bit; //!< the bit where read/write flag is stored in command 26 | uint8_t data_start_bit; //!< the the position of first bit 27 | 28 | float GetSensorAngle() override; 29 | 30 | 31 | /***** Port Specified Implements *****/ 32 | virtual void SpiInit() = 0; 33 | 34 | virtual uint16_t SpiTransmitAndRead16Bits(uint16_t _dataTx) = 0; 35 | }; 36 | 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Sensor/Encoder/encoder_base.cpp: -------------------------------------------------------------------------------- 1 | #include "encoder_base.h" 2 | #include "Ctrl/Utils/foc_utils.h" 3 | 4 | inline float abs(float _v) 5 | { 6 | return _v >= 0 ? _v : -_v; 7 | } 8 | 9 | void EncoderBase::update() 10 | { 11 | float val = GetSensorAngle(); 12 | angle_prev_ts = micros(); 13 | float d_angle = val - angle_prev; 14 | // if overflow happened track it as full rotation 15 | if (abs(d_angle) > (0.8f * _2PI)) 16 | full_rotations += (d_angle > 0) ? -1 : 1; 17 | angle_prev = val; 18 | } 19 | 20 | 21 | /** get current angular velocity (rad/s) */ 22 | float EncoderBase::getVelocity() 23 | { 24 | // calculate sample time 25 | float Ts = (float) (angle_prev_ts - vel_angle_prev_ts) * 1e-6f; 26 | // quick fix for strange cases (micros overflow) 27 | if (Ts <= 0) Ts = 1e-3f; 28 | // velocity calculation 29 | float vel = ((float) (full_rotations - vel_full_rotations) * _2PI + (angle_prev - vel_angle_prev)) / Ts; 30 | // save variables for future pass 31 | vel_angle_prev = angle_prev; 32 | vel_full_rotations = full_rotations; 33 | vel_angle_prev_ts = angle_prev_ts; 34 | return vel; 35 | } 36 | 37 | void EncoderBase::InitVars() 38 | { 39 | // initialize all the internal variables of EncoderBase to ensure a "smooth" startup (without a 'jump' from zero) 40 | GetSensorAngle(); // call once 41 | delayMicroseconds(1); 42 | vel_angle_prev = GetSensorAngle(); // call again 43 | vel_angle_prev_ts = micros(); 44 | delay(1); 45 | GetSensorAngle(); // call once 46 | delayMicroseconds(1); 47 | angle_prev = GetSensorAngle(); // call again 48 | angle_prev_ts = micros(); 49 | } 50 | 51 | 52 | float EncoderBase::getMechanicalAngle() 53 | { 54 | return angle_prev; 55 | } 56 | 57 | 58 | float EncoderBase::GetAngle() 59 | { 60 | return (float) full_rotations * _2PI + angle_prev; 61 | } 62 | 63 | 64 | int32_t EncoderBase::getFullRotations() 65 | { 66 | return full_rotations; 67 | } 68 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Signal/button_base.cpp: -------------------------------------------------------------------------------- 1 | #include "button_base.h" 2 | 3 | void ButtonBase::Tick(uint32_t _timeElapseMillis) 4 | { 5 | timer += _timeElapseMillis; 6 | bool pinIO = ReadButtonPinIO(id); 7 | 8 | if (lastPinIO != pinIO) 9 | { 10 | if (pinIO) 11 | { 12 | OnEventFunc(UP); 13 | if (timer - pressTime > longPressTime) 14 | OnEventFunc(LONG_PRESS); 15 | else 16 | OnEventFunc(CLICK); 17 | } else 18 | { 19 | OnEventFunc(DOWN); 20 | pressTime = timer; 21 | } 22 | 23 | lastPinIO = pinIO; 24 | } 25 | } 26 | 27 | void ButtonBase::SetOnEventListener(void (* _callback)(Event)) 28 | { 29 | lastPinIO = ReadButtonPinIO(id); 30 | 31 | OnEventFunc = _callback; 32 | } 33 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Signal/button_base.h: -------------------------------------------------------------------------------- 1 | #ifndef CTRL_STEP_FW_BUTTON_BASE_H 2 | #define CTRL_STEP_FW_BUTTON_BASE_H 3 | 4 | #include 5 | 6 | class ButtonBase 7 | { 8 | public: 9 | enum Event 10 | { 11 | UP, 12 | DOWN, 13 | LONG_PRESS, 14 | CLICK 15 | }; 16 | 17 | explicit ButtonBase(uint8_t _id) : 18 | id(_id) 19 | {} 20 | 21 | ButtonBase(uint8_t _id, uint32_t _longPressTime) : 22 | id(_id), longPressTime(_longPressTime) 23 | {} 24 | 25 | void Tick(uint32_t _timeElapseMillis); 26 | void SetOnEventListener(void (* _callback)(Event)); 27 | 28 | protected: 29 | uint8_t id; 30 | bool lastPinIO{}; 31 | uint32_t timer=0; 32 | uint32_t pressTime{}; 33 | uint32_t longPressTime = 2000; 34 | 35 | void (* OnEventFunc)(Event){}; 36 | 37 | virtual bool ReadButtonPinIO(uint8_t _id) = 0; 38 | }; 39 | 40 | #endif 41 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Utils/foc_utils.h: -------------------------------------------------------------------------------- 1 | #ifndef FOCUTILS_LIB_H 2 | #define FOCUTILS_LIB_H 3 | #include "Platform/Utils/time_utils.h" 4 | 5 | // sign function 6 | #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) 7 | #define _round(x) ((x)>=0?(long)((x)+0.5f):(long)((x)-0.5f)) 8 | #define _constrain(amt, low, high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) 9 | #define _sqrt(a) (_sqrtApprox(a)) 10 | #define _isset(a) ( (a) != (NOT_SET) ) 11 | #define _UNUSED(v) (void) (v) 12 | 13 | // utility defines 14 | #define _2_SQRT3 1.15470053838f 15 | #define _SQRT3 1.73205080757f 16 | #define _1_SQRT3 0.57735026919f 17 | #define _SQRT3_2 0.86602540378f 18 | #define _SQRT2 1.41421356237f 19 | #define _120_D2R 2.09439510239f 20 | #define _PI 3.14159265359f 21 | #define _PI_2 1.57079632679f 22 | #define _PI_3 1.0471975512f 23 | #define _2PI 6.28318530718f 24 | #define _3PI_2 4.71238898038f 25 | #define _PI_6 0.52359877559f 26 | 27 | #define NOT_SET -12345.0 28 | #define _HIGH_IMPEDANCE 0 29 | #define _HIGH_Z _HIGH_IMPEDANCE 30 | #define _ACTIVE 1 31 | 32 | // dq current structure 33 | struct DQCurrent_s 34 | { 35 | float d; 36 | float q; 37 | }; 38 | // phase current structure 39 | struct PhaseCurrent_s 40 | { 41 | float a; 42 | float b; 43 | float c; 44 | }; 45 | // dq voltage structs 46 | struct DQVoltage_s 47 | { 48 | float d; 49 | float q; 50 | }; 51 | 52 | 53 | /** 54 | * Function approximating the sine calculation by using fixed size array 55 | * - execution time ~40us (Arduino UNO) 56 | * 57 | * @param a angle in between 0 and 2PI 58 | */ 59 | float _sin(float a); 60 | /** 61 | * Function approximating cosine calculation by using fixed size array 62 | * - execution time ~50us (Arduino UNO) 63 | * 64 | * @param a angle in between 0 and 2PI 65 | */ 66 | float _cos(float a); 67 | 68 | /** 69 | * normalizing radian angle to [0,2PI] 70 | * @param angle - angle to be normalized 71 | */ 72 | float _normalizeAngle(float angle); 73 | 74 | 75 | /** 76 | * Electrical angle calculation 77 | * 78 | * @param shaft_angle - shaft angle of the motor 79 | * @param pole_pairs - number of pole pairs 80 | */ 81 | float _electricalAngle(float shaft_angle, int pole_pairs); 82 | 83 | /** 84 | * Function approximating square root function 85 | * - using fast inverse square root 86 | * 87 | * @param value - number 88 | */ 89 | float _sqrtApprox(float value); 90 | 91 | #endif -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Utils/lowpass_filter.cpp: -------------------------------------------------------------------------------- 1 | #include "lowpass_filter.h" 2 | 3 | LowPassFilter::LowPassFilter(float time_constant) 4 | : Tf(time_constant), y_prev(0.0f) 5 | { 6 | timestamp_prev = micros(); 7 | } 8 | 9 | 10 | float LowPassFilter::operator()(float x) 11 | { 12 | unsigned long timestamp = micros(); 13 | float dt = ((float) timestamp - (float) timestamp_prev) * 1e-6f; 14 | 15 | if (dt < 0.0f) dt = 1e-3f; 16 | else if (dt > 0.3f) 17 | { 18 | y_prev = x; 19 | timestamp_prev = timestamp; 20 | return x; 21 | } 22 | 23 | float alpha = Tf / (Tf + dt); 24 | float y = alpha * y_prev + (1.0f - alpha) * x; 25 | y_prev = y; 26 | timestamp_prev = timestamp; 27 | return y; 28 | } 29 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Utils/lowpass_filter.h: -------------------------------------------------------------------------------- 1 | #ifndef LOWPASS_FILTER_H 2 | #define LOWPASS_FILTER_H 3 | 4 | 5 | #include "Platform/Utils/time_utils.h" 6 | #include "foc_utils.h" 7 | 8 | /** 9 | * Low pass filter class 10 | */ 11 | class LowPassFilter 12 | { 13 | public: 14 | /** 15 | * @param Tf - Low pass filter time constant 16 | */ 17 | LowPassFilter(float Tf); 18 | ~LowPassFilter() = default; 19 | 20 | float operator()(float x); 21 | float Tf; //!< Low pass filter time constant 22 | 23 | protected: 24 | unsigned long timestamp_prev; //!< Last execution timestamp 25 | float y_prev; //!< filtered value in previous execution step 26 | }; 27 | 28 | #endif // LOWPASS_FILTER_H -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Utils/pid.cpp: -------------------------------------------------------------------------------- 1 | #include "pid.h" 2 | 3 | PIDController::PIDController(float P, float I, float D, float ramp, float limit) 4 | : P(P), I(I), D(D), output_ramp(ramp) // output derivative limit [volts/second] 5 | , limit(limit) // output supply limit [volts] 6 | , error_prev(0.0f), output_prev(0.0f), integral_prev(0.0f) 7 | { 8 | timestamp_prev = micros(); 9 | } 10 | 11 | // PID controller function 12 | float PIDController::operator()(float error) 13 | { 14 | // calculate the time from the last call 15 | unsigned long timestamp_now = micros(); 16 | float Ts = (timestamp_now - timestamp_prev) * 1e-6f; 17 | // quick fix for strange cases (micros overflow) 18 | if (Ts <= 0 || Ts > 0.5f) Ts = 1e-3f; 19 | 20 | // u(s) = (P + I/s + Ds)e(s) 21 | // Discrete implementations 22 | // proportional part 23 | // u_p = P *e(k) 24 | float proportional = P * error; 25 | // Tustin transform of the integral part 26 | // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) 27 | float integral = integral_prev + I * Ts * 0.5f * (error + error_prev); 28 | // antiwindup - limit the output 29 | integral = _constrain(integral, -limit, limit); 30 | // Discrete derivation 31 | // u_dk = D(ek - ek_1)/Ts 32 | float derivative = D * (error - error_prev) / Ts; 33 | 34 | // sum all the components 35 | float output = proportional + integral + derivative; 36 | // antiwindup - limit the output variable 37 | output = _constrain(output, -limit, limit); 38 | 39 | // if output ramp defined 40 | if (output_ramp > 0) 41 | { 42 | // limit the acceleration by ramping the output 43 | float output_rate = (output - output_prev) / Ts; 44 | if (output_rate > output_ramp) 45 | output = output_prev + output_ramp * Ts; 46 | else if (output_rate < -output_ramp) 47 | output = output_prev - output_ramp * Ts; 48 | } 49 | // saving for the next pass 50 | integral_prev = integral; 51 | output_prev = output; 52 | error_prev = error; 53 | timestamp_prev = timestamp_now; 54 | return output; 55 | } 56 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Ctrl/Utils/pid.h: -------------------------------------------------------------------------------- 1 | #ifndef PID_H 2 | #define PID_H 3 | 4 | 5 | #include "Platform/Utils/time_utils.h" 6 | #include "foc_utils.h" 7 | 8 | /** 9 | * PID controller class 10 | */ 11 | class PIDController 12 | { 13 | public: 14 | /** 15 | * 16 | * @param P - Proportional gain 17 | * @param I - Integral gain 18 | * @param D - Derivative gain 19 | * @param ramp - Maximum speed of change of the output value 20 | * @param limit - Maximum output value 21 | */ 22 | PIDController(float P, float I, float D, float ramp, float limit); 23 | ~PIDController() = default; 24 | 25 | float operator()(float error); 26 | 27 | float P; //!< Proportional gain 28 | float I; //!< Integral gain 29 | float D; //!< Derivative gain 30 | float output_ramp; //!< Maximum speed of change of the output value 31 | float limit; //!< Maximum output value 32 | 33 | protected: 34 | float error_prev; //!< last tracking error value 35 | float output_prev; //!< last pid output value 36 | float integral_prev; //!< last integral component value 37 | unsigned long timestamp_prev; //!< Last execution timestamp 38 | }; 39 | 40 | #endif // PID_H -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/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 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/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 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Sensor/Encoder/encoder_as5047_stm32.cpp: -------------------------------------------------------------------------------- 1 | #include "encoder_as5047_stm32.h" 2 | #include "spi.h" 3 | 4 | void EncoderAS5047::SpiInit() 5 | { 6 | MX_SPI1_Init(); 7 | } 8 | 9 | 10 | uint16_t EncoderAS5047::SpiTransmitAndRead16Bits(uint16_t _dataTx) 11 | { 12 | uint16_t dataRx; 13 | 14 | GPIOA->BRR = GPIO_PIN_4; // Chip select 15 | HAL_SPI_TransmitReceive(&hspi1, (uint8_t*) &_dataTx, (uint8_t*) &dataRx, 1, HAL_MAX_DELAY); 16 | GPIOA->BSRR = GPIO_PIN_4; 17 | 18 | return dataRx; 19 | } 20 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Sensor/Encoder/encoder_as5047_stm32.h: -------------------------------------------------------------------------------- 1 | #ifndef CTRL_STEP_FW_AS5047_STM32_H 2 | #define CTRL_STEP_FW_AS5047_STM32_H 3 | 4 | #include "Ctrl/Sensor/Encoder/Instances/encoder_as5047.h" 5 | 6 | class EncoderAS5047 : public EncoderAS5047Base 7 | { 8 | public: 9 | explicit EncoderAS5047() : EncoderAS5047Base() 10 | {} 11 | 12 | 13 | private: 14 | void SpiInit() override; 15 | 16 | uint16_t SpiTransmitAndRead16Bits(uint16_t _data) override; 17 | }; 18 | 19 | #endif 20 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Signal/button_stm32.cpp: -------------------------------------------------------------------------------- 1 | #include "button_stm32.h" 2 | #include "Core/Inc/gpio.h" 3 | 4 | bool Button::ReadButtonPinIO(uint8_t _id) 5 | { 6 | switch (_id) 7 | { 8 | case 1: 9 | return HAL_GPIO_ReadPin(GPIOB, GPIO_PIN_12) == GPIO_PIN_SET; 10 | case 2: 11 | return HAL_GPIO_ReadPin(GPIOB, GPIO_PIN_2) == GPIO_PIN_SET; 12 | default: 13 | return false; 14 | } 15 | } 16 | bool Button::IsPressed() 17 | { 18 | return !ReadButtonPinIO(id); 19 | } 20 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Signal/button_stm32.h: -------------------------------------------------------------------------------- 1 | #ifndef CTRL_STEP_FW_BUTTON_STM32_H 2 | #define CTRL_STEP_FW_BUTTON_STM32_H 3 | 4 | #include "Ctrl/Signal/button_base.h" 5 | 6 | class Button : public ButtonBase 7 | { 8 | public: 9 | explicit Button(uint8_t _id) : ButtonBase(_id) 10 | {} 11 | 12 | Button(uint8_t _id, uint32_t _longPressTime) : ButtonBase(_id, _longPressTime) 13 | {} 14 | 15 | bool IsPressed(); 16 | 17 | private: 18 | bool ReadButtonPinIO(uint8_t _id) override; 19 | }; 20 | 21 | #endif 22 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Utils/retarget.c: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "Platform/Utils/retarget.h" 4 | #include "usart.h" 5 | 6 | #if !defined(OS_USE_SEMIHOSTING) 7 | 8 | #define STDIN_FILENO 0 9 | #define STDOUT_FILENO 1 10 | #define STDERR_FILENO 2 11 | 12 | UART_HandleTypeDef *gHuart; 13 | 14 | void RetargetInit(UART_HandleTypeDef *huart) 15 | { 16 | gHuart = huart; 17 | 18 | /* Disable I/O buffering for STDOUT stream, so that 19 | * chars are sent out as soon as they are printed. */ 20 | setvbuf(stdout, NULL, _IONBF, 0); 21 | } 22 | 23 | int _isatty(int fd) 24 | { 25 | if (fd >= STDIN_FILENO && fd <= STDERR_FILENO) 26 | return 1; 27 | 28 | errno = EBADF; 29 | return 0; 30 | } 31 | 32 | int _write(int fd, char *ptr, int len) 33 | { 34 | if (fd == STDOUT_FILENO || fd == STDERR_FILENO) 35 | { 36 | HAL_UART_Transmit_DMA(gHuart, (uint8_t *) ptr, len); 37 | return len; 38 | } else 39 | return -1; 40 | } 41 | 42 | int _close(int fd) 43 | { 44 | if (fd >= STDIN_FILENO && fd <= STDERR_FILENO) 45 | return 0; 46 | 47 | errno = EBADF; 48 | return -1; 49 | } 50 | 51 | int _lseek(int fd, int ptr, int dir) 52 | { 53 | (void) fd; 54 | (void) ptr; 55 | (void) dir; 56 | 57 | errno = EBADF; 58 | return -1; 59 | } 60 | 61 | int _read(int fd, char *ptr, int len) 62 | { 63 | HAL_StatusTypeDef hstatus; 64 | 65 | if (fd == STDIN_FILENO) 66 | { 67 | hstatus = HAL_UART_Receive(gHuart, (uint8_t *) ptr, 1, HAL_MAX_DELAY); 68 | if (hstatus == HAL_OK) 69 | return 1; 70 | else 71 | return EIO; 72 | } 73 | errno = EBADF; 74 | return -1; 75 | } 76 | 77 | int _fstat(int fd, struct stat *st) 78 | { 79 | if (fd >= STDIN_FILENO && fd <= STDERR_FILENO) 80 | { 81 | st->st_mode = S_IFCHR; 82 | return 0; 83 | } 84 | 85 | errno = EBADF; 86 | return 0; 87 | } 88 | 89 | #endif //#if !defined(OS_USE_SEMIHOSTING) -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Utils/retarget.h: -------------------------------------------------------------------------------- 1 | #ifndef _RETARGET_H__ 2 | #define _RETARGET_H__ 3 | 4 | #include "stm32f1xx_hal.h" 5 | #include 6 | #include 7 | 8 | void RetargetInit(UART_HandleTypeDef *huart); 9 | 10 | int _isatty(int fd); 11 | 12 | int _write(int fd, char *ptr, int len); 13 | 14 | int _close(int fd); 15 | 16 | int _lseek(int fd, int ptr, int dir); 17 | 18 | int _read(int fd, char *ptr, int len); 19 | 20 | int _fstat(int fd, struct stat *st); 21 | 22 | #endif //#ifndef _RETARGET_H__ -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Utils/st_hardware.c: -------------------------------------------------------------------------------- 1 | #include "st_hardware.h" 2 | #include "stm32f103xb.h" 3 | 4 | uint64_t GetSerialNumber() 5 | { 6 | // This procedure of building a USB serial number should be identical 7 | // to the way the STM's built-in USB bootloader does it. This means 8 | // that the device will have the same serial number in normal and DFU mode. 9 | uint32_t uuid0 = *(uint32_t * )(UID_BASE + 0); 10 | uint32_t uuid1 = *(uint32_t * )(UID_BASE + 4); 11 | uint32_t uuid2 = *(uint32_t * )(UID_BASE + 8); 12 | uint32_t uuid_mixed_part = uuid0 + uuid2; 13 | uint64_t serialNumber = ((uint64_t) uuid_mixed_part << 16) | (uint64_t)(uuid1 >> 16); 14 | 15 | return serialNumber; 16 | } -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Utils/st_hardware.h: -------------------------------------------------------------------------------- 1 | #ifndef CTRL_STEP_FW_ST_HARDWARE_H 2 | #define CTRL_STEP_FW_ST_HARDWARE_H 3 | 4 | #include 5 | 6 | #ifdef __cplusplus 7 | extern "C" { 8 | #endif 9 | 10 | uint64_t GetSerialNumber(); 11 | 12 | #ifdef __cplusplus 13 | } 14 | 15 | 16 | #endif 17 | #endif 18 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Utils/time_utils.cpp: -------------------------------------------------------------------------------- 1 | #include "time_utils.h" 2 | #include "stm32f1xx_hal.h" 3 | 4 | void delay(uint32_t _ms) 5 | { 6 | uint32_t t0 = micros(); 7 | while (micros() - t0 < _ms * 1000) 8 | __NOP(); 9 | } 10 | 11 | 12 | void delayMicroseconds(uint32_t _us) 13 | { 14 | uint32_t t0 = micros(); 15 | while (micros() - t0 < _us) 16 | __NOP(); 17 | } 18 | 19 | 20 | __STATIC_INLINE uint32_t LL_SYSTICK_IsActiveCounterFlag() 21 | { 22 | return ((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) == (SysTick_CTRL_COUNTFLAG_Msk)); 23 | } 24 | 25 | 26 | uint64_t micros() 27 | { 28 | /* Ensure COUNTFLAG is reset by reading SysTick control and status register */ 29 | LL_SYSTICK_IsActiveCounterFlag(); 30 | uint32_t m = HAL_GetTick(); 31 | static const uint32_t tms = SysTick->LOAD + 1; 32 | __IO uint32_t u = tms - SysTick->VAL; 33 | if (LL_SYSTICK_IsActiveCounterFlag()) 34 | { 35 | m = HAL_GetTick(); 36 | u = tms - SysTick->VAL; 37 | } 38 | return (m * 1000 + (u * 1000) / tms); 39 | } 40 | 41 | 42 | uint32_t millis() 43 | { 44 | return HAL_GetTick(); 45 | } 46 | 47 | 48 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/Platform/Utils/time_utils.h: -------------------------------------------------------------------------------- 1 | #ifndef TIME_UTILS_H 2 | #define TIME_UTILS_H 3 | 4 | #include 5 | 6 | void delay(uint32_t ms); 7 | void delayMicroseconds(uint32_t us); 8 | uint64_t micros(); 9 | uint32_t millis(); 10 | 11 | 12 | #endif -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/UserApp/common_inc.h: -------------------------------------------------------------------------------- 1 | #ifndef LOOP_H 2 | #define LOOP_H 3 | 4 | #ifdef __cplusplus 5 | extern "C" { 6 | #endif 7 | /*---------------------------- C Scope ---------------------------*/ 8 | #include "stdint-gcc.h" 9 | #include 10 | 11 | void Main(); 12 | void OnUartCmd(uint8_t* _data, uint16_t _len); 13 | void OnCanCmd(uint8_t _cmd, uint8_t* _data, uint32_t _len); 14 | 15 | #ifdef __cplusplus 16 | } 17 | /*---------------------------- C++ Scope ---------------------------*/ 18 | #include 19 | #include "UserApp/configurations.h" 20 | #include "Platform/Utils/time_utils.h" 21 | #include "Platform/Sensor/Encoder/encoder_as5047_stm32.h" 22 | 23 | #endif 24 | #endif 25 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/UserApp/configurations.h: -------------------------------------------------------------------------------- 1 | #ifndef CONFIGURATIONS_H 2 | #define CONFIGURATIONS_H 3 | 4 | #ifdef __cplusplus 5 | extern "C" { 6 | #endif 7 | /*---------------------------- C Scope ---------------------------*/ 8 | #include 9 | #include "stdint-gcc.h" 10 | 11 | typedef enum configStatus_t 12 | { 13 | CONFIG_RESTORE = 0, 14 | CONFIG_OK, 15 | CONFIG_COMMIT 16 | } configStatus_t; 17 | 18 | 19 | typedef struct Config_t 20 | { 21 | configStatus_t configStatus; 22 | uint32_t canNodeId; 23 | } BoardConfig_t; 24 | 25 | extern BoardConfig_t boardConfig; 26 | 27 | 28 | #ifdef __cplusplus 29 | } 30 | /*---------------------------- C++ Scope ---------------------------*/ 31 | 32 | #include "Platform/Utils/Memory/eeprom_interface.h" 33 | 34 | 35 | #endif 36 | #endif 37 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/UserApp/main.cpp: -------------------------------------------------------------------------------- 1 | #include "common_inc.h" 2 | #include "Platform/Utils/st_hardware.h" 3 | 4 | EncoderAS5047 encoder; 5 | 6 | /* Component Definitions -----------------------------------------------------*/ 7 | BoardConfig_t boardConfig; 8 | 9 | 10 | #include "adc.h" 11 | 12 | /* Main Entry ----------------------------------------------------------------*/ 13 | void Main() 14 | { 15 | uint64_t serialNum = GetSerialNumber(); 16 | uint16_t defaultNodeID = 0; 17 | 18 | encoder.Init(); 19 | 20 | //HAL_TIM_Base_Start_IT(&htim1); 21 | 22 | HAL_ADCEx_Calibration_Start(&hadc1); 23 | 24 | 25 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_1); 26 | HAL_TIMEx_PWMN_Start(&htim1, TIM_CHANNEL_1); 27 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2); 28 | HAL_TIMEx_PWMN_Start(&htim1, TIM_CHANNEL_2); 29 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3); 30 | HAL_TIMEx_PWMN_Start(&htim1, TIM_CHANNEL_3); 31 | __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, 200); 32 | __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, 300); 33 | __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, 300); 34 | 35 | delay(10); 36 | // HAL_ADC_Start_DMA(&hadc1, (uint32_t*) adcData, 2); 37 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_4); 38 | __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_4, 720); 39 | HAL_ADCEx_InjectedStart_IT(&hadc1); 40 | 41 | 42 | for (;;) 43 | { 44 | encoder.update(); 45 | // printf("%.2f,%.2f\n", encoder.GetAngle(), encoder.getVelocity()); 46 | delay(1); 47 | 48 | printf("%d,%d\n", adcData[0], adcData[1]); 49 | } 50 | } 51 | 52 | 53 | void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc) 54 | { 55 | GPIOB->BSRR = GPIO_PIN_12; 56 | adcData[0] = hadc->Instance->JDR1; 57 | adcData[1] = hadc->Instance->JDR2; 58 | GPIOB->BRR = GPIO_PIN_12; 59 | } -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/UserApp/protocols/interface_can.cpp: -------------------------------------------------------------------------------- 1 | #include "common_inc.h" 2 | #include 3 | 4 | 5 | 6 | CAN_TxHeaderTypeDef txHeader = 7 | { 8 | .StdId = 0x00, 9 | .ExtId = 0x00, 10 | .IDE = CAN_ID_STD, 11 | .RTR = CAN_RTR_DATA, 12 | .DLC = 8, 13 | .TransmitGlobalTime = DISABLE 14 | }; 15 | 16 | 17 | void OnCanCmd(uint8_t _cmd, uint8_t* _data, uint32_t _len) 18 | { 19 | float tmpF; 20 | int32_t tmpI; 21 | 22 | switch (_cmd) 23 | { 24 | default: 25 | break; 26 | } 27 | 28 | } 29 | 30 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/UserApp/protocols/interface_uart.cpp: -------------------------------------------------------------------------------- 1 | #include "common_inc.h" 2 | #include "configurations.h" 3 | 4 | 5 | void OnUartCmd(uint8_t* _data, uint16_t _len) 6 | { 7 | float cur, pos, vel, time; 8 | int ret = 0; 9 | 10 | printf("%s\n",_data); 11 | } 12 | 13 | -------------------------------------------------------------------------------- /2.Firmware/STM32_HAL_version/Ctrl-FOC-Lite-fw/stlink.cfg: -------------------------------------------------------------------------------- 1 | # choose st-link/j-link/dap-link etc. 2 | #adapter driver cmsis-dap 3 | #transport select swd 4 | source [find interface/stlink.cfg] 5 | transport select hla_swd 6 | source [find target/stm32f1x.cfg] 7 | 8 | # download speed = 10MHz 9 | adapter speed 10000 -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.gitignore: -------------------------------------------------------------------------------- 1 | .pio 2 | CMakeListsPrivate.txt 3 | cmake-build-*/ 4 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.idea/.gitignore: -------------------------------------------------------------------------------- 1 | # Default ignored files 2 | /shelf/ 3 | /workspace.xml 4 | # Datasource local storage ignored files 5 | /dataSources/ 6 | /dataSources.local.xml 7 | # Editor-based HTTP Client requests 8 | /httpRequests/ 9 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.idea/Ctrl-FOC-Lite-fw.iml: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.idea/SimpleFOC-fw.iml: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.idea/deployment.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.idea/misc.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.idea/modules.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.idea/serialmonitor_settings.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/.idea/vcs.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # !!! WARNING !!! AUTO-GENERATED FILE, PLEASE DO NOT MODIFY IT AND USE 2 | # https://docs.platformio.org/page/projectconf/section_env_build.html#build-flags 3 | # 4 | # If you need to override existing CMake configuration or add extra, 5 | # please create `CMakeListsUser.txt` in the root of project. 6 | # The `CMakeListsUser.txt` will not be overwritten by PlatformIO. 7 | 8 | cmake_minimum_required(VERSION 3.13) 9 | set(CMAKE_SYSTEM_NAME Generic) 10 | set(CMAKE_C_COMPILER_WORKS 1) 11 | set(CMAKE_CXX_COMPILER_WORKS 1) 12 | 13 | project("Ctrl-FOC-Lite-fw" C CXX) 14 | 15 | include(CMakeListsPrivate.txt) 16 | 17 | if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/CMakeListsUser.txt) 18 | include(CMakeListsUser.txt) 19 | endif() 20 | 21 | add_custom_target( 22 | Production ALL 23 | COMMAND platformio -c clion run "$<$>:-e${CMAKE_BUILD_TYPE}>" 24 | WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} 25 | ) 26 | 27 | add_custom_target( 28 | Debug ALL 29 | COMMAND platformio -c clion run --target debug "$<$>:-e${CMAKE_BUILD_TYPE}>" 30 | WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} 31 | ) 32 | 33 | add_executable(Z_DUMMY_TARGET ${SRC_LIST}) 34 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/include/README: -------------------------------------------------------------------------------- 1 | 2 | This directory is intended for project header files. 3 | 4 | A header file is a file containing C declarations and macro definitions 5 | to be shared between several project source files. You request the use of a 6 | header file in your project source file (C, C++, etc) located in `src` folder 7 | by including it, with the C preprocessing directive `#include'. 8 | 9 | ```src/main.c 10 | 11 | #include "header.h" 12 | 13 | int main (void) 14 | { 15 | ... 16 | } 17 | ``` 18 | 19 | Including a header file produces the same results as copying the header file 20 | into each source file that needs it. Such copying would be time-consuming 21 | and error-prone. With a header file, the related declarations appear 22 | in only one place. If they need to be changed, they can be changed in one 23 | place, and programs that include the header file will automatically use the 24 | new version when next recompiled. The header file eliminates the labor of 25 | finding and changing all the copies as well as the risk that a failure to 26 | find one copy will result in inconsistencies within a program. 27 | 28 | In C, the usual convention is to give header files names that end with `.h'. 29 | It is most portable to use only letters, digits, dashes, and underscores in 30 | header file names, and at most one dot. 31 | 32 | Read more about using header files in official GCC documentation: 33 | 34 | * Include Syntax 35 | * Include Operation 36 | * Once-Only Headers 37 | * Computed Includes 38 | 39 | https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html 40 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/.github/workflows/ccpp.yml: -------------------------------------------------------------------------------- 1 | name: Library Compile 2 | on: push 3 | jobs: 4 | build: 5 | name: Test compiling 6 | runs-on: ubuntu-latest 7 | steps: 8 | - name: Checkout 9 | uses: actions/checkout@master 10 | - name: Compile all examples 11 | uses: ArminJo/arduino-test-compile@v1.0.0 12 | with: 13 | libraries: PciManager 14 | examples-exclude: bluepill_position_control, esp32_position_control, esp32_i2c_dual_bus_example, stm32_i2c_dual_bus_example, magnetic_sensor_spi_alt_example, osc_esp32_3pwm, osc_esp32_fullcontrol, nano33IoT_velocity_control 15 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2020 Antun Skuric 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 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/hardware_specific_examples/SAMD_examples/nano33IoT/nano33IoT_velocity_control/nano33IoT_velocity_control.ino: -------------------------------------------------------------------------------- 1 | 2 | // show the infos for SAMD pin assignment on serial console 3 | // set this #define SIMPLEFOC_SAMD_DEBUG in drivers/hardware_specific/samd21_mcu.h 4 | 5 | 6 | #include "Arduino.h" 7 | #include 8 | #include 9 | #include 10 | 11 | // this is for an AS5048B absolute magnetic encoder on I2C address 0x41 12 | MagneticSensorI2C sensor = MagneticSensorI2C(0x41, 14, 0xFE, 8); 13 | 14 | // small BLDC gimbal motor, 7 pole-pairs 15 | BLDCMotor motor = BLDCMotor(7); 16 | // 3-PWM driving on pins 6, 5 and 8 - these are all on the same timer unit (TCC0), but different channels 17 | BLDCDriver3PWM driver = BLDCDriver3PWM(6, 5, 8); 18 | 19 | // velocity set point variable 20 | float target_velocity = 2.0; 21 | // instantiate the commander 22 | Commander command = Commander(SerialUSB); 23 | 24 | void doTarget(char *cmd) 25 | { command.scalar(&target_velocity, cmd); } 26 | 27 | 28 | void setup() 29 | { 30 | Serial.begin(115200); 31 | delay(1000); 32 | Serial.println("Initializing..."); 33 | 34 | sensor.init(); 35 | Wire.setClock(400000); 36 | motor.linkSensor(&sensor); 37 | driver.voltage_power_supply = 9; 38 | driver.init(); 39 | motor.linkDriver(&driver); 40 | motor.controller = MotionControlType::velocity; 41 | motor.PID_velocity.P = 0.2; 42 | motor.PID_velocity.I = 20; 43 | motor.PID_velocity.D = 0.001; 44 | motor.PID_velocity.output_ramp = 1000; 45 | motor.LPF_velocity.Tf = 0.01; 46 | motor.voltage_limit = 9; 47 | //motor.P_angle.P = 20; 48 | motor.init(); 49 | motor.initFOC(); 50 | 51 | // add target command T 52 | command.add('T', doTarget, "target velocity"); 53 | 54 | Serial.println(F("Motor ready.")); 55 | Serial.println(F("Set the target velocity using serial terminal:")); 56 | delay(100); 57 | } 58 | 59 | 60 | void loop() 61 | { 62 | // Serial.print("Sensor: "); 63 | // Serial.println(sensor.getAngle()); 64 | motor.loopFOC(); 65 | motor.move(target_velocity); 66 | // user communication 67 | command.run(); 68 | } 69 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/motion_control/open_loop_motor_control/open_loop_position_example/open_loop_position_example.ino: -------------------------------------------------------------------------------- 1 | // Open loop motor control example 2 | #include 3 | 4 | 5 | // BLDC motor & driver instance 6 | // BLDCMotor motor = BLDCMotor(pole pair number); 7 | BLDCMotor motor = BLDCMotor(11); 8 | // BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional)); 9 | BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8); 10 | 11 | // Stepper motor & driver instance 12 | //StepperMotor motor = StepperMotor(50); 13 | //StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8); 14 | 15 | //target variable 16 | float target_position = 0; 17 | 18 | // instantiate the commander 19 | Commander command = Commander(Serial); 20 | 21 | void doTarget(char *cmd) 22 | { command.scalar(&target_position, cmd); } 23 | 24 | void setup() 25 | { 26 | 27 | // driver config 28 | // power supply voltage [V] 29 | driver.voltage_power_supply = 12; 30 | driver.init(); 31 | // link the motor and the driver 32 | motor.linkDriver(&driver); 33 | 34 | // limiting motor movements 35 | motor.voltage_limit = 3; // [V] 36 | motor.velocity_limit = 5; // [rad/s] cca 50rpm 37 | // open loop control config 38 | motor.controller = MotionControlType::angle_openloop; 39 | 40 | // init motor hardware 41 | motor.init(); 42 | 43 | // add target command T 44 | command.add('T', doTarget, "target angle"); 45 | 46 | Serial.begin(115200); 47 | Serial.println("Motor ready!"); 48 | Serial.println("Set target position [rad]"); 49 | _delay(1000); 50 | } 51 | 52 | void loop() 53 | { 54 | // open loop angle movements 55 | // using motor.voltage_limit and motor.velocity_limit 56 | motor.move(target_position); 57 | 58 | // user communication 59 | command.run(); 60 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/motion_control/open_loop_motor_control/open_loop_velocity_example/open_loop_velocity_example.ino: -------------------------------------------------------------------------------- 1 | // Open loop motor control example 2 | #include 3 | 4 | 5 | // BLDC motor & driver instance 6 | // BLDCMotor motor = BLDCMotor(pole pair number); 7 | BLDCMotor motor = BLDCMotor(11); 8 | // BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional)); 9 | BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8); 10 | 11 | // Stepper motor & driver instance 12 | //StepperMotor motor = StepperMotor(50); 13 | //StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8); 14 | 15 | 16 | //target variable 17 | float target_velocity = 0; 18 | 19 | // instantiate the commander 20 | Commander command = Commander(Serial); 21 | 22 | void doTarget(char *cmd) 23 | { command.scalar(&target_velocity, cmd); } 24 | 25 | void setup() 26 | { 27 | 28 | // driver config 29 | // power supply voltage [V] 30 | driver.voltage_power_supply = 12; 31 | driver.init(); 32 | // link the motor and the driver 33 | motor.linkDriver(&driver); 34 | 35 | // limiting motor movements 36 | motor.voltage_limit = 3; // [V] 37 | motor.velocity_limit = 5; // [rad/s] cca 50rpm 38 | 39 | // open loop control config 40 | motor.controller = MotionControlType::velocity_openloop; 41 | 42 | // init motor hardware 43 | motor.init(); 44 | 45 | // add target command T 46 | command.add('T', doTarget, "target velocity"); 47 | 48 | Serial.begin(115200); 49 | Serial.println("Motor ready!"); 50 | Serial.println("Set target velocity [rad/s]"); 51 | _delay(1000); 52 | } 53 | 54 | void loop() 55 | { 56 | 57 | // open loop velocity movement 58 | // using motor.voltage_limit and motor.velocity_limit 59 | motor.move(target_velocity); 60 | 61 | // user communication 62 | command.run(); 63 | } 64 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/osc_control_examples/README.md: -------------------------------------------------------------------------------- 1 | # OSC control examples 2 | 3 | OSC - opensoundcontrol.org is a simple message exchange protocol. Widely used in the Audio world it is being hailed as 4 | the successor to MIDI. But MIDI itself, and now OSC, has always been about sending and receiving fairly simple control 5 | messages, at medium speed, and that makes it well suited for the same kind of task in robotics or other control 6 | applications. 7 | 8 | As a protocol it is simple, making implementation quite easy, and while binary, simple enough to be fairly "human 9 | readable", which aids in debugging and reduces errors. 10 | 11 | The main advantage of using it is that there is a bunch of ready made software, and also libraries to use in your own 12 | programs, neaning you don't have to re-invent these things from scratch. 13 | 14 | ## TouchOSC 15 | 16 | The first example shows how to set up control of a motor from TouchOSC. It's a super-fast way to set up a customizable 17 | GUI for your motor-project, that runs on your phone... 18 | 19 | ## purr-Data 20 | 21 | The second example, "simplefoc\_osc\_esp32\_fullcontrol.ino" allows setting the variables and tuning the motor 22 | parameters, in the same way as the serial control but via OSC. The file "osc\_fullcontrol.pd" contains a sample GUI to 23 | go with that sketch, allowing the control and tuning of 2 BLDC motors. 24 | 25 | Here a screenshot of what it looks like in purr-Data: 26 | 27 | ![Screenshot from pD](osc_fullcontrol_screenshot.png?raw=true "pD controlling 2 BLDC motors") 28 | 29 | ## Links to software used in examples 30 | 31 | - OSC - opensoundcontrol.org 32 | - pD - https://puredata.info 33 | - TouchOSC - https://hexler.net/products/touchosc 34 | 35 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/osc_control_examples/osc_esp32_3pwm/layout1.touchosc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/osc_control_examples/osc_esp32_3pwm/layout1.touchosc -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/osc_control_examples/osc_esp32_fullcontrol/ssid.h_rename_me: -------------------------------------------------------------------------------- 1 | 2 | #define MYSSID "yourssid" 3 | #define MYPASS "yourpassword" 4 | 5 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/osc_control_examples/osc_fullcontrol_screenshot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/osc_control_examples/osc_fullcontrol_screenshot.png -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/communication_test/commander/commander_extend_example/commander_extend_example.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Simple example of custom commands that have nothing to do with the simple foc library 3 | */ 4 | 5 | #include 6 | 7 | // instantiate the commander 8 | Commander command = Commander(Serial); 9 | 10 | // led control function 11 | void doLed(char *cmd) 12 | { 13 | if (atoi(cmd)) digitalWrite(LED_BUILTIN, HIGH); 14 | else digitalWrite(LED_BUILTIN, LOW); 15 | }; 16 | 17 | // get analog input 18 | void doAnalog(char *cmd) 19 | { 20 | if (cmd[0] == '0') Serial.println(analogRead(A0)); 21 | else if (cmd[0] == '1') Serial.println(analogRead(A1)); 22 | else if (cmd[0] == '2') Serial.println(analogRead(A2)); 23 | else if (cmd[0] == '3') Serial.println(analogRead(A3)); 24 | else if (cmd[0] == '4') Serial.println(analogRead(A4)); 25 | }; 26 | 27 | void setup() 28 | { 29 | // define pins 30 | pinMode(LED_BUILTIN, OUTPUT); 31 | pinMode(A0, INPUT); 32 | pinMode(A1, INPUT); 33 | pinMode(A2, INPUT); 34 | pinMode(A3, INPUT); 35 | pinMode(A4, INPUT); 36 | 37 | // Serial port to be used 38 | Serial.begin(115200); 39 | 40 | // add new commands 41 | command.add('L', doLed, "led on/off"); 42 | command.add('A', doAnalog, "analog read A0-A4"); 43 | 44 | Serial.println(F("Commander listening")); 45 | Serial.println(F(" - Send ? to see the node list...")); 46 | Serial.println(F(" - Send L0 to turn the led off and L1 to turn it off")); 47 | Serial.println(F(" - Send A0-A4 to read the analog pins")); 48 | _delay(1000); 49 | } 50 | 51 | 52 | void loop() 53 | { 54 | 55 | // user communication 56 | command.run(); 57 | _delay(10); 58 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/communication_test/commander/commander_no_serial/commander_no_serial.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Simple example of how to use the commander without serial - using just strings 3 | */ 4 | 5 | #include 6 | 7 | // instantiate the commander 8 | Commander command = Commander(); 9 | 10 | // led control function 11 | void doLed(char *cmd) 12 | { 13 | if (atoi(cmd)) digitalWrite(LED_BUILTIN, HIGH); 14 | else digitalWrite(LED_BUILTIN, LOW); 15 | }; 16 | 17 | // get analog input 18 | void doAnalog(char *cmd) 19 | { 20 | if (cmd[0] == '0') Serial.println(analogRead(A0)); 21 | else if (cmd[0] == '1') Serial.println(analogRead(A1)); 22 | }; 23 | 24 | void setup() 25 | { 26 | // define pins 27 | pinMode(LED_BUILTIN, OUTPUT); 28 | pinMode(A0, INPUT); 29 | pinMode(A1, INPUT); 30 | 31 | // Serial port to be used 32 | Serial.begin(115200); 33 | 34 | // add new commands 35 | command.add('L', doLed, "led control"); 36 | command.add('A', doAnalog, "analog read A0-A1"); 37 | 38 | Serial.println(F("Commander running")); 39 | _delay(1000); 40 | } 41 | 42 | 43 | void loop() 44 | { 45 | // user communication 46 | command.run("?"); 47 | _delay(2000); 48 | command.run("L0"); 49 | _delay(1000); 50 | command.run("A0"); 51 | _delay(1000); 52 | command.run("A1"); 53 | _delay(1000); 54 | command.run("L1"); 55 | _delay(1000); 56 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/communication_test/step_dir/step_dir_listener_simple/step_dir_listener_simple.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * A simple example of reading step/dir communication 3 | * - this example uses hadware interrupts 4 | */ 5 | 6 | #include 7 | 8 | // angle 9 | float received_angle = 0; 10 | 11 | // StepDirListener( step_pin, dir_pin, counter_to_value) 12 | StepDirListener step_dir = StepDirListener(2, 3, 360.0 / 200.0); // receive the angle in degrees 13 | void onStep() 14 | { step_dir.handle(); } 15 | 16 | void setup() 17 | { 18 | 19 | Serial.begin(115200); 20 | 21 | // init step and dir pins 22 | step_dir.init(); 23 | // enable interrupts 24 | step_dir.enableInterrupt(onStep); 25 | // attach the variable to be updated on each step (optional) 26 | // the same can be done asynchronously by caling step_dir.getValue(); 27 | step_dir.attach(&received_angle); 28 | 29 | Serial.println(F("Step/Dir listenning.")); 30 | _delay(1000); 31 | } 32 | 33 | void loop() 34 | { 35 | Serial.print(received_angle); 36 | Serial.print("\t"); 37 | Serial.println(step_dir.getValue()); 38 | _delay(500); 39 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/communication_test/step_dir/step_dir_listener_software_interrupt/step_dir_listener_software_interrupt.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * A simple example of reading step/dir communication 3 | * - this example uses software interrupts - this code is intended primarily 4 | * for Arduino UNO/Mega and similar boards with very limited number of interrupt pins 5 | */ 6 | 7 | #include 8 | // software interrupt library 9 | #include 10 | #include 11 | 12 | 13 | // angle 14 | float received_angle = 0; 15 | 16 | // StepDirListener( step_pin, dir_pin, counter_to_value) 17 | StepDirListener step_dir = StepDirListener(4, 5, 2.0 * _PI / 200.0); // receive the angle in radians 18 | void onStep() 19 | { step_dir.handle(); } 20 | 21 | // If no available hadware interrupt pins use the software interrupt 22 | PciListenerImp listenStep(step_dir.pin_step, onStep); 23 | 24 | void setup() 25 | { 26 | 27 | Serial.begin(115200); 28 | 29 | // init step and dir pins 30 | step_dir.init(); 31 | // enable software interrupts 32 | PciManager.registerListener(&listenStep); 33 | // attach the variable to be updated on each step (optional) 34 | // the same can be done asynchronously by caling step_dir.getValue(); 35 | step_dir.attach(&received_angle); 36 | 37 | Serial.println(F("Step/Dir listenning.")); 38 | _delay(1000); 39 | } 40 | 41 | void loop() 42 | { 43 | Serial.print(received_angle); 44 | Serial.print("\t"); 45 | Serial.println(step_dir.getValue()); 46 | _delay(500); 47 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/current_sense_test/inline_current_sense_test/inline_current_sense_test.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Testing example code for the Inline current sensing class 3 | */ 4 | #include 5 | 6 | // current sensor 7 | // shunt resistor value 8 | // gain value 9 | // pins phase A,B, (C optional) 10 | InlineCurrentSense current_sense = InlineCurrentSense(0.01, 50.0, A0, A2); 11 | 12 | 13 | void setup() 14 | { 15 | // initialise the current sensing 16 | current_sense.init(); 17 | 18 | // for SimpleFOCShield v2.01/v2.0.2 19 | current_sense.gain_b *= -1; 20 | 21 | Serial.begin(115200); 22 | Serial.println("Current sense ready."); 23 | } 24 | 25 | void loop() 26 | { 27 | 28 | PhaseCurrent_s currents = current_sense.getPhaseCurrents(); 29 | float current_magnitude = current_sense.getDCCurrent(); 30 | 31 | Serial.print(currents.a * 1000); // milli Amps 32 | Serial.print("\t"); 33 | Serial.print(currents.b * 1000); // milli Amps 34 | Serial.print("\t"); 35 | Serial.print(currents.c * 1000); // milli Amps 36 | Serial.print("\t"); 37 | Serial.println(current_magnitude * 1000); // milli Amps 38 | } 39 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/driver_standalone_test/bldc_driver_3pwm_standalone/bldc_driver_3pwm_standalone.ino: -------------------------------------------------------------------------------- 1 | // BLDC driver standalone example 2 | #include 3 | 4 | 5 | // BLDC driver instance 6 | BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8); 7 | 8 | void setup() 9 | { 10 | 11 | // pwm frequency to be used [Hz] 12 | // for atmega328 fixed to 32kHz 13 | // esp32/stm32/teensy configurable 14 | driver.pwm_frequency = 50000; 15 | // power supply voltage [V] 16 | driver.voltage_power_supply = 12; 17 | // Max DC voltage allowed - default voltage_power_supply 18 | driver.voltage_limit = 12; 19 | 20 | // driver init 21 | driver.init(); 22 | 23 | // enable driver 24 | driver.enable(); 25 | 26 | _delay(1000); 27 | } 28 | 29 | void loop() 30 | { 31 | // setting pwm 32 | // phase A: 3V 33 | // phase B: 6V 34 | // phase C: 5V 35 | driver.setPwm(3, 6, 5); 36 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/driver_standalone_test/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino: -------------------------------------------------------------------------------- 1 | // BLDC driver standalone example 2 | #include 3 | 4 | // BLDC driver instance 5 | BLDCDriver6PWM driver = BLDCDriver6PWM(5, 6, 9, 10, 3, 11, 8); 6 | 7 | void setup() 8 | { 9 | 10 | // pwm frequency to be used [Hz] 11 | // for atmega328 fixed to 32kHz 12 | // esp32/stm32/teensy configurable 13 | driver.pwm_frequency = 50000; 14 | // power supply voltage [V] 15 | driver.voltage_power_supply = 12; 16 | // Max DC voltage allowed - default voltage_power_supply 17 | driver.voltage_limit = 12; 18 | // daad_zone [0,1] - default 0.02 - 2% 19 | driver.dead_zone = 0.05; 20 | 21 | // driver init 22 | driver.init(); 23 | 24 | // enable driver 25 | driver.enable(); 26 | 27 | _delay(1000); 28 | } 29 | 30 | void loop() 31 | { 32 | // setting pwm 33 | // phase A: 3V 34 | // phase B: 6V 35 | // phase C: 5V 36 | driver.setPwm(3, 6, 5); 37 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/driver_standalone_test/stepper_driver_2pwm_standalone/stepper_driver_2pwm_standalone.ino: -------------------------------------------------------------------------------- 1 | // Stepper driver standalone example 2 | #include 3 | 4 | 5 | // Stepper driver instance 6 | // StepperDriver2PWM(pwm1, in1a, in1b, pwm2, in2a, in2b, (en1, en2 optional)) 7 | StepperDriver2PWM driver = StepperDriver2PWM(3, 4, 5, 10, 9, 8, 11, 12); 8 | 9 | // StepperDriver2PWM(pwm1, dir1, pwm2, dir2,(en1, en2 optional)) 10 | // StepperDriver2PWM driver = StepperDriver2PWM(3, 4, 5, 6, 11, 12); 11 | 12 | void setup() 13 | { 14 | 15 | // pwm frequency to be used [Hz] 16 | // for atmega328 fixed to 32kHz 17 | // esp32/stm32/teensy configurable 18 | driver.pwm_frequency = 30000; 19 | // power supply voltage [V] 20 | driver.voltage_power_supply = 12; 21 | // Max DC voltage allowed - default voltage_power_supply 22 | driver.voltage_limit = 12; 23 | 24 | // driver init 25 | driver.init(); 26 | 27 | // enable driver 28 | driver.enable(); 29 | 30 | _delay(1000); 31 | } 32 | 33 | void loop() 34 | { 35 | // setting pwm 36 | // phase A: 3V 37 | // phase B: 6V 38 | driver.setPwm(3, 6); 39 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/driver_standalone_test/stepper_driver_4pwm_standalone/stepper_driver_4pwm_standalone.ino: -------------------------------------------------------------------------------- 1 | // Stepper driver standalone example 2 | #include 3 | 4 | 5 | // Stepper driver instance 6 | // StepperDriver4PWM(ph1A, ph1B, ph2A, ph2B, (en1, en2 optional)) 7 | StepperDriver4PWM driver = StepperDriver4PWM(5, 6, 9, 10, 7, 8); 8 | 9 | void setup() 10 | { 11 | 12 | // pwm frequency to be used [Hz] 13 | // for atmega328 fixed to 32kHz 14 | // esp32/stm32/teensy configurable 15 | driver.pwm_frequency = 30000; 16 | // power supply voltage [V] 17 | driver.voltage_power_supply = 12; 18 | // Max DC voltage allowed - default voltage_power_supply 19 | driver.voltage_limit = 12; 20 | 21 | // driver init 22 | driver.init(); 23 | 24 | // enable driver 25 | driver.enable(); 26 | 27 | _delay(1000); 28 | } 29 | 30 | void loop() 31 | { 32 | // setting pwm 33 | // phase A: 3V 34 | // phase B: 6V 35 | driver.setPwm(3, 6); 36 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/encoder/encoder_example/encoder_example.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Encoder example code 3 | * 4 | * This is a code intended to test the encoder connections and to demonstrate the encoder setup. 5 | * 6 | */ 7 | 8 | #include 9 | 10 | 11 | Encoder encoder = Encoder(2, 3, 8192); 12 | 13 | // interrupt routine intialisation 14 | void doA() 15 | { encoder.handleA(); } 16 | 17 | void doB() 18 | { encoder.handleB(); } 19 | 20 | void setup() 21 | { 22 | // monitoring port 23 | Serial.begin(115200); 24 | 25 | // enable/disable quadrature mode 26 | encoder.quadrature = Quadrature::ON; 27 | 28 | // check if you need internal pullups 29 | encoder.pullup = Pullup::USE_EXTERN; 30 | 31 | // initialise encoder hardware 32 | encoder.init(); 33 | // hardware interrupt enable 34 | encoder.enableInterrupts(doA, doB); 35 | 36 | Serial.println("Encoder ready"); 37 | _delay(1000); 38 | } 39 | 40 | void loop() 41 | { 42 | // display the angle and the angular velocity to the terminal 43 | Serial.print(encoder.getAngle()); 44 | Serial.print("\t"); 45 | Serial.println(encoder.getVelocity()); 46 | } 47 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/encoder/encoder_software_interrupts_example/encoder_software_interrupts_example.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Encoder example code using only software interrupts 3 | * 4 | * This is a code intended to test the encoder connections and to 5 | * demonstrate the encoder setup fully using software interrupts. 6 | * - We use PciManager library: https://github.com/prampec/arduino-pcimanager 7 | * 8 | * This code will work on Arduino devices but not on STM32 devices 9 | * 10 | */ 11 | 12 | #include 13 | // software interrupt library 14 | #include 15 | #include 16 | 17 | // encoder instance 18 | Encoder encoder = Encoder(A0, A1, 2048); 19 | 20 | // interrupt routine intialisation 21 | void doA() 22 | { encoder.handleA(); } 23 | 24 | void doB() 25 | { encoder.handleB(); } 26 | 27 | // encoder interrupt init 28 | PciListenerImp listenerA(encoder.pinA, doA); 29 | PciListenerImp listenerB(encoder.pinB, doB); 30 | 31 | void setup() 32 | { 33 | // monitoring port 34 | Serial.begin(115200); 35 | 36 | // enable/disable quadrature mode 37 | encoder.quadrature = Quadrature::ON; 38 | 39 | // check if you need internal pullups 40 | encoder.pullup = Pullup::USE_EXTERN; 41 | 42 | // initialise encoder hardware 43 | encoder.init(); 44 | 45 | // interrupt initialization 46 | PciManager.registerListener(&listenerA); 47 | PciManager.registerListener(&listenerB); 48 | 49 | Serial.println("Encoder ready"); 50 | _delay(1000); 51 | } 52 | 53 | void loop() 54 | { 55 | // display the angle and the angular velocity to the terminal 56 | Serial.print(encoder.getAngle()); 57 | Serial.print("\t"); 58 | Serial.println(encoder.getVelocity()); 59 | } 60 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_example/hall_sensor_example.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Hall sensor example code 3 | * 4 | * This is a code intended to test the hall sensors connections and to demonstrate the hall sensor setup. 5 | * 6 | */ 7 | 8 | #include 9 | 10 | // Hall sensor instance 11 | // HallSensor(int hallA, int hallB , int cpr, int index) 12 | // - hallA, hallB, hallC - HallSensor A, B and C pins 13 | // - pp - pole pairs 14 | HallSensor sensor = HallSensor(2, 3, 4, 11); 15 | 16 | // Interrupt routine intialisation 17 | // channel A and B callbacks 18 | void doA() 19 | { sensor.handleA(); } 20 | 21 | void doB() 22 | { sensor.handleB(); } 23 | 24 | void doC() 25 | { sensor.handleC(); } 26 | 27 | 28 | void setup() 29 | { 30 | // monitoring port 31 | Serial.begin(115200); 32 | 33 | // check if you need internal pullups 34 | sensor.pullup = Pullup::USE_EXTERN; 35 | 36 | // initialise encoder hardware 37 | sensor.init(); 38 | // hardware interrupt enable 39 | sensor.enableInterrupts(doA, doB, doC); 40 | 41 | Serial.println("Sensor ready"); 42 | _delay(1000); 43 | } 44 | 45 | void loop() 46 | { 47 | // display the angle and the angular velocity to the terminal 48 | Serial.print(sensor.getAngle()); 49 | Serial.print("\t"); 50 | Serial.println(sensor.getVelocity()); 51 | } 52 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_software_interrupts_example/hall_sensors_software_interrupt_example.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Hall sensors example code using only software interrupts 3 | * 4 | * This is a code intended to test the hall sensor connections and to 5 | * demonstrate the hall sensor setup fully using software interrupts. 6 | * - We use PciManager library: https://github.com/prampec/arduino-pcimanager 7 | * 8 | * This code will work on Arduino devices but not on STM32 devices 9 | */ 10 | 11 | #include 12 | // software interrupt library 13 | #include 14 | #include 15 | 16 | // Hall sensor instance 17 | // HallSensor(int hallA, int hallB , int cpr, int index) 18 | // - hallA, hallB, hallC - HallSensor A, B and C pins 19 | // - pp - pole pairs 20 | HallSensor sensor = HallSensor(2, 3, 4, 11); 21 | 22 | // Interrupt routine intialisation 23 | // channel A and B callbacks 24 | void doA() 25 | { sensor.handleA(); } 26 | 27 | void doB() 28 | { sensor.handleB(); } 29 | 30 | void doC() 31 | { sensor.handleC(); } 32 | 33 | // If no available hadware interrupt pins use the software interrupt 34 | PciListenerImp listenA(sensor.pinA, doA); 35 | PciListenerImp listenB(sensor.pinB, doB); 36 | PciListenerImp listenC(sensor.pinC, doC); 37 | 38 | void setup() 39 | { 40 | // monitoring port 41 | Serial.begin(115200); 42 | 43 | // check if you need internal pullups 44 | sensor.pullup = Pullup::USE_EXTERN; 45 | 46 | // initialise encoder hardware 47 | sensor.init(); 48 | 49 | // software interrupts 50 | PciManager.registerListener(&listenA); 51 | PciManager.registerListener(&listenB); 52 | PciManager.registerListener(&listenC); 53 | 54 | Serial.println("Sensor ready"); 55 | _delay(1000); 56 | } 57 | 58 | void loop() 59 | { 60 | // display the angle and the angular velocity to the terminal 61 | Serial.print(sensor.getAngle()); 62 | Serial.print("\t"); 63 | Serial.println(sensor.getVelocity()); 64 | } 65 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_analog_example/find_raw_min_max/find_raw_min_max.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | /** 4 | * An example to find out the raw max and min count to be provided to the constructor 5 | * Spin your motor/sensor/magnet to see what is the maximum output of the sensor and what is the minimum value 6 | * And replace values 14 and 1020 with new values. Once when you replace them make sure there is no jump in the angle reading sensor.getAngle(). 7 | * If there is a jump that means you can still find better values. 8 | */ 9 | 10 | /** 11 | * Magnetic sensor reading analog voltage on pin A1. This voltage is proportional to rotation position. 12 | * Tested on AS5600 magnetic sensor running in 'analog mode'. Note AS5600 works better in 'i2C mode' (less noise) but only supports one sensor per i2c bus. 13 | * 14 | * MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max) 15 | * - pinAnalog - the pin that is reading the pwm from magnetic sensor 16 | * - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution 17 | * - max_raw_count - the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note ESP32 will be closer to 4096 with its 12bit ADC 18 | */ 19 | MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020); 20 | 21 | void setup() 22 | { 23 | // monitoring port 24 | Serial.begin(115200); 25 | 26 | // initialise magnetic sensor hardware 27 | sensor.init(); 28 | 29 | Serial.println("Sensor ready"); 30 | _delay(1000); 31 | } 32 | 33 | int max_count = 0; 34 | int min_count = 100000; 35 | 36 | void loop() 37 | { 38 | 39 | // keep track of min and max 40 | if (sensor.raw_count > max_count) max_count = sensor.raw_count; 41 | else if (sensor.raw_count < min_count) min_count = sensor.raw_count; 42 | 43 | // display the raw count, and max and min raw count 44 | Serial.print("angle:"); 45 | Serial.print(sensor.getAngle()); 46 | Serial.print("\t, raw:"); 47 | Serial.print(sensor.raw_count); 48 | Serial.print("\t, min:"); 49 | Serial.print(min_count); 50 | Serial.print("\t, max:"); 51 | Serial.println(max_count); 52 | delay(100); 53 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_analog_example/magnetic_sensor_analog/magnetic_sensor_analog.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | 4 | /** 5 | * Magnetic sensor reading analog voltage on pin A1. This voltage is proportional to rotation position. 6 | * Tested on AS5600 magnetic sensor running in 'analog mode'. Note AS5600 works better in 'i2C mode' (less noise) but only supports one sensor per i2c bus. 7 | * 8 | * MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max) 9 | * - pinAnalog - the pin that is reading the pwm from magnetic sensor 10 | * - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution 11 | * - max_raw_count - the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note ESP32 will be closer to 4096 with its 12bit ADC 12 | */ 13 | MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020); 14 | 15 | void setup() 16 | { 17 | // monitoring port 18 | Serial.begin(115200); 19 | 20 | // initialise magnetic sensor hardware 21 | sensor.init(); 22 | 23 | Serial.println("Sensor ready"); 24 | _delay(1000); 25 | } 26 | 27 | void loop() 28 | { 29 | // display the angle and the angular velocity to the terminal 30 | Serial.print(sensor.getAngle()); 31 | Serial.print("\t"); 32 | Serial.println(sensor.getVelocity()); 33 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c_dual_bus_examples/esp32_i2c_dual_bus_example/esp32_i2c_dual_bus_example.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | /** Annoyingly some i2c sensors (e.g. AS5600) have a fixed chip address. This means only one of these devices can be addressed on a single bus 4 | * This example shows how a second i2c bus can be used to communicate with a second sensor. 5 | */ 6 | 7 | MagneticSensorI2C sensor0 = MagneticSensorI2C(AS5600_I2C); 8 | MagneticSensorI2C sensor1 = MagneticSensorI2C(AS5600_I2C); 9 | 10 | 11 | void setup() 12 | { 13 | 14 | Serial.begin(115200); 15 | _delay(750); 16 | 17 | Wire.setClock(400000); 18 | Wire1.setClock(400000); 19 | 20 | // Normally SimpleFOC will call begin for i2c but with esp32 begin() is the only way to set pins! 21 | // It seems safe to call begin multiple times 22 | Wire1.begin(19, 23, 400000); 23 | 24 | sensor0.init(); 25 | sensor1.init(&Wire1); 26 | } 27 | 28 | void loop() 29 | { 30 | _delay(200); 31 | Serial.print(sensor0.getAngle()); 32 | Serial.print(" - "); 33 | Serial.print(sensor1.getAngle()); 34 | Serial.println(); 35 | } 36 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c_dual_bus_examples/stm32_i2c_dual_bus_example/stm32_i2c_dual_bus_example.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | /** Annoyingly some i2c sensors (e.g. AS5600) have a fixed chip address. This means only one of these devices can be addressed on a single bus 4 | * This example shows how a second i2c bus can be used to communicate with a second sensor. 5 | */ 6 | 7 | MagneticSensorI2C sensor0 = MagneticSensorI2C(AS5600_I2C); 8 | MagneticSensorI2C sensor1 = MagneticSensorI2C(AS5600_I2C); 9 | 10 | // example of stm32 defining 2nd bus 11 | TwoWire Wire1(PB11, PB10); 12 | 13 | 14 | void setup() 15 | { 16 | 17 | Serial.begin(115200); 18 | _delay(750); 19 | 20 | Wire.setClock(400000); 21 | Wire1.setClock(400000); 22 | 23 | sensor0.init(); 24 | sensor1.init(&Wire1); 25 | } 26 | 27 | void loop() 28 | { 29 | _delay(200); 30 | Serial.print(sensor0.getAngle()); 31 | Serial.print(" - "); 32 | Serial.print(sensor1.getAngle()); 33 | Serial.println(); 34 | } 35 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c_example/magnetic_sensor_i2c_example.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb) 4 | // chip_address I2C chip address 5 | // bit_resolution resolution of the sensor 6 | // angle_register_msb angle read register msb 7 | // bits_used_msb number of used bits in msb register 8 | // 9 | // make sure to read the chip address and the chip angle register msb value from the datasheet 10 | // also in most cases you will need external pull-ups on SDA and SCL lines!!!!! 11 | // 12 | // For AS5058B 13 | // MagneticSensorI2C sensor = MagneticSensorI2C(0x40, 14, 0xFE, 8); 14 | 15 | // Example of AS5600 configuration 16 | MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C); 17 | 18 | 19 | void setup() 20 | { 21 | // monitoring port 22 | Serial.begin(115200); 23 | 24 | // configure i2C 25 | Wire.setClock(400000); 26 | // initialise magnetic sensor hardware 27 | sensor.init(); 28 | 29 | Serial.println("Sensor ready"); 30 | _delay(1000); 31 | } 32 | 33 | void loop() 34 | { 35 | // display the angle and the angular velocity to the terminal 36 | Serial.print(sensor.getAngle()); 37 | Serial.print("\t"); 38 | Serial.println(sensor.getVelocity()); 39 | } 40 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm_example/find_raw_min_max/find_raw_min_max.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | 4 | /** 5 | * An example to find out the raw max and min count to be provided to the constructor 6 | * SPin your motor/sensor/magnet to see what is the maximum output of the sensor and what is the minimum value 7 | * And replace values 4 and 904 with new values. Once when you replace them make sure there is no jump in the angle reading sensor.getAngle(). 8 | * If there is a jump that means you can still find better values. 9 | */ 10 | MagneticSensorPWM sensor = MagneticSensorPWM(2, 4, 904); 11 | 12 | void doPWM() 13 | { sensor.handlePWM(); } 14 | 15 | void setup() 16 | { 17 | // monitoring port 18 | Serial.begin(115200); 19 | 20 | // initialise magnetic sensor hardware 21 | sensor.init(); 22 | // comment out to use sensor in blocking (non-interrupt) way 23 | sensor.enableInterrupt(doPWM); 24 | 25 | Serial.println("Sensor ready"); 26 | _delay(1000); 27 | } 28 | 29 | int max_pulse = 0; 30 | int min_pulse = 10000; 31 | 32 | void loop() 33 | { 34 | 35 | // keep track of min and max 36 | if (sensor.pulse_length_us > max_pulse) max_pulse = sensor.pulse_length_us; 37 | else if (sensor.pulse_length_us < min_pulse) min_pulse = sensor.pulse_length_us; 38 | 39 | // display the raw count, and max and min raw count 40 | Serial.print("angle:"); 41 | Serial.print(sensor.getAngle()); 42 | Serial.print("\t, raw:"); 43 | Serial.print(sensor.pulse_length_us); 44 | Serial.print("\t, min:"); 45 | Serial.print(min_pulse); 46 | Serial.print("\t, max:"); 47 | Serial.println(max_pulse); 48 | } 49 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm_example/magnetic_sensor_pwm/magnetic_sensor_pwm.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | 4 | /** 5 | * Magnetic sensor reading pwm signal on pin 2. The pwm duty cycle is proportional to the sensor angle. 6 | * 7 | * MagneticSensorPWM(uint8_t MagneticSensorPWM, int _min, int _max) 8 | * - pinPWM - the pin that is reading the pwm from magnetic sensor 9 | * - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~5. Getting this wrong results in a small click once per revolution 10 | * - max_raw_count - the largest value read. whilst you might expect it to be 1kHz = 1000 it is often ~910. depending on the exact frequency and saturation 11 | */ 12 | MagneticSensorPWM sensor = MagneticSensorPWM(2, 4, 904); 13 | 14 | void doPWM() 15 | { sensor.handlePWM(); } 16 | 17 | void setup() 18 | { 19 | // monitoring port 20 | Serial.begin(115200); 21 | 22 | // initialise magnetic sensor hardware 23 | sensor.init(); 24 | // comment out to use sensor in blocking (non-interrupt) way 25 | sensor.enableInterrupt(doPWM); 26 | 27 | Serial.println("Sensor ready"); 28 | _delay(1000); 29 | } 30 | 31 | void loop() 32 | { 33 | // display the angle and the angular velocity to the terminal 34 | Serial.print(sensor.getAngle()); 35 | Serial.print("\t"); 36 | Serial.println(sensor.getVelocity()); 37 | } 38 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm_example/magnetic_sensor_pwm_software_interrupt/magnetic_sensor_pwm_software_interrupt.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // software interrupt library 4 | #include 5 | #include 6 | 7 | /** 8 | * Magnetic sensor reading analog voltage on pin which does not have hardware interrupt support. Such as A0. 9 | * 10 | * MagneticSensorPWM(uint8_t MagneticSensorPWM, int _min, int _max) 11 | * - pinPWM - the pin that is reading the pwm from magnetic sensor 12 | * - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~5. Getting this wrong results in a small click once per revolution 13 | * - max_raw_count - the largest value read. whilst you might expect it to be 1kHz = 1000 it is often ~910. depending on the exact frequency and saturation 14 | */ 15 | MagneticSensorPWM sensor = MagneticSensorPWM(A0, 4, 904); 16 | 17 | void doPWM() 18 | { sensor.handlePWM(); } 19 | 20 | // encoder interrupt init 21 | PciListenerImp listenerPWM(sensor.pinPWM, doPWM); 22 | 23 | void setup() 24 | { 25 | // monitoring port 26 | Serial.begin(115200); 27 | 28 | // initialise magnetic sensor hardware 29 | sensor.init(); 30 | // comment out to use sensor in blocking (non-interrupt) way 31 | PciManager.registerListener(&listenerPWM); 32 | 33 | Serial.println("Sensor ready"); 34 | _delay(1000); 35 | } 36 | 37 | void loop() 38 | { 39 | // display the angle and the angular velocity to the terminal 40 | Serial.print(sensor.getAngle()); 41 | Serial.print("\t"); 42 | Serial.println(sensor.getVelocity()); 43 | } 44 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi_alt_example/magnetic_sensor_spi_alt_example.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // MagneticSensorSPI(int cs, float _cpr, int _angle_register) 4 | // config - SPI config 5 | // cs - SPI chip select pin 6 | MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, PA15); 7 | 8 | // these are valid pins (mosi, miso, sclk) for 2nd SPI bus on storm32 board (stm32f107rc) 9 | SPIClass SPI_2(PB15, PB14, PB13); 10 | 11 | void setup() 12 | { 13 | // monitoring port 14 | Serial.begin(115200); 15 | 16 | // initialise magnetic sensor hardware 17 | sensor.init(&SPI_2); 18 | 19 | Serial.println("Sensor ready"); 20 | _delay(1000); 21 | } 22 | 23 | void loop() 24 | { 25 | // display the angle and the angular velocity to the terminal 26 | Serial.print(sensor.getAngle()); 27 | Serial.print("\t"); 28 | Serial.println(sensor.getVelocity()); 29 | } 30 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi_example/magnetic_sensor_spi_example.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs) 4 | // config - SPI config 5 | // cs - SPI chip select pin 6 | // magnetic sensor instance - SPI 7 | MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10); 8 | // alternative constructor (chipselsect, bit_resolution, angle_read_register, ) 9 | // MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF); 10 | 11 | void setup() 12 | { 13 | // monitoring port 14 | Serial.begin(115200); 15 | 16 | // initialise magnetic sensor hardware 17 | sensor.init(); 18 | 19 | Serial.println("Sensor ready"); 20 | _delay(1000); 21 | } 22 | 23 | void loop() 24 | { 25 | // display the angle and the angular velocity to the terminal 26 | Serial.print(sensor.getAngle()); 27 | Serial.print("\t"); 28 | Serial.println(sensor.getVelocity()); 29 | } 30 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/library.properties: -------------------------------------------------------------------------------- 1 | name=Simple FOC 2 | version=2.1.1 3 | author=Simplefoc 4 | maintainer=Simplefoc 5 | sentence=A library demistifying FOC for BLDC motors 6 | paragraph=Simple library intended for hobby comunity to run the BLDC and Stepper motor using FOC algorithm. It is intended to support as many BLDC/Stepper motor+sensor+driver combinations as possible and in the same time maintain simplicity of usage. Library supports Arudino devices such as Arduino UNO, MEGA, NANO and similar, stm32 boards such as Nucleo and Bluepill, ESP32 and Teensy boards. 7 | category=Device Control 8 | url=https://docs.simplefoc.com 9 | architectures=* 10 | includes=SimpleFOC.h 11 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/base_classes/BLDCDriver.h: -------------------------------------------------------------------------------- 1 | #ifndef BLDCDRIVER_H 2 | #define BLDCDRIVER_H 3 | 4 | #include "Arduino.h" 5 | 6 | class BLDCDriver 7 | { 8 | public: 9 | 10 | /** Initialise hardware */ 11 | virtual int init() = 0; 12 | 13 | /** Enable hardware */ 14 | virtual void enable() = 0; 15 | 16 | /** Disable hardware */ 17 | virtual void disable() = 0; 18 | 19 | long pwm_frequency; //!< pwm frequency value in hertz 20 | float voltage_power_supply; //!< power supply voltage 21 | float voltage_limit; //!< limiting voltage set to the motor 22 | 23 | 24 | float dc_a; //!< currently set duty cycle on phaseA 25 | float dc_b; //!< currently set duty cycle on phaseB 26 | float dc_c; //!< currently set duty cycle on phaseC 27 | 28 | /** 29 | * Set phase voltages to the harware 30 | * 31 | * @param Ua - phase A voltage 32 | * @param Ub - phase B voltage 33 | * @param Uc - phase C voltage 34 | */ 35 | virtual void setPwm(float Ua, float Ub, float Uc) = 0; 36 | 37 | /** 38 | * Set phase state, enable/disable 39 | * 40 | * @param sc - phase A state : active / disabled ( high impedance ) 41 | * @param sb - phase B state : active / disabled ( high impedance ) 42 | * @param sa - phase C state : active / disabled ( high impedance ) 43 | */ 44 | virtual void setPhaseState(int sa, int sb, int sc) = 0; 45 | }; 46 | 47 | #endif -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/base_classes/Sensor.cpp: -------------------------------------------------------------------------------- 1 | #include "Sensor.h" 2 | #include "../foc_utils.h" 3 | #include "../time_utils.h" 4 | 5 | /** 6 | * returns 0 if it does need search for absolute zero 7 | * 0 - magnetic sensor (& encoder with index which is found) 8 | * 1 - ecoder with index (with index not found yet) 9 | */ 10 | int Sensor::needsSearch() 11 | { 12 | return 0; 13 | } 14 | 15 | /** get current angular velocity (rad/s)*/ 16 | float Sensor::getVelocity() 17 | { 18 | 19 | // calculate sample time 20 | unsigned long now_us = _micros(); 21 | float Ts = (now_us - velocity_calc_timestamp) * 1e-6; 22 | // quick fix for strange cases (micros overflow) 23 | if (Ts <= 0 || Ts > 0.5) Ts = 1e-3; 24 | 25 | // current angle 26 | float angle_c = getAngle(); 27 | // velocity calculation 28 | float vel = (angle_c - angle_prev) / Ts; 29 | 30 | // save variables for future pass 31 | angle_prev = angle_c; 32 | velocity_calc_timestamp = now_us; 33 | return vel; 34 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/base_classes/Sensor.h: -------------------------------------------------------------------------------- 1 | #ifndef SENSOR_H 2 | #define SENSOR_H 3 | 4 | /** 5 | * Direction structure 6 | */ 7 | enum Direction 8 | { 9 | CW = 1, //clockwise 10 | CCW = -1, // counter clockwise 11 | UNKNOWN = 0 //not yet known or invalid state 12 | }; 13 | 14 | 15 | /** 16 | * Pullup configuration structure 17 | */ 18 | enum Pullup 19 | { 20 | USE_INTERN, //!< Use internal pullups 21 | USE_EXTERN //!< Use external pullups 22 | }; 23 | 24 | /** 25 | * Sensor abstract class defintion 26 | * Each sensor needs to have these functions implemented 27 | */ 28 | class Sensor 29 | { 30 | public: 31 | 32 | /** get current angle (rad) */ 33 | virtual float getAngle() = 0; 34 | 35 | /** get current angular velocity (rad/s)*/ 36 | virtual float getVelocity(); 37 | 38 | /** 39 | * returns 0 if it does need search for absolute zero 40 | * 0 - magnetic sensor (& encoder with index which is found) 41 | * 1 - ecoder with index (with index not found yet) 42 | */ 43 | virtual int needsSearch(); 44 | 45 | private: 46 | // velocity calculation variables 47 | float angle_prev = 0; //!< angle in previous velocity calculation step 48 | long velocity_calc_timestamp = 0; //!< last velocity calculation timestamp 49 | }; 50 | 51 | #endif 52 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/base_classes/StepperDriver.h: -------------------------------------------------------------------------------- 1 | #ifndef STEPPERDRIVER_H 2 | #define STEPPERDRIVER_H 3 | 4 | class StepperDriver 5 | { 6 | public: 7 | 8 | /** Initialise hardware */ 9 | virtual int init() = 0; 10 | 11 | /** Enable hardware */ 12 | virtual void enable() = 0; 13 | 14 | /** Disable hardware */ 15 | virtual void disable() = 0; 16 | 17 | long pwm_frequency; //!< pwm frequency value in hertz 18 | float voltage_power_supply; //!< power supply voltage 19 | float voltage_limit; //!< limiting voltage set to the motor 20 | 21 | /** 22 | * Set phase voltages to the harware 23 | * 24 | * @param Ua phase A voltage 25 | * @param Ub phase B voltage 26 | */ 27 | virtual void setPwm(float Ua, float Ub) = 0; 28 | }; 29 | 30 | #endif -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/defaults.h: -------------------------------------------------------------------------------- 1 | // default configuration values 2 | // change this file to optimal values for your application 3 | 4 | #define DEF_POWER_SUPPLY 12.0 //!< default power supply voltage 5 | // velocity PI controller params 6 | #define DEF_PID_VEL_P 0.5 //!< default PID controller P value 7 | #define DEF_PID_VEL_I 10.0 //!< default PID controller I value 8 | #define DEF_PID_VEL_D 0.0 //!< default PID controller D value 9 | #define DEF_PID_VEL_RAMP 1000.0 //!< default PID controller voltage ramp value 10 | #define DEF_PID_VEL_LIMIT (DEF_POWER_SUPPLY) //!< default PID controller voltage limit 11 | 12 | // current sensing PID values 13 | #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) 14 | // for 16Mhz controllers like Arduino uno and mega 15 | #define DEF_PID_CURR_P 2 //!< default PID controller P value 16 | #define DEF_PID_CURR_I 100 //!< default PID controller I value 17 | #define DEF_PID_CURR_D 0.0 //!< default PID controller D value 18 | #define DEF_PID_CURR_RAMP 1000.0 //!< default PID controller voltage ramp value 19 | #define DEF_PID_CURR_LIMIT (DEF_POWER_SUPPLY) //!< default PID controller voltage limit 20 | #define DEF_CURR_FILTER_Tf 0.01 //!< default velocity filter time constant 21 | #else 22 | // for stm32, due, teensy, esp32 and similar 23 | #define DEF_PID_CURR_P 3 //!< default PID controller P value 24 | #define DEF_PID_CURR_I 300.0 //!< default PID controller I value 25 | #define DEF_PID_CURR_D 0.0 //!< default PID controller D value 26 | #define DEF_PID_CURR_RAMP 0 //!< default PID controller voltage ramp value 27 | #define DEF_PID_CURR_LIMIT (DEF_POWER_SUPPLY) //!< default PID controller voltage limit 28 | #define DEF_CURR_FILTER_Tf 0.005 //!< default currnet filter time constant 29 | #endif 30 | // default current limit values 31 | #define DEF_CURRENT_LIM 0.2 //!< 2Amps current limit by default 32 | 33 | // default monitor downsample 34 | #define DEF_MON_DOWNSMAPLE 100 //!< default monitor downsample 35 | #define DEF_MOTION_DOWNSMAPLE 0 //!< default motion downsample - disable 36 | 37 | // angle P params 38 | #define DEF_P_ANGLE_P 20.0 //!< default P controller P value 39 | #define DEF_VEL_LIM 20.0 //!< angle velocity limit default 40 | 41 | // index search 42 | #define DEF_INDEX_SEARCH_TARGET_VELOCITY 1.0 //!< default index search velocity 43 | // align voltage 44 | #define DEF_VOLTAGE_SENSOR_ALIGN 3.0 //!< default voltage for sensor and motor zero alignemt 45 | // low pass filter velocity 46 | #define DEF_VEL_FILTER_Tf 0.005 //!< default velocity filter time constant -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/foc_utils.h: -------------------------------------------------------------------------------- 1 | #ifndef FOCUTILS_LIB_H 2 | #define FOCUTILS_LIB_H 3 | 4 | #include "Arduino.h" 5 | 6 | // sign function 7 | #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) 8 | #define _round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) 9 | #define _constrain(amt, low, high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) 10 | #define _sqrt(a) (_sqrtApprox(a)) 11 | #define _isset(a) ( (a) != (NOT_SET) ) 12 | 13 | // utility defines 14 | #define _2_SQRT3 1.15470053838 15 | #define _SQRT3 1.73205080757 16 | #define _1_SQRT3 0.57735026919 17 | #define _SQRT3_2 0.86602540378 18 | #define _SQRT2 1.41421356237 19 | #define _120_D2R 2.09439510239 20 | #define _PI 3.14159265359 21 | #define _PI_2 1.57079632679 22 | #define _PI_3 1.0471975512 23 | #define _2PI 6.28318530718 24 | #define _3PI_2 4.71238898038 25 | #define _PI_6 0.52359877559 26 | 27 | #define NOT_SET -12345.0 28 | #define _HIGH_IMPEDANCE 0 29 | #define _HIGH_Z _HIGH_IMPEDANCE 30 | #define _ACTIVE 1 31 | 32 | // dq current structure 33 | struct DQCurrent_s 34 | { 35 | float d; 36 | float q; 37 | }; 38 | // phase current structure 39 | struct PhaseCurrent_s 40 | { 41 | float a; 42 | float b; 43 | float c; 44 | }; 45 | // dq voltage structs 46 | struct DQVoltage_s 47 | { 48 | float d; 49 | float q; 50 | }; 51 | 52 | 53 | /** 54 | * Function approximating the sine calculation by using fixed size array 55 | * - execution time ~40us (Arduino UNO) 56 | * 57 | * @param a angle in between 0 and 2PI 58 | */ 59 | float _sin(float a); 60 | 61 | /** 62 | * Function approximating cosine calculation by using fixed size array 63 | * - execution time ~50us (Arduino UNO) 64 | * 65 | * @param a angle in between 0 and 2PI 66 | */ 67 | float _cos(float a); 68 | 69 | /** 70 | * normalizing radian angle to [0,2PI] 71 | * @param angle - angle to be normalized 72 | */ 73 | float _normalizeAngle(float angle); 74 | 75 | 76 | /** 77 | * Electrical angle calculation 78 | * 79 | * @param shaft_angle - shaft angle of the motor 80 | * @param pole_pairs - number of pole pairs 81 | */ 82 | float _electricalAngle(float shaft_angle, int pole_pairs); 83 | 84 | /** 85 | * Function approximating square root function 86 | * - using fast inverse square root 87 | * 88 | * @param value - number 89 | */ 90 | float _sqrtApprox(float value); 91 | 92 | #endif -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/lowpass_filter.cpp: -------------------------------------------------------------------------------- 1 | #include "lowpass_filter.h" 2 | 3 | LowPassFilter::LowPassFilter(float time_constant) 4 | : Tf(time_constant), y_prev(0.0f) 5 | { 6 | timestamp_prev = _micros(); 7 | } 8 | 9 | 10 | float LowPassFilter::operator()(float x) 11 | { 12 | unsigned long timestamp = _micros(); 13 | float dt = (timestamp - timestamp_prev) * 1e-6f; 14 | 15 | if (dt < 0.0f || dt > 0.5f) 16 | dt = 1e-3f; 17 | 18 | float alpha = Tf / (Tf + dt); 19 | float y = alpha * y_prev + (1.0f - alpha) * x; 20 | 21 | y_prev = y; 22 | timestamp_prev = timestamp; 23 | return y; 24 | } 25 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/lowpass_filter.h: -------------------------------------------------------------------------------- 1 | #ifndef LOWPASS_FILTER_H 2 | #define LOWPASS_FILTER_H 3 | 4 | 5 | #include "time_utils.h" 6 | #include "foc_utils.h" 7 | 8 | /** 9 | * Low pass filter class 10 | */ 11 | class LowPassFilter 12 | { 13 | public: 14 | /** 15 | * @param Tf - Low pass filter time constant 16 | */ 17 | LowPassFilter(float Tf); 18 | 19 | ~LowPassFilter() = default; 20 | 21 | float operator()(float x); 22 | 23 | float Tf; //!< Low pass filter time constant 24 | 25 | protected: 26 | unsigned long timestamp_prev; //!< Last execution timestamp 27 | float y_prev; //!< filtered value in previous execution step 28 | }; 29 | 30 | #endif // LOWPASS_FILTER_H -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/pid.cpp: -------------------------------------------------------------------------------- 1 | #include "pid.h" 2 | 3 | PIDController::PIDController(float P, float I, float D, float ramp, float limit) 4 | : P(P), I(I), D(D), output_ramp(ramp) // output derivative limit [volts/second] 5 | , limit(limit) // output supply limit [volts] 6 | , integral_prev(0.0), error_prev(0.0), output_prev(0.0) 7 | { 8 | timestamp_prev = _micros(); 9 | } 10 | 11 | // PID controller function 12 | float PIDController::operator()(float error) 13 | { 14 | // calculate the time from the last call 15 | unsigned long timestamp_now = _micros(); 16 | float Ts = (timestamp_now - timestamp_prev) * 1e-6; 17 | // quick fix for strange cases (micros overflow) 18 | if (Ts <= 0 || Ts > 0.5) Ts = 1e-3; 19 | 20 | // u(s) = (P + I/s + Ds)e(s) 21 | // Discrete implementations 22 | // proportional part 23 | // u_p = P *e(k) 24 | float proportional = P * error; 25 | // Tustin transform of the integral part 26 | // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1) 27 | float integral = integral_prev + I * Ts * 0.5 * (error + error_prev); 28 | // antiwindup - limit the output 29 | integral = _constrain(integral, -limit, limit); 30 | // Discrete derivation 31 | // u_dk = D(ek - ek_1)/Ts 32 | float derivative = D * (error - error_prev) / Ts; 33 | 34 | // sum all the components 35 | float output = proportional + integral + derivative; 36 | // antiwindup - limit the output variable 37 | output = _constrain(output, -limit, limit); 38 | 39 | // if output ramp defined 40 | if (output_ramp > 0) 41 | { 42 | // limit the acceleration by ramping the output 43 | float output_rate = (output - output_prev) / Ts; 44 | if (output_rate > output_ramp) 45 | output = output_prev + output_ramp * Ts; 46 | else if (output_rate < -output_ramp) 47 | output = output_prev - output_ramp * Ts; 48 | } 49 | // saving for the next pass 50 | integral_prev = integral; 51 | output_prev = output; 52 | error_prev = error; 53 | timestamp_prev = timestamp_now; 54 | return output; 55 | } 56 | 57 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/pid.h: -------------------------------------------------------------------------------- 1 | #ifndef PID_H 2 | #define PID_H 3 | 4 | 5 | #include "time_utils.h" 6 | #include "foc_utils.h" 7 | 8 | /** 9 | * PID controller class 10 | */ 11 | class PIDController 12 | { 13 | public: 14 | /** 15 | * 16 | * @param P - Proportional gain 17 | * @param I - Integral gain 18 | * @param D - Derivative gain 19 | * @param ramp - Maximum speed of change of the output value 20 | * @param limit - Maximum output value 21 | */ 22 | PIDController(float P, float I, float D, float ramp, float limit); 23 | 24 | ~PIDController() = default; 25 | 26 | float operator()(float error); 27 | 28 | float P; //!< Proportional gain 29 | float I; //!< Integral gain 30 | float D; //!< Derivative gain 31 | float output_ramp; //!< Maximum speed of change of the output value 32 | float limit; //!< Maximum output value 33 | 34 | protected: 35 | float integral_prev; //!< last integral component value 36 | float error_prev; //!< last tracking error value 37 | unsigned long timestamp_prev; //!< Last execution timestamp 38 | float output_prev; //!< last pid output value 39 | }; 40 | 41 | #endif // PID_H -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/time_utils.cpp: -------------------------------------------------------------------------------- 1 | #include "time_utils.h" 2 | 3 | // function buffering delay() 4 | // arduino uno function doesn't work well with interrupts 5 | void _delay(unsigned long ms) 6 | { 7 | #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) 8 | // if arduino uno and other atmega328p chips 9 | // use while instad of delay, 10 | // due to wrong measurement based on changed timer0 11 | unsigned long t = _micros() + ms*1000; 12 | while( _micros() < t ){}; 13 | #else 14 | // regular micros 15 | delay(ms); 16 | #endif 17 | } 18 | 19 | 20 | // function buffering _micros() 21 | // arduino function doesn't work well with interrupts 22 | unsigned long _micros() 23 | { 24 | #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) 25 | // if arduino uno and other atmega328p chips 26 | //return the value based on the prescaler 27 | if((TCCR0B & 0b00000111) == 0x01) return (micros()/32); 28 | else return (micros()); 29 | #else 30 | // regular micros 31 | return micros(); 32 | #endif 33 | } 34 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/common/time_utils.h: -------------------------------------------------------------------------------- 1 | #ifndef TIME_UTILS_H 2 | #define TIME_UTILS_H 3 | 4 | #include "foc_utils.h" 5 | 6 | /** 7 | * Function implementing delay() function in milliseconds 8 | * - blocking function 9 | * - hardware specific 10 | 11 | * @param ms number of milliseconds to wait 12 | */ 13 | void _delay(unsigned long ms); 14 | 15 | /** 16 | * Function implementing timestamp getting function in microseconds 17 | * hardware specific 18 | */ 19 | unsigned long _micros(); 20 | 21 | 22 | #endif -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/communication/StepDirListener.cpp: -------------------------------------------------------------------------------- 1 | #include "StepDirListener.h" 2 | 3 | StepDirListener::StepDirListener(int _pinStep, int _pinDir, float _counter_to_value) 4 | { 5 | pin_step = _pinStep; 6 | pin_dir = _pinDir; 7 | counter_to_value = _counter_to_value; 8 | } 9 | 10 | void StepDirListener::init() 11 | { 12 | pinMode(pin_dir, INPUT); 13 | pinMode(pin_step, INPUT_PULLUP); 14 | count = 0; 15 | } 16 | 17 | void StepDirListener::enableInterrupt(void (*doA)()) 18 | { 19 | attachInterrupt(digitalPinToInterrupt(pin_step), doA, CHANGE); 20 | } 21 | 22 | void StepDirListener::attach(float *variable) 23 | { 24 | attached_variable = variable; 25 | } 26 | 27 | void StepDirListener::handle() 28 | { 29 | // read step status 30 | bool step = digitalRead(pin_step); 31 | // update counter only on rising edge 32 | if (step && step != step_active) 33 | { 34 | if (digitalRead(pin_dir)) 35 | count++; 36 | else 37 | count--; 38 | } 39 | step_active = step; 40 | // if attached variable update it 41 | if (attached_variable) *attached_variable = getValue(); 42 | } 43 | 44 | // calculate the position from counter 45 | float StepDirListener::getValue() 46 | { 47 | return (float) count * counter_to_value; 48 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/communication/StepDirListener.h: -------------------------------------------------------------------------------- 1 | #ifndef STEPDIR_H 2 | #define STEPDIR_H 3 | 4 | #include "Arduino.h" 5 | #include "../common/foc_utils.h" 6 | 7 | /** 8 | * Step/Dir listenner class for easier interraction with this communication interface. 9 | */ 10 | class StepDirListener 11 | { 12 | public: 13 | 14 | /** 15 | * Constructor for step/direction interface 16 | * @param step - pin 17 | * @param direction - pin 18 | * @param counter_to_value - step counter to value 19 | */ 20 | StepDirListener(int pinStep, int pinDir, float counter_to_value = 1); 21 | 22 | /** 23 | * Start listenning for step commands 24 | * 25 | * @param handleStep - on step received handler 26 | */ 27 | void enableInterrupt(void (*handleStep)()); 28 | 29 | /** 30 | * Initialise dir and step commands 31 | */ 32 | void init(); 33 | 34 | /** 35 | * step handler 36 | */ 37 | void handle(); 38 | 39 | /** 40 | * Get so far received valued 41 | */ 42 | float getValue(); 43 | 44 | /** 45 | * Attach the value to be updated on each step receive 46 | * - no need to call getValue function 47 | */ 48 | void attach(float *variable); 49 | 50 | // variables 51 | int pin_step; //!< step pin 52 | int pin_dir; //!< direction pin 53 | long count; //!< current counter value - should be set to 0 for homing 54 | 55 | private: 56 | float *attached_variable = nullptr; //!< pointer to the attached variable 57 | float counter_to_value; //!< step counter to value 58 | bool step_active = 0; //!< current step pin status (HIGH/LOW) - debouncing variable 59 | }; 60 | 61 | #endif -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/communication/commands.h: -------------------------------------------------------------------------------- 1 | #ifndef COMMANDS_h 2 | #define COMMANDS_h 3 | 4 | // see docs.simplefoc.com for in depth explanation of the commands 5 | 6 | // list of commands 7 | #define CMD_C_D_PID 'D' //!< current d PID & LPF 8 | #define CMD_C_Q_PID 'Q' //!< current d PID & LPF 9 | #define CMD_V_PID 'V' //!< velocity PID & LPF 10 | #define CMD_A_PID 'A' //!< angle PID & LPF 11 | #define CMD_STATUS 'E' //!< motor status enable/disable 12 | #define CMD_LIMITS 'L' //!< limits current/voltage/velocity 13 | #define CMD_MOTION_TYPE 'C' //!< motion control type 14 | #define CMD_TORQUE_TYPE 'T' //!< torque control type 15 | #define CMD_SENSOR 'S' //!< sensor offsets 16 | #define CMD_MONITOR 'M' //!< monitoring 17 | #define CMD_RESIST 'R' //!< motor phase resistance 18 | #define CMD_PWMMOD 'W' //!< pwm modulation 19 | 20 | // commander configuration 21 | #define CMD_SCAN '?' //!< command scaning the network - only for commander 22 | #define CMD_VERBOSE '@' //!< command setting output mode - only for commander 23 | #define CMD_DECIMAL '#' //!< command setting decimal places - only for commander 24 | 25 | // subcomands 26 | //pid - lpf 27 | #define SCMD_PID_P 'P' //!< PID gain P 28 | #define SCMD_PID_I 'I' //!< PID gain I 29 | #define SCMD_PID_D 'D' //!< PID gain D 30 | #define SCMD_PID_RAMP 'R' //!< PID ramp 31 | #define SCMD_PID_LIM 'L' //!< PID limit 32 | #define SCMD_LPF_TF 'F' //!< LPF time constant 33 | // limits 34 | #define SCMD_LIM_CURR 'C' //!< Limit current 35 | #define SCMD_LIM_VOLT 'U' //!< Limit voltage 36 | #define SCMD_LIM_VEL 'V' //!< Limit velocity 37 | //sensor 38 | #define SCMD_SENS_MECH_OFFSET 'M' //!< Sensor offset 39 | #define SCMD_SENS_ELEC_OFFSET 'E' //!< Sensor electrical zero offset 40 | // monitoring 41 | #define SCMD_DOWNSAMPLE 'D' //!< Monitoring downsample value 42 | #define SCMD_CLEAR 'C' //!< Clear all monitored variables 43 | #define SCMD_GET 'G' //!< Get variable only one value 44 | #define SCMD_SET 'S' //!< Set variables to be monitored 45 | 46 | #define SCMD_PWMMOD_TYPE 'T' //!<< Pwm modulation type 47 | #define SCMD_PWMMOD_CENTER 'C' //!<< Pwm modulation center flag 48 | 49 | 50 | #endif -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/current_sense/InlineCurrentSense.h: -------------------------------------------------------------------------------- 1 | #ifndef INLINE_CS_LIB_H 2 | #define INLINE_CS_LIB_H 3 | 4 | #include "Arduino.h" 5 | #include "../common/foc_utils.h" 6 | #include "../common/time_utils.h" 7 | #include "../common/base_classes/CurrentSense.h" 8 | #include "hardware_api.h" 9 | 10 | 11 | class InlineCurrentSense : public CurrentSense 12 | { 13 | public: 14 | /** 15 | InlineCurrentSense class constructor 16 | @param shunt_resistor shunt resistor value 17 | @param gain current-sense op-amp gain 18 | @param phA A phase adc pin 19 | @param phB B phase adc pin 20 | @param phC C phase adc pin (optional) 21 | */ 22 | InlineCurrentSense(float shunt_resistor, float gain, int pinA, int pinB, int pinC = NOT_SET); 23 | 24 | // CurrentSense interface implementing functions 25 | void init() override; 26 | 27 | PhaseCurrent_s getPhaseCurrents() override; 28 | 29 | int driverSync(BLDCDriver *driver) override; 30 | 31 | int driverAlign(BLDCDriver *driver, float voltage) override; 32 | 33 | // ADC measuremnet gain for each phase 34 | // support for different gains for different phases of more commonly - inverted phase currents 35 | // this should be automated later 36 | float gain_a; //!< phase A gain 37 | float gain_b; //!< phase B gain 38 | float gain_c; //!< phase C gain 39 | 40 | private: 41 | 42 | // hardware variables 43 | int pinA; //!< pin A analog pin for current measurement 44 | int pinB; //!< pin B analog pin for current measurement 45 | int pinC; //!< pin C analog pin for current measurement 46 | 47 | // gain variables 48 | double shunt_resistor; //!< Shunt resistor value 49 | double amp_gain; //!< amp gain value 50 | double volts_to_amps_ratio; //!< Volts to amps ratio 51 | 52 | /** 53 | * Function finding zero offsets of the ADC 54 | */ 55 | void calibrateOffsets(); 56 | 57 | double offset_ia; //!< zero current A voltage value (center of the adc reading) 58 | double offset_ib; //!< zero current B voltage value (center of the adc reading) 59 | double offset_ic; //!< zero current C voltage value (center of the adc reading) 60 | 61 | }; 62 | 63 | #endif -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/current_sense/hardware_api.h: -------------------------------------------------------------------------------- 1 | #ifndef HARDWARE_UTILS_H 2 | #define HARDWARE_UTILS_H 3 | 4 | #include "../common/foc_utils.h" 5 | #include "../common/time_utils.h" 6 | 7 | /** 8 | * function reading an ADC value and returning the read voltage 9 | * 10 | * @param pinA - the arduino pin to be read (it has to be ADC pin) 11 | */ 12 | float _readADCVoltage(const int pinA); 13 | 14 | /** 15 | * function reading an ADC value and returning the read voltage 16 | * 17 | * @param pinA - adc pin A 18 | * @param pinB - adc pin B 19 | * @param pinC - adc pin C 20 | */ 21 | void _configureADC(const int pinA, const int pinB, const int pinC = NOT_SET); 22 | 23 | #endif -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/current_sense/hardware_specific/generic_mcu.cpp: -------------------------------------------------------------------------------- 1 | #include "../hardware_api.h" 2 | 3 | 4 | #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) // if mcu is atmega328 or atmega2560 5 | #define _ADC_VOLTAGE 5.0 6 | #define _ADC_RESOLUTION 1024.0 7 | #ifndef cbi 8 | #define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit)) 9 | #endif 10 | #ifndef sbi 11 | #define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit)) 12 | #endif 13 | #elif defined(__arm__) && defined(CORE_TEENSY) // or teensy 14 | #define _ADC_VOLTAGE 3.3 15 | #define _ADC_RESOLUTION 1024.0 16 | #elif defined(__arm__) && defined(__SAM3X8E__) // or due 17 | #define _ADC_VOLTAGE 3.3 18 | #define _ADC_RESOLUTION 1024.0 19 | #elif defined(ESP_H) // or esp32 20 | #define _ADC_VOLTAGE 3.3 21 | #define _ADC_RESOLUTION 4095.0 22 | #elif defined(_STM32_DEF_) // or stm32 23 | #define _ADC_VOLTAGE 3.3 24 | #define _ADC_RESOLUTION 1024.0 25 | #else 26 | #define _ADC_VOLTAGE 5.0 27 | #define _ADC_RESOLUTION 1024.0 28 | #endif 29 | 30 | // adc counts to voltage conversion ratio 31 | // some optimizing for faster execution 32 | #define _ADC_CONV ( (_ADC_VOLTAGE) / (_ADC_RESOLUTION) ) 33 | 34 | // function reading an ADC value and returning the read voltage 35 | float _readADCVoltage(const int pinA) 36 | { 37 | uint32_t raw_adc = analogRead(pinA); 38 | return raw_adc * _ADC_CONV; 39 | } 40 | 41 | 42 | // function reading an ADC value and returning the read voltage 43 | void _configureADC(const int pinA, const int pinB, const int pinC) 44 | { 45 | pinMode(pinA, INPUT); 46 | pinMode(pinB, INPUT); 47 | if (_isset(pinC)) pinMode(pinC, INPUT); 48 | 49 | #if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) // if mcu is atmega328 or atmega2560 50 | // set hight frequency adc - ADPS2,ADPS1,ADPS0 | 001 (16mhz/2) | 010 ( 16mhz/4 ) | 011 (16mhz/8) | 100(16mhz/16) | 101 (16mhz/32) | 110 (16mhz/64) | 111 (16mhz/128 default) 51 | // set divisor to 8 - adc frequency 16mhz/8 = 2 mhz 52 | // arduino takes 25 conversions per sample so - 2mhz/25 = 80k samples per second - 12.5us per sample 53 | cbi(ADCSRA, ADPS2); 54 | sbi(ADCSRA, ADPS1); 55 | sbi(ADCSRA, ADPS0); 56 | #endif 57 | } -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/drivers/BLDCDriver3PWM.h: -------------------------------------------------------------------------------- 1 | #ifndef BLDCDriver3PWM_h 2 | #define BLDCDriver3PWM_h 3 | 4 | #include "../common/base_classes/BLDCDriver.h" 5 | #include "../common/foc_utils.h" 6 | #include "../common/time_utils.h" 7 | #include "../common/defaults.h" 8 | #include "hardware_api.h" 9 | 10 | /** 11 | 3 pwm bldc driver class 12 | */ 13 | class BLDCDriver3PWM : public BLDCDriver 14 | { 15 | public: 16 | /** 17 | BLDCDriver class constructor 18 | @param phA A phase pwm pin 19 | @param phB B phase pwm pin 20 | @param phC C phase pwm pin 21 | @param en1 enable pin (optional input) 22 | @param en2 enable pin (optional input) 23 | @param en3 enable pin (optional input) 24 | */ 25 | BLDCDriver3PWM(int phA, int phB, int phC, int en1 = NOT_SET, int en2 = NOT_SET, int en3 = NOT_SET); 26 | 27 | /** Motor hardware init function */ 28 | int init() override; 29 | 30 | /** Motor disable function */ 31 | void disable() override; 32 | 33 | /** Motor enable function */ 34 | void enable() override; 35 | 36 | // hardware variables 37 | int pwmA; //!< phase A pwm pin number 38 | int pwmB; //!< phase B pwm pin number 39 | int pwmC; //!< phase C pwm pin number 40 | int enableA_pin; //!< enable pin number 41 | int enableB_pin; //!< enable pin number 42 | int enableC_pin; //!< enable pin number 43 | 44 | /** 45 | * Set phase voltages to the harware 46 | * 47 | * @param Ua - phase A voltage 48 | * @param Ub - phase B voltage 49 | * @param Uc - phase C voltage 50 | */ 51 | void setPwm(float Ua, float Ub, float Uc) override; 52 | 53 | /** 54 | * Set phase voltages to the harware 55 | * 56 | * @param sc - phase A state : active / disabled ( high impedance ) 57 | * @param sb - phase B state : active / disabled ( high impedance ) 58 | * @param sa - phase C state : active / disabled ( high impedance ) 59 | */ 60 | virtual void setPhaseState(int sa, int sb, int sc) override; 61 | 62 | private: 63 | 64 | }; 65 | 66 | 67 | #endif 68 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/drivers/BLDCDriver6PWM.h: -------------------------------------------------------------------------------- 1 | #ifndef BLDCDriver6PWM_h 2 | #define BLDCDriver6PWM_h 3 | 4 | #include "../common/base_classes/BLDCDriver.h" 5 | #include "../common/foc_utils.h" 6 | #include "../common/time_utils.h" 7 | #include "../common/defaults.h" 8 | #include "hardware_api.h" 9 | 10 | /** 11 | 6 pwm bldc driver class 12 | */ 13 | class BLDCDriver6PWM : public BLDCDriver 14 | { 15 | public: 16 | /** 17 | BLDCDriver class constructor 18 | @param phA_h A phase pwm pin 19 | @param phA_l A phase pwm pin 20 | @param phB_h B phase pwm pin 21 | @param phB_l A phase pwm pin 22 | @param phC_h C phase pwm pin 23 | @param phC_l A phase pwm pin 24 | @param en enable pin (optional input) 25 | */ 26 | BLDCDriver6PWM(int phA_h, int phA_l, int phB_h, int phB_l, int phC_h, int phC_l, int en = NOT_SET); 27 | 28 | /** Motor hardware init function */ 29 | int init() override; 30 | 31 | /** Motor disable function */ 32 | void disable() override; 33 | 34 | /** Motor enable function */ 35 | void enable() override; 36 | 37 | // hardware variables 38 | int pwmA_h, pwmA_l; //!< phase A pwm pin number 39 | int pwmB_h, pwmB_l; //!< phase B pwm pin number 40 | int pwmC_h, pwmC_l; //!< phase C pwm pin number 41 | int enable_pin; //!< enable pin number 42 | bool enable_active_high = true; 43 | 44 | float dead_zone; //!< a percentage of dead-time(zone) (both high and low side in low) for each pwm cycle [0,1] 45 | 46 | /** 47 | * Set phase voltages to the harware 48 | * 49 | * @param Ua - phase A voltage 50 | * @param Ub - phase B voltage 51 | * @param Uc - phase C voltage 52 | */ 53 | void setPwm(float Ua, float Ub, float Uc) override; 54 | 55 | /** 56 | * Set phase voltages to the harware 57 | * 58 | * @param sc - phase A state : active / disabled ( high impedance ) 59 | * @param sb - phase B state : active / disabled ( high impedance ) 60 | * @param sa - phase C state : active / disabled ( high impedance ) 61 | */ 62 | virtual void setPhaseState(int sa, int sb, int sc) override; 63 | 64 | private: 65 | 66 | }; 67 | 68 | 69 | #endif 70 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/drivers/StepperDriver2PWM.h: -------------------------------------------------------------------------------- 1 | #ifndef STEPPER_DRIVER_2PWM_h 2 | #define STEPPER_DRIVER_2PWM_h 3 | 4 | #include "../common/base_classes/StepperDriver.h" 5 | #include "../common/foc_utils.h" 6 | #include "../common/time_utils.h" 7 | #include "../common/defaults.h" 8 | #include "hardware_api.h" 9 | 10 | /** 11 | 2 pwm stepper driver class 12 | */ 13 | class StepperDriver2PWM : public StepperDriver 14 | { 15 | public: 16 | /** 17 | StepperMotor class constructor 18 | @param pwm1 PWM1 phase pwm pin 19 | @param in1a IN1A phase dir pin 20 | @param in1b IN1B phase dir pin 21 | @param pwm2 PWM2 phase pwm pin 22 | @param in2a IN2A phase dir pin 23 | @param in2b IN2B phase dir pin 24 | @param en1 enable pin phase 1 (optional input) 25 | @param en2 enable pin phase 2 (optional input) 26 | */ 27 | StepperDriver2PWM(int pwm1, int in1a, int in1b, int pwm2, int in2a, int in2b, int en1 = NOT_SET, int en2 = NOT_SET); 28 | 29 | /** 30 | StepperMotor class constructor 31 | @param pwm1 PWM1 phase pwm pin 32 | @param dir1 DIR1 phase dir pin 33 | @param pwm2 PWM2 phase pwm pin 34 | @param dir2 DIR2 phase dir pin 35 | @param en1 enable pin phase 1 (optional input) 36 | @param en2 enable pin phase 2 (optional input) 37 | */ 38 | StepperDriver2PWM(int pwm1, int dir1, int pwm2, int dir2, int en1 = NOT_SET, int en2 = NOT_SET); 39 | 40 | /** Motor hardware init function */ 41 | int init() override; 42 | 43 | /** Motor disable function */ 44 | void disable() override; 45 | 46 | /** Motor enable function */ 47 | void enable() override; 48 | 49 | // hardware variables 50 | int pwm1; //!< phase 1 pwm pin number 51 | int dir1a; //!< phase 1 INA pin number 52 | int dir1b; //!< phase 1 INB pin number 53 | int pwm2; //!< phase 2 pwm pin number 54 | int dir2a; //!< phase 2 INA pin number 55 | int dir2b; //!< phase 2 INB pin number 56 | int enable_pin1; //!< enable pin number phase 1 57 | int enable_pin2; //!< enable pin number phase 2 58 | 59 | /** 60 | * Set phase voltages to the harware 61 | * 62 | * @param Ua phase A voltage 63 | * @param Ub phase B voltage 64 | */ 65 | void setPwm(float Ua, float Ub) override; 66 | 67 | private: 68 | 69 | }; 70 | 71 | 72 | #endif 73 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/drivers/StepperDriver4PWM.h: -------------------------------------------------------------------------------- 1 | #ifndef STEPPER_DRIVER_4PWM_h 2 | #define STEPPER_DRIVER_4PWM_h 3 | 4 | #include "../common/base_classes/StepperDriver.h" 5 | #include "../common/foc_utils.h" 6 | #include "../common/time_utils.h" 7 | #include "../common/defaults.h" 8 | #include "hardware_api.h" 9 | 10 | /** 11 | 4 pwm stepper driver class 12 | */ 13 | class StepperDriver4PWM : public StepperDriver 14 | { 15 | public: 16 | /** 17 | StepperMotor class constructor 18 | @param ph1A 1A phase pwm pin 19 | @param ph1B 1B phase pwm pin 20 | @param ph2A 2A phase pwm pin 21 | @param ph2B 2B phase pwm pin 22 | @param en1 enable pin phase 1 (optional input) 23 | @param en2 enable pin phase 2 (optional input) 24 | */ 25 | StepperDriver4PWM(int ph1A, int ph1B, int ph2A, int ph2B, int en1 = NOT_SET, int en2 = NOT_SET); 26 | 27 | /** Motor hardware init function */ 28 | int init() override; 29 | 30 | /** Motor disable function */ 31 | void disable() override; 32 | 33 | /** Motor enable function */ 34 | void enable() override; 35 | 36 | // hardware variables 37 | int pwm1A; //!< phase 1A pwm pin number 38 | int pwm1B; //!< phase 1B pwm pin number 39 | int pwm2A; //!< phase 2A pwm pin number 40 | int pwm2B; //!< phase 2B pwm pin number 41 | int enable_pin1; //!< enable pin number phase 1 42 | int enable_pin2; //!< enable pin number phase 2 43 | 44 | /** 45 | * Set phase voltages to the harware 46 | * 47 | * @param Ua phase A voltage 48 | * @param Ub phase B voltage 49 | */ 50 | void setPwm(float Ua, float Ub) override; 51 | 52 | private: 53 | 54 | }; 55 | 56 | 57 | #endif 58 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/Arduino-FOC/src/sensors/MagneticSensorAnalog.h: -------------------------------------------------------------------------------- 1 | #ifndef MAGNETICSENSORANALOG_LIB_H 2 | #define MAGNETICSENSORANALOG_LIB_H 3 | 4 | #include "Arduino.h" 5 | #include "../common/base_classes/Sensor.h" 6 | #include "../common/foc_utils.h" 7 | #include "../common/time_utils.h" 8 | 9 | /** 10 | * This sensor has been tested with AS5600 running in 'analog mode'. This is where output pin of AS6000 is connected to an analog pin on your microcontroller. 11 | * This approach is very simple but you may more accurate results with MagneticSensorI2C if that is also supported as its skips the DAC -> ADC conversion (ADC supports MagneticSensorI2C) 12 | */ 13 | class MagneticSensorAnalog : public Sensor 14 | { 15 | public: 16 | /** 17 | * MagneticSensorAnalog class constructor 18 | * @param _pinAnalog the pin to read the PWM signal 19 | */ 20 | MagneticSensorAnalog(uint8_t _pinAnalog, int _min = 0, int _max = 0); 21 | 22 | 23 | /** sensor initialise pins */ 24 | void init(); 25 | 26 | int pinAnalog; //!< encoder hardware pin A 27 | 28 | // Encoder configuration 29 | Pullup pullup; 30 | 31 | // implementation of abstract functions of the Sensor class 32 | /** get current angle (rad) */ 33 | float getAngle() override; 34 | 35 | /** get current angular velocity (rad/s) **/ 36 | float getVelocity() override; 37 | 38 | /** raw count (typically in range of 0-1023), useful for debugging resolution issues */ 39 | int raw_count; 40 | 41 | private: 42 | int min_raw_count; 43 | int max_raw_count; 44 | int cpr; 45 | 46 | int read(); 47 | 48 | /** 49 | * Function getting current angle register value 50 | * it uses angle_register variable 51 | */ 52 | int getRawCount(); 53 | 54 | // total angle tracking variables 55 | float full_rotation_offset; //! THIS FILE 25 | | 26 | |- platformio.ini 27 | |--src 28 | |- main.c 29 | 30 | and a contents of `src/main.c`: 31 | ``` 32 | #include 33 | #include 34 | 35 | int main (void) 36 | { 37 | ... 38 | } 39 | 40 | ``` 41 | 42 | PlatformIO Library Dependency Finder will find automatically dependent 43 | libraries scanning project source files. 44 | 45 | More information about PlatformIO Library Dependency Finder 46 | - https://docs.platformio.org/page/librarymanager/ldf.html 47 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/STM32_Examples.h: -------------------------------------------------------------------------------- 1 | #error *********** This is a dummy library, purely to make the STM32 examples easy to access. Do not include it ********* -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Analog/AnalogInOutSerial/AnalogInOutSerial.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Analog input, analog output, serial output 3 | 4 | Reads an analog input pin, maps the result to a range from 0 to 5 | 65535 and uses the result to set the pulse width modulation (PWM) of 6 | an output pin. Also prints the results to the serial monitor. 7 | 8 | (You may need to change the pin numbers analogInPin and analogOutPin 9 | if you're not using a Maple). 10 | 11 | The circuit: 12 | * Potentiometer connected to analog pin 15. 13 | Center pin of the potentiometer goes to the analog pin. 14 | Side pins of the potentiometer go to +3.3V and ground. 15 | * LED connected from digital pin 9 to ground 16 | 17 | created 29 Dec. 2008 18 | by Tom Igoe 19 | 20 | ported to Maple 21 | by LeafLabs 22 | */ 23 | 24 | // These constants won't change. They're used to give names 25 | // to the pins used: 26 | 27 | const int analogInPin = 15; // Analog input pin that the potentiometer 28 | // is attached to 29 | 30 | const int pwmOutPin = 9; // PWM pin that the LED is attached to 31 | 32 | // These variables will change: 33 | int sensorValue = 0; // value read from the pot 34 | int outputValue = 0; // value output to the PWM 35 | 36 | void setup() 37 | { 38 | // Configure the ADC pin 39 | pinMode(analogInPin, INPUT_ANALOG); 40 | // Configure LED pin 41 | pinMode(pwmOutPin, PWM); 42 | Serial.begin(115200); // Ignored by Maple. But needed by boards using Hardware serial via a USB to Serial Adaptor 43 | } 44 | 45 | void loop() 46 | { 47 | // read the analog in value: 48 | sensorValue = analogRead(analogInPin); 49 | // map it to the range of the analog out: 50 | outputValue = map(sensorValue, 0, 1023, 0, 65535); 51 | // change the analog out value: 52 | pwmWrite(pwmOutPin, outputValue); 53 | 54 | // print the results to the serial monitor: 55 | Serial.print("sensor = "); 56 | Serial.print(sensorValue); 57 | Serial.print("\t output = "); 58 | Serial.println(outputValue); 59 | } 60 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Analog/AnalogInSerial/AnalogInSerial.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Analog input, serial output 3 | 4 | Reads an analog input pin, prints the results to the serial monitor. 5 | 6 | The circuit: 7 | 8 | * Potentiometer connected to analog pin 15. 9 | * Center pin of the potentiometer goes to the analog pin. 10 | * Side pins of the potentiometer go to +3.3V (VCC) and ground 11 | 12 | created over and over again 13 | by Tom Igoe and everyone who's ever used Arduino 14 | 15 | Ported to Maple 27 May, 2010 by Bryan Newbold 16 | */ 17 | 18 | // Analog input pin. You may need to change this number if your board 19 | // can't do analog input on pin 15. 20 | const int analogInputPin = 15; 21 | 22 | void setup() 23 | { 24 | // Declare analogInputPin as INPUT_ANALOG: 25 | pinMode(analogInputPin, INPUT_ANALOG); 26 | Serial.begin(115200); // Ignored by Maple. But needed by boards using Hardware serial via a USB to Serial Adaptor 27 | } 28 | 29 | void loop() 30 | { 31 | // Read the analog input into a variable: 32 | int analogValue = analogRead(analogInputPin); 33 | 34 | // print the result: 35 | Serial.println(analogValue); 36 | } 37 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Analog/AnalogInput/AnalogInput.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Analog Input 3 | 4 | Demonstrates analog input by reading an analog sensor on analog pin 5 | 0 and turning on and off the Maple's built-in light emitting diode 6 | (LED). The amount of time the LED will be on and off depends on the 7 | value obtained by analogRead(). 8 | 9 | Created by David Cuartielles 10 | Modified 16 Jun 2009 11 | By Tom Igoe 12 | 13 | http://leaflabs.com/docs/adc.html 14 | 15 | Ported to Maple 27 May 2010 16 | by Bryan Newbold 17 | */ 18 | 19 | int sensorPin = 0; // Select the input pin for the potentiometer 20 | int sensorValue = 0; // Variable to store the value coming from the sensor 21 | 22 | void setup() 23 | { 24 | // Declare the sensorPin as INPUT_ANALOG: 25 | pinMode(sensorPin, INPUT_ANALOG); 26 | // Declare the LED's pin as an OUTPUT. (33 is a built-in 27 | // constant which is the pin number of the built-in LED. On the 28 | // Maple, it is 13.) 29 | pinMode(33, OUTPUT); 30 | } 31 | 32 | void loop() 33 | { 34 | // Read the value from the sensor: 35 | sensorValue = analogRead(sensorPin); 36 | // Turn the LED pin on: 37 | digitalWrite(33, HIGH); 38 | // Stop the program for milliseconds: 39 | delay(sensorValue); 40 | // Turn the LED pin off: 41 | digitalWrite(33, LOW); 42 | // Stop the program for for milliseconds: 43 | delay(sensorValue); 44 | } 45 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Analog/Calibration/Calibration.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Calibration 3 | 4 | Demonstrates one techinque for calibrating sensor input. The sensor 5 | readings during the first five seconds of the sketch execution 6 | define the minimum and maximum of expected values attached to the 7 | sensor pin. 8 | 9 | The sensor minumum and maximum initial values may seem backwards. 10 | Initially, you set the minimum high and listen for anything lower, 11 | saving it as the new minumum. Likewise, you set the maximum low and 12 | listen for anything higher as the new maximum. 13 | 14 | The circuit: 15 | * Analog sensor (potentiometer will do) attached to analog input 15 16 | 17 | created 29 Oct 2008 18 | By David A Mellis 19 | Modified 17 Jun 2009 20 | By Tom Igoe 21 | 22 | http://arduino.cc/en/Tutorial/Calibration 23 | 24 | Ported to Maple 27 May 2010 25 | by Bryan Newbold 26 | */ 27 | 28 | // Constant (won't change): 29 | const int sensorPin = 15; // pin that the sensor is attached to 30 | 31 | // Variables: 32 | int sensorMin = 1023; // minimum sensor value 33 | int sensorMax = 0; // maximum sensor value 34 | int sensorValue = 0; // the sensor value 35 | 36 | void setup() 37 | { 38 | // Declare the sensorPin as INPUT_ANALOG: 39 | pinMode(sensorPin, INPUT_ANALOG); 40 | 41 | // Turn on the built-in LED to signal the start of the calibration 42 | // period: 43 | pinMode(33, OUTPUT); 44 | digitalWrite(33, HIGH); 45 | 46 | // Calibrate during the first five seconds: 47 | while (millis() < 5000) 48 | { 49 | sensorValue = analogRead(sensorPin); 50 | 51 | // Record the maximum sensor value: 52 | if (sensorValue > sensorMax) 53 | { 54 | sensorMax = sensorValue; 55 | } 56 | 57 | // Record the minimum sensor value: 58 | if (sensorValue < sensorMin) 59 | { 60 | sensorMin = sensorValue; 61 | } 62 | } 63 | 64 | // Signal the end of the calibration period: 65 | digitalWrite(33, LOW); 66 | } 67 | 68 | void loop() 69 | { 70 | // Read the sensor: 71 | sensorValue = analogRead(sensorPin); 72 | 73 | // Apply the calibration to the sensor reading: 74 | sensorValue = map(sensorValue, sensorMin, sensorMax, 0, 65535); 75 | 76 | // In case the sensor value is outside the range seen during calibration: 77 | sensorValue = constrain(sensorValue, 0, 65535); 78 | 79 | // Fade the LED using the calibrated value: 80 | pwmWrite(33, sensorValue); 81 | } 82 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Analog/Fading/Fading.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Fading 3 | 4 | This example shows how to fade an LED using the pwmWrite() function. 5 | 6 | Created 1 Nov 2008 7 | By David A. Mellis 8 | Modified 17 June 2009 9 | By Tom Igoe 10 | 11 | Modified by LeafLabs for Maple 12 | 13 | http://arduino.cc/en/Tutorial/Fading 14 | 15 | For differences between Maple's pwmWrite() and Arduino's analogWrite(): 16 | http://leaflabs.com/docs/lang/api/analogwrite.html#arduino-compatibility 17 | */ 18 | 19 | int ledPin = 9; // Connect an LED to digital pin 9, or any other 20 | // PWM-capable pin 21 | 22 | void setup() 23 | { 24 | pinMode(ledPin, PWM); // setup the pin as PWM 25 | } 26 | 27 | void loop() 28 | { 29 | // Fade in from min to max in increments of 1280 points: 30 | for (int fadeValue = 0; fadeValue <= 65535; fadeValue += 1280) 31 | { 32 | // Sets the value (range from 0 to 65535): 33 | pwmWrite(ledPin, fadeValue); 34 | // Wait for 30 milliseconds to see the dimming effect: 35 | delay(30); 36 | } 37 | 38 | // Fade out from max to min in increments of 1280 points: 39 | for (int fadeValue = 65535; fadeValue >= 0; fadeValue -= 1280) 40 | { 41 | // Sets the value (range from 0 to 1280): 42 | pwmWrite(ledPin, fadeValue); 43 | // Wait for 30 milliseconds to see the dimming effect: 44 | delay(30); 45 | } 46 | } 47 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Analog/Smoothing/Smoothing.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Smoothing 3 | 4 | Reads repeatedly from an analog input, calculating a running average 5 | and printing it to the computer. Keeps ten readings in an array and 6 | continually averages them. 7 | 8 | The circuit: 9 | * Analog sensor (potentiometer will do) attached to pin 15 10 | 11 | Created 22 April 2007 12 | By David A. Mellis 13 | 14 | http://www.arduino.cc/en/Tutorial/Smoothing 15 | 16 | Ported to Maple 27 May 2010 17 | by Bryan Newbold 18 | */ 19 | 20 | // Define the number of samples to keep track of. The higher the number, 21 | // the more the readings will be smoothed, but the slower the output will 22 | // respond to the input. Using a constant rather than a normal variable lets 23 | // use this value to determine the size of the readings array. 24 | const int numReadings = 10; 25 | 26 | int readings[numReadings]; // the readings from the analog input 27 | int index1 = 0; // the index1 of the current reading 28 | int total = 0; // the running total 29 | int average = 0; // the average 30 | 31 | int inputPin = 15; // analog input pin 32 | 33 | void setup() 34 | { 35 | // Declare the input pin as INPUT_ANALOG: 36 | pinMode(inputPin, INPUT_ANALOG); 37 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 38 | 39 | // Initialize all the readings to 0: 40 | for (int thisReading = 0; thisReading < numReadings; thisReading++) 41 | { 42 | readings[thisReading] = 0; 43 | } 44 | } 45 | 46 | void loop() 47 | { 48 | // Subtract the last reading: 49 | total = total - readings[index1]; 50 | // Read from the sensor: 51 | readings[index1] = analogRead(inputPin); 52 | // Add the reading to the total: 53 | total = total + readings[index1]; 54 | // Advance to the next position in the array: 55 | index1 = index1 + 1; 56 | 57 | // If we're at the end of the array... 58 | if (index1 >= numReadings) 59 | { 60 | // ...wrap around to the beginning: 61 | index1 = 0; 62 | } 63 | 64 | // Calculate the average: 65 | average = total / numReadings; 66 | // Send it to the computer (as ASCII digits) 67 | Serial.println(average, DEC); 68 | } 69 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Communication/Dimmer/Dimmer.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Dimmer 3 | 4 | Demonstrates sending data from the computer to the Maple, in this 5 | case to control the brightness of an LED. The data is sent in 6 | individual bytes, each of which ranges from 0 to 255. Maple reads 7 | these bytes and uses them to set the brightness of the LED. 8 | 9 | The circuit: 10 | LED connected to pin 9. 11 | Serial connection to Processing, Max/MSP, or another serial application. 12 | 13 | created 2006 14 | by David A. Mellis 15 | modified 14 Apr 2009 16 | by Tom Igoe and Scott Fitzgerald 17 | 18 | http://www.arduino.cc/en/Tutorial/Dimmer 19 | http://leaflabs.com/docs/lang/api/pwmwrite.html 20 | 21 | Ported to the Maple 28 May 2010 22 | */ 23 | 24 | int ledPin = 9; 25 | 26 | void setup() 27 | { 28 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 29 | // Declare ledPin as an OUTPUT: 30 | pinMode(ledPin, OUTPUT); 31 | } 32 | 33 | void loop() 34 | { 35 | int brightness; 36 | 37 | // Check if data has been sent from the computer: 38 | if (Serial.available()) 39 | { 40 | // Read the most recent byte (which will be from 0 to 255), then 41 | // convert it to be between 0 and 65,535, which are the minimum 42 | // and maximum values usable for PWM: 43 | brightness = map(Serial.read(), 0, 255, 0, 65535); 44 | // Set the brightness of the LED: 45 | pwmWrite(ledPin, brightness); 46 | } 47 | } 48 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Communication/MIDI/Midi.ino: -------------------------------------------------------------------------------- 1 | /* 2 | MIDI note player 3 | 4 | This sketch shows how to use Serial1 (pins 7 and 8) to send MIDI 5 | note data. If this circuit is connected to a MIDI synth, it will 6 | play the notes F#-0 (0x1E) to F#-5 (0x5A) in sequence. 7 | 8 | 9 | The circuit: 10 | * Pin 7 connected to MIDI jack pin 5 11 | * MIDI jack pin 2 connected to ground 12 | * MIDI jack pin 4 connected to +5V through 220-ohm resistor 13 | Attach a MIDI cable to the jack, then to a MIDI synth, and play music. 14 | 15 | created 13 Jun 2006 16 | modified 2 Jul 2009 17 | by Tom Igoe 18 | 19 | http://www.arduino.cc/en/Tutorial/MIDI 20 | 21 | Ported to the Maple 27 May 2010 22 | by Bryan Newbold 23 | */ 24 | 25 | void setup() 26 | { 27 | // Set MIDI baud rate: 28 | Serial1.begin(31250); 29 | } 30 | 31 | void loop() 32 | { 33 | // Play notes from F#-0 (0x1E) to F#-5 (0x5A): 34 | for (int note = 0x1E; note < 0x5A; note++) 35 | { 36 | // Note on channel 1 (0x90), some note value (note), middle 37 | // velocity (0x45): 38 | noteOn(0x90, note, 0x45); 39 | delay(100); 40 | // Note on channel 1 (0x90), some note value (note), silent 41 | // velocity (0x00): 42 | noteOn(0x90, note, 0x00); 43 | delay(100); 44 | } 45 | } 46 | 47 | // Plays a MIDI note. Doesn't check to see that cmd is greater than 48 | // 127, or that data values are less than 127: 49 | void noteOn(int cmd, int pitch, int velocity) 50 | { 51 | Serial1.write(cmd); 52 | Serial1.write(pitch); 53 | Serial1.write(velocity); 54 | } 55 | 56 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Communication/SerialPassthrough/SerialPassthrough.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Multiple serial test 3 | 4 | Receives from Serial1, sends to Serial. 5 | 6 | The circuit: 7 | * Maple connected over Serial 8 | * Serial device (e.g. an Xbee radio, another Maple) 9 | 10 | created 30 Dec. 2008 11 | by Tom Igoe 12 | 13 | Ported to the Maple 27 May 2010 14 | by Bryan Newbold 15 | */ 16 | 17 | int inByte; // Byte read from Serial1 18 | 19 | void setup() 20 | { 21 | // Initialize Serial1 22 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 23 | Serial1.begin(115200); 24 | } 25 | 26 | void loop() 27 | { 28 | // Read from Serial1, send over USB on Maple (or uses hardware serial 1 and hardware serial 2 on non-maple boards: 29 | if (Serial1.available()) 30 | { 31 | inByte = Serial1.read(); 32 | Serial.write(inByte); 33 | } 34 | } 35 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Control/Arrays/Arrays.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Arrays 3 | 4 | Demonstrates the use of an array to hold pin numbers in order to 5 | iterate over the pins in a sequence. Lights multiple LEDs in 6 | sequence, then in reverse. 7 | 8 | Unlike the for loop tutorial, where the pins have to be 9 | contiguous, here the pins can be in any random order. 10 | 11 | The circuit: 12 | * LEDs from pins 2 through 7 to ground, through resistors 13 | 14 | created 2006 15 | by David A. Mellis 16 | modified 5 Jul 2009 17 | by Tom Igoe 18 | modifed for Maple 19 | by LeafLabs 20 | 21 | http://leaflabs.com/docs/lang/cpp/array.html 22 | */ 23 | 24 | int delayTime = 100; // The higher the number, the slower the timing. 25 | int ledPins[] = { 26 | 2, 7, 4, 6, 5, 3}; // An array of pin numbers to which LEDs are attached 27 | int pinCount = 6; // The number of pins (i.e. the length of the array) 28 | 29 | void setup() 30 | { 31 | int thisPin; 32 | // The array elements are numbered from 0 to (pinCount - 1). 33 | // Use a for loop to initialize each pin as an output: 34 | for (int thisPin = 0; thisPin < pinCount; thisPin++) 35 | { 36 | pinMode(ledPins[thisPin], OUTPUT); 37 | } 38 | } 39 | 40 | void loop() 41 | { 42 | // Loop from the lowest pin to the highest: 43 | for (int thisPin = 0; thisPin < pinCount; thisPin++) 44 | { 45 | // Turn the pin on: 46 | digitalWrite(ledPins[thisPin], HIGH); 47 | delay(delayTime); 48 | // Turn the pin off: 49 | digitalWrite(ledPins[thisPin], LOW); 50 | } 51 | 52 | // Loop from the highest pin to the lowest: 53 | for (int thisPin = pinCount - 1; thisPin >= 0; thisPin--) 54 | { 55 | // Turn the pin on: 56 | digitalWrite(ledPins[thisPin], HIGH); 57 | delay(delayTime); 58 | // Turn the pin off: 59 | digitalWrite(ledPins[thisPin], LOW); 60 | } 61 | } 62 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Control/ForLoopIteration/ForLoopIteration.ino: -------------------------------------------------------------------------------- 1 | /* 2 | for loop iteration 3 | 4 | Demonstrates the use of a for() loop. 5 | Lights multiple LEDs in sequence, then in reverse. 6 | 7 | The circuit: 8 | * LEDs from pins 2 through 7 to ground, through resistors 9 | 10 | created 2006 11 | by David A. Mellis 12 | modified 5 Jul 2009 13 | by Tom Igoe 14 | 15 | http://leaflabs.com/docs/lang/cpp/for.html 16 | 17 | Modified for Maple 18 | by LeafLabs 19 | */ 20 | 21 | int delayTime = 100; // The higher the number, the slower the timing. 22 | 23 | void setup() 24 | { 25 | // Use a for loop to initialize each pin as an output: 26 | for (int thisPin = 2; thisPin <= 7; thisPin++) 27 | { 28 | pinMode(thisPin, OUTPUT); 29 | } 30 | } 31 | 32 | void loop() 33 | { 34 | // Loop from the lowest pin to the highest: 35 | for (int thisPin = 2; thisPin <= 7; thisPin++) 36 | { 37 | // Turn the pin on: 38 | digitalWrite(thisPin, HIGH); 39 | delay(delayTime); 40 | // Turn the pin off: 41 | digitalWrite(thisPin, LOW); 42 | } 43 | 44 | // Loop from the highest pin to the lowest: 45 | for (int thisPin = 7; thisPin >= 2; thisPin--) 46 | { 47 | // Turn the pin on: 48 | digitalWrite(thisPin, HIGH); 49 | delay(delayTime); 50 | // Turn the pin off: 51 | digitalWrite(thisPin, LOW); 52 | } 53 | } 54 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Control/IfStatementConditional/IfStatementConditional.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Conditionals - If statement 3 | 4 | This example demonstrates the use of if() statements. It reads the 5 | state of a potentiometer (an analog input) and turns on an LED only 6 | if the LED goes above a certain threshold level. It prints the 7 | analog value regardless of the level. 8 | 9 | The circuit: 10 | * Potentiometer connected to pin 15. 11 | Center pin of the potentiometer goes to the Maple pin. 12 | Side pins of the potentiometer go to +3.3V and ground 13 | 14 | created 17 Jan 2009 15 | by Tom Igoe 16 | 17 | Ported to the Maple 27 May 2010 18 | by Bryan Newbold 19 | 20 | http://leaflabs.com/docs/lang/cpp/if.html 21 | */ 22 | 23 | // These constants won't change: 24 | 25 | const int analogPin = 15; // Pin that the sensor is attached to 26 | 27 | const int threshold = 400; // A random threshold level that's in 28 | // the range of the analog input 29 | 30 | void setup() 31 | { 32 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 33 | // Initialize the built-in LED pin as an output: 34 | pinMode(33, OUTPUT); 35 | 36 | // Initialize the potentiometer pin as an analog input: 37 | pinMode(analogPin, INPUT_ANALOG); 38 | } 39 | 40 | void loop() 41 | { 42 | // Read the value of the potentiometer: 43 | int analogValue = analogRead(analogPin); 44 | 45 | // If the analog value is high enough, turn on the LED: 46 | if (analogValue > threshold) 47 | { 48 | digitalWrite(33, HIGH); 49 | } else 50 | { 51 | digitalWrite(33, LOW); 52 | } 53 | 54 | // Print the analog value: 55 | Serial.println(analogValue, DEC); 56 | } 57 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Control/switchCase/switchCase.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Switch statement 3 | 4 | Demonstrates the use of a switch statement. The switch statement 5 | allows you to choose from among a set of discrete values of a 6 | variable. It's like a series of if statements. 7 | 8 | To see this sketch in action, but the board and sensor in a well-lit 9 | room, open the serial monitor, and and move your hand gradually down 10 | over the sensor. 11 | 12 | The circuit: 13 | * photoresistor from analog in 0 to +5V 14 | * 10K resistor from analog in 0 to ground 15 | 16 | created 1 Jul 2009 17 | by Tom Igoe 18 | 19 | Ported to the Maple 27 May 2010 20 | by Bryan Newbold 21 | 22 | http://leaflabs.com/docs/lang/cpp/switchcase.html 23 | */ 24 | 25 | // These constants won't change: 26 | const int sensorMin = 0; // sensor minimum, discovered through experiment 27 | const int sensorMax = 600; // sensor maximum, discovered through experiment 28 | 29 | void setup() 30 | { 31 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 32 | pinMode(0, INPUT_ANALOG); 33 | } 34 | 35 | void loop() 36 | { 37 | // Read the sensor: 38 | int sensorReading = analogRead(0); 39 | // Map the sensor range to a range of four options: 40 | int range = map(sensorReading, sensorMin, sensorMax, 0, 3); 41 | 42 | // Do something different depending on the range value: 43 | switch (range) 44 | { 45 | case 0: // your hand is on the sensor 46 | Serial.println("dark"); 47 | break; 48 | case 1: // your hand is close to the sensor 49 | Serial.println("dim"); 50 | break; 51 | case 2: // your hand is a few inches from the sensor 52 | Serial.println("medium"); 53 | break; 54 | case 3: // your hand is nowhere near the sensor 55 | Serial.println("bright"); 56 | break; 57 | } 58 | } 59 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Control/switchCase2/switchCase2.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Switch statement with serial input 3 | 4 | Demonstrates the use of a switch statement. The switch statement 5 | allows you to choose from among a set of discrete values of a 6 | variable. It's like a series of if statements. 7 | 8 | To see this sketch in action, open the Serial monitor and send any 9 | character. The characters a, b, c, d, and e, will turn on LEDs. 10 | Any other character will turn the LEDs off. 11 | 12 | The circuit: 13 | * 5 LEDs attached to pins 2 through 6 through 220-ohm resistors 14 | 15 | created 1 Jul 2009 16 | by Tom Igoe 17 | 18 | Ported to the Maple 27 May 2010 19 | by Bryan Newbold 20 | 21 | http://leaflabs.com/docs/lang/cpp/switchcase.html 22 | */ 23 | 24 | void setup() 25 | { 26 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 27 | // Initialize the LED pins: 28 | for (int thisPin = 2; thisPin <= 6; thisPin++) 29 | { 30 | pinMode(thisPin, OUTPUT); 31 | } 32 | } 33 | 34 | void loop() 35 | { 36 | // Read the sensor: 37 | if (Serial.available() > 0) 38 | { 39 | int inByte = Serial.read(); 40 | // Do something different depending on the character received. 41 | // The switch statement expects single number values for each 42 | // case; in this example, though, you're using single quotes 43 | // to tell the controller to get the ASCII value for the 44 | // character. For example 'a' = 97, 'b' = 98, and so forth: 45 | switch (inByte) 46 | { 47 | case 'a': 48 | digitalWrite(2, HIGH); 49 | break; 50 | case 'b': 51 | digitalWrite(3, HIGH); 52 | break; 53 | case 'c': 54 | digitalWrite(4, HIGH); 55 | break; 56 | case 'd': 57 | digitalWrite(5, HIGH); 58 | break; 59 | case 'e': 60 | digitalWrite(6, HIGH); 61 | break; 62 | default: 63 | // Turn all the LEDs off: 64 | for (int thisPin = 2; thisPin < 7; thisPin++) 65 | { 66 | digitalWrite(thisPin, LOW); 67 | } 68 | } 69 | } 70 | } 71 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Digital/Blink/Blink.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Blink 3 | Turns on an LED on for one second, then off for one second, repeatedly. 4 | 5 | Most Arduinos have an on-board LED you can control. On the Uno and 6 | Leonardo, it is attached to digital pin 13. If you're unsure what 7 | pin the on-board LED is connected to on your Arduino model, check 8 | the documentation at http://arduino.cc 9 | 10 | This example code is in the public domain. 11 | 12 | modified 8 May 2014 13 | by Scott Fitzgerald 14 | 15 | Modified by Roger Clark. www.rogerclark.net for Maple mini 25th April 2015 , where the LED is on PB1 16 | 17 | */ 18 | 19 | 20 | // the setup function runs once when you press reset or power the board 21 | void setup() 22 | { 23 | // initialize digital pin PB1 as an output. 24 | pinMode(PB1, OUTPUT); 25 | } 26 | 27 | // the loop function runs over and over again forever 28 | void loop() 29 | { 30 | digitalWrite(PB1, HIGH); // turn the LED on (HIGH is the voltage level) 31 | delay(1000); // wait for a second 32 | digitalWrite(PB1, LOW); // turn the LED off by making the voltage LOW 33 | delay(1000); // wait for a second 34 | } 35 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Digital/BlinkWithoutDelay/BlinkWithoutDelay.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Blink without delay 3 | 4 | Turns on and off the built-in light emitting diode (LED), without 5 | using the delay() function. This means that other code can run at 6 | the same time without being interrupted by the LED code. 7 | 8 | created 2005 9 | by David A. Mellis 10 | modified 17 Jun 2009 11 | by Tom Igoe 12 | modified for Maple 27 May 2011 13 | by Marti Bolivar 14 | */ 15 | 16 | // Variables: 17 | int previousMillis = 0; // will store the last time the LED was updated 18 | int interval = 1000; // interval at which to blink (in milliseconds) 19 | 20 | void setup() 21 | { 22 | // Set up the built-in LED pin as output: 23 | pinMode(33, OUTPUT); 24 | } 25 | 26 | void loop() 27 | { 28 | // Check to see if it's time to blink the LED; that is, if the 29 | // difference between the current time and last time we blinked 30 | // the LED is bigger than the interval at which we want to blink 31 | // the LED. 32 | if (millis() - previousMillis > interval) 33 | { 34 | // Save the last time you blinked the LED 35 | previousMillis = millis(); 36 | 37 | // If the LED is off, turn it on, and vice-versa: 38 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 39 | } 40 | } 41 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Digital/Button/Button.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Button 3 | 4 | Turns on and off the built-in LED when the built-in button is 5 | pressed. 6 | 7 | Ported to Maple from the Arduino example 27 May 2011 8 | by Marti Bolivar 9 | */ 10 | 11 | void setup() 12 | { 13 | // Initialize the built-in LED pin as an output: 14 | pinMode(33, OUTPUT); 15 | // Initialize the built-in button (labeled BUT) as an input: 16 | pinMode(BOARD_BUTTON_PIN, INPUT); 17 | } 18 | 19 | #define BUTTON_DEBOUNCE_DELAY 1 20 | 21 | uint8 isButtonPressed(uint8 pin = BOARD_BUTTON_PIN, 22 | uint32 pressedLevel = BOARD_BUTTON_PRESSED_LEVEL) 23 | { 24 | if (digitalRead(pin) == pressedLevel) 25 | { 26 | delay(BUTTON_DEBOUNCE_DELAY); 27 | while (digitalRead(pin) == pressedLevel); 28 | return true; 29 | } 30 | return false; 31 | } 32 | 33 | void loop() 34 | { 35 | // Check if the button is pressed. 36 | if (isButtonPressed()) 37 | { 38 | // If so, turn the LED from on to off, or from off to on: 39 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 40 | } 41 | } 42 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Digital/Debounce/Debounce.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Debounce 3 | 4 | Each time the input pin goes from LOW to HIGH (e.g. because of a push-button 5 | press), the output pin is toggled from LOW to HIGH or HIGH to LOW. There's 6 | a minimum delay between toggles to debounce the circuit (i.e. to ignore 7 | noise). 8 | 9 | created 21 November 2006 10 | by David A. Mellis 11 | modified 3 Jul 2009 12 | by Limor Fried 13 | modified 15 Jul 2010 14 | by Bryan Newbold; thanks adamfeuer! 15 | */ 16 | 17 | // Variables: 18 | int ledState = HIGH; // the current state of the output pin 19 | int buttonState; // the current reading from the input pin 20 | int lastButtonState = LOW; // the previous reading from the input pin 21 | int lastDebounceTime = 0; // the last time the output pin was toggled 22 | int debounceDelay = 50; // the debounce time; increase if the output flickers 23 | 24 | void setup() 25 | { 26 | pinMode(BOARD_BUTTON_PIN, INPUT); 27 | pinMode(33, OUTPUT); 28 | } 29 | 30 | void loop() 31 | { 32 | // read the state of the switch into a local variable: 33 | int reading = digitalRead(BOARD_BUTTON_PIN); 34 | 35 | // check to see if you just pressed the button 36 | // (i.e. the input went from LOW to HIGH), and you've waited 37 | // long enough since the last press to ignore any noise: 38 | 39 | // If the switch changed, due to noise or pressing: 40 | if (reading != lastButtonState) 41 | { 42 | // reset the debouncing timer 43 | lastDebounceTime = millis(); 44 | } 45 | 46 | if ((millis() - lastDebounceTime) > debounceDelay) 47 | { 48 | // whatever the reading is at, it's been there for longer 49 | // than the debounce delay, so take it as the actual current state: 50 | buttonState = reading; 51 | } 52 | 53 | // set the LED using the state of the button: 54 | digitalWrite(33, buttonState); 55 | 56 | // save the reading. Next time through the loop, 57 | // it'll be the lastButtonState: 58 | lastButtonState = reading; 59 | } 60 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Digital/MapleMorse/MapleMorse.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Blink 3 | 4 | Turns on the built-in LED on for one second, then off for one second, 5 | repeatedly. 6 | 7 | Ported to Maple from the Arduino example 27 May 2011 8 | By Marti Bolivar 9 | 10 | Updated for to remove definition for BOARD_LED_PIN by Roger Clark www.rogerclark.net 25th April 2015 11 | 12 | Note. This code only works on the Maple mini and other boards where the LED is on GPIO PB1 aka pin 33 on the Maple mini silk screen 13 | 14 | I could not resist making this a bit more interesting than the simple blinking on and off, as I expect most users of this hardware will understand how 15 | 16 | 17 | */ 18 | #define LED_PIN PB1 19 | #define TIMECONSTANT 100 20 | 21 | void setup() 22 | { 23 | // Set up the built-in LED pin as an output: 24 | pinMode(LED_PIN, OUTPUT); 25 | } 26 | 27 | void loop() 28 | { 29 | sendMorse("-- .- .--. .-.. . "); 30 | } 31 | 32 | void sendMorse(char *dotsAndDashes) 33 | { 34 | while (*dotsAndDashes != 0) 35 | { 36 | switch (*dotsAndDashes) 37 | { 38 | case '-': 39 | digitalWrite(LED_PIN, HIGH); 40 | delay(TIMECONSTANT * 3); 41 | digitalWrite(LED_PIN, LOW); 42 | delay(TIMECONSTANT); 43 | break; 44 | case '.': 45 | digitalWrite(LED_PIN, HIGH); 46 | delay(TIMECONSTANT); 47 | digitalWrite(LED_PIN, LOW); 48 | delay(TIMECONSTANT); 49 | break; 50 | case ' ': 51 | default: 52 | digitalWrite(LED_PIN, LOW); 53 | delay(TIMECONSTANT * 3); 54 | break; 55 | } 56 | dotsAndDashes++; 57 | } 58 | } 59 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Display/barGraph/barGraph.ino: -------------------------------------------------------------------------------- 1 | /* 2 | LED bar graph 3 | 4 | Turns on a series of LEDs based on the value of an analog sensor. 5 | This is a simple way to make a bar graph display. Though this graph 6 | uses 10 LEDs, you can use any number by changing the LED count and 7 | the pins in the array. 8 | 9 | This method can be used to control any series of digital outputs 10 | that depends on an analog input. 11 | 12 | The circuit: 13 | * LEDs from pins 2 through 11 to ground 14 | 15 | created 26 Jun 2009 16 | by Tom Igoe 17 | 18 | modified for Maple 19 | by LeafLabs 20 | 21 | http://www.arduino.cc/en/Tutorial/BarGraph 22 | */ 23 | 24 | // these constants won't change: 25 | const int analogPin = 0; // the pin that the potentiometer is attached to 26 | const int ledCount = 10; // the number of LEDs in the bar graph 27 | 28 | int ledPins[] = { 29 | 2, 3, 4, 5, 6, 7, 8, 9, 10, 11}; // an array of pin numbers to which LEDs are attached 30 | 31 | void setup() 32 | { 33 | // set up analogPin for analog input: 34 | pinMode(analogPin, INPUT_ANALOG); 35 | // loop over the pin array and set them all to output: 36 | for (int thisLed = 0; thisLed < ledCount; thisLed++) 37 | { 38 | pinMode(ledPins[thisLed], OUTPUT); 39 | } 40 | } 41 | 42 | void loop() 43 | { 44 | // read the potentiometer: 45 | int sensorReading = analogRead(analogPin); 46 | // map the result to a range from 0 to the number of LEDs: 47 | int ledLevel = map(sensorReading, 0, 4095, 0, ledCount); 48 | 49 | // loop over the LED array: 50 | for (int thisLed = 0; thisLed < ledCount; thisLed++) 51 | { 52 | // if the array element's index is less than ledLevel, 53 | // turn the pin for this element on: 54 | if (thisLed < ledLevel) 55 | { 56 | digitalWrite(ledPins[thisLed], HIGH); 57 | } 58 | // turn off all pins higher than the ledLevel: 59 | else 60 | { 61 | digitalWrite(ledPins[thisLed], LOW); 62 | } 63 | } 64 | } 65 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/Blink/Blink.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Blink: Turns on the built-in LED on for one second, then off for one second, repeatedly. 3 | Arduino 1.6.0rc1 4 | Sketch uses 11,900 bytes (11%) of program storage space. Maximum is 108,000 bytes. 5 | Global variables use 2,592 bytes of dynamic memory. 6 | Ported to Maple from the Arduino example 27 May 2011 By Marti Bolivar 7 | */ 8 | 9 | void setup() 10 | { 11 | // Set up the built-in LED pin as an output: 12 | pinMode(33, OUTPUT); 13 | } 14 | 15 | void loop() 16 | { 17 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 18 | delay(1000); // Wait for 1 second (1000 milliseconds) 19 | } 20 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/BlinkNcount/BlinkNcount.ino: -------------------------------------------------------------------------------- 1 | /* 2 | BlinkNcount for Maple Mini by m. ray burnette 3 | Sketch uses 13,808 bytes (12%) of program storage space. Maximum is 108,000 bytes. 4 | Global variables use 2,592 bytes of dynamic memory. 5 | Turns on an LED on for one second, then off for one second, repeatedly. 6 | Counts and displays the count on the attached serial monitor 7 | This example code is in the public domain. 8 | */ 9 | int n = 0; 10 | 11 | 12 | void setup() 13 | { 14 | // initialize the digital pin as an output. 15 | pinMode(LED_BUILTIN, OUTPUT); 16 | // Initialize virtual COM over USB on Maple Mini 17 | Serial.begin(9600); // BAUD has no effect on USB serial: placeholder for physical UART 18 | // wait for serial monitor to be connected. 19 | while (!Serial) 20 | { 21 | digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); // Turn the LED from off to on, or on to off 22 | delay(100); // fast blink 23 | } 24 | Serial.println("Blink LED & count Demo"); 25 | } 26 | 27 | void loop() 28 | { 29 | digitalWrite(LED_BUILTIN, HIGH); // set the LED on 30 | delay(500); // wait for a second 31 | digitalWrite(LED_BUILTIN, LOW); // set the LED off 32 | Serial.print("Loop #: "); 33 | n++; 34 | Serial.println(n); 35 | 36 | delay(500); // wait 37 | } 38 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/FadingOnboard/FadingOnboard.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Fading: This example shows how to fade an LED using the pwmWrite() function. 3 | 4 | Created 1 Nov 2008 5 | By David A. Mellis 6 | Modified 17 June 2009 7 | By Tom Igoe 8 | 9 | Modified by LeafLabs for Maple http://arduino.cc/en/Tutorial/Fading 10 | 11 | For differences between Maple's pwmWrite() and Arduino's analogWrite(): 12 | http://leaflabs.com/docs/lang/api/analogwrite.html 13 | */ 14 | 15 | // int ledPin = 9; // Connect an LED to digital pin 9, or any other 16 | // PWM-capable pin 17 | int ledPin = 33; 18 | 19 | void setup() 20 | { 21 | pinMode(ledPin, PWM); // setup the pin as PWM 22 | } 23 | 24 | void loop() 25 | { 26 | // Fade in from min to max in increments of 1280 points: 27 | for (int fadeValue = 0; fadeValue <= 65535; fadeValue += 1280) 28 | { 29 | // Sets the value (range from 0 to 65535): 30 | pwmWrite(ledPin, fadeValue); 31 | // Wait for 30 milliseconds to see the dimming effect: 32 | delay(30); 33 | } 34 | 35 | // Fade out from max to min in increments of 1280 points: 36 | for (int fadeValue = 65535; fadeValue >= 0; fadeValue -= 1280) 37 | { 38 | // Sets the value (range from 0 to 1280): 39 | pwmWrite(ledPin, fadeValue); 40 | // Wait for 30 milliseconds to see the dimming effect: 41 | delay(30); 42 | } 43 | } 44 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/IntegerInput/IntegerInput.ino: -------------------------------------------------------------------------------- 1 | /* 2 | IntegerInput by m. Ray Burnette - PUBLIC DOMAIN EXAMPLE 3 | Maple Mini: Compiled under Arduino 1.6.0rc1 4 | Sketch uses 15,624 bytes (14%) of program storage space. Maximum is 108,000 bytes. 5 | Global variables use 3,704 bytes of dynamic memory. 6 | */ 7 | 8 | #define BAUD 9600 9 | #define timeoutPeriod 2147483647 // Long time... about 25 days 10 | 11 | int a; 12 | int b; 13 | 14 | void setup() 15 | { 16 | // initialize the digital pin as an output. 17 | pinMode(33, OUTPUT); 18 | Serial.begin(BAUD); // BAUD has no effect on USB serial: placeholder for physical UART 19 | Serial.setTimeout(timeoutPeriod); // default is 1 second 20 | // wait for serial monitor to be connected. 21 | while (!Serial) 22 | { 23 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 24 | delay(100); // fast blink 25 | } 26 | } 27 | 28 | void loop() 29 | { 30 | Serial.println("Enter first integer: "); 31 | a = Serial.parseInt(); 32 | Serial.print("a = "); 33 | Serial.println(a); 34 | 35 | 36 | Serial.println("Enter second integer: "); 37 | b = Serial.parseInt(); 38 | Serial.print("b = "); 39 | Serial.println(b); 40 | 41 | Serial.print("Sum a + b ="); 42 | Serial.println(a + b); 43 | Serial.print("Dif a - b ="); 44 | Serial.println(a - b); 45 | } 46 | 47 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/IntegerInput_FloatOutput/IntegerInput_FloatOutput.ino: -------------------------------------------------------------------------------- 1 | /* 2 | IntegerInput_FloatOutput by m. Ray Burnette - PUBLIC DOMAIN EXAMPLE 3 | Maple Mini: Compiled under Arduino 1.6.0rc1 4 | Sketch uses 19,868 bytes (18%) of program storage space. Maximum is 108,000 bytes. 5 | Global variables use 3,704 bytes of dynamic memory. 6 | */ 7 | 8 | #define BAUD 9600 9 | #define timeoutPeriod 2147483647 // Long var... about 25 days 10 | 11 | float a; 12 | float b; 13 | 14 | 15 | void setup() 16 | { 17 | // initialize the digital pin as an output. 18 | pinMode(33, OUTPUT); 19 | Serial.begin(BAUD); // BAUD has no effect on USB serial: placeholder for physical UART 20 | Serial.setTimeout(timeoutPeriod); // default is 1 second 21 | // wait for serial monitor to be connected. 22 | while (!Serial) 23 | { 24 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 25 | delay(100); // fast blink 26 | } 27 | Serial.println("Integer Input - Floating Output"); 28 | Serial.println("You may wish to try 355 and 113 (Pi)"); 29 | } 30 | 31 | void loop() 32 | { 33 | Serial.println("Enter first integer: "); 34 | 35 | a = Serial.parseInt(); 36 | Serial.print("a = "); 37 | Serial.println(a); 38 | 39 | Serial.println("Enter second integer: "); 40 | 41 | b = Serial.parseInt(); 42 | Serial.print("b = "); 43 | Serial.println(b); 44 | 45 | a = a / b; 46 | Serial.print("a/b = "); 47 | Serial.println(a); 48 | Serial.println(); 49 | } 50 | 51 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/PrimeNos2/PrimeNos2.ino: -------------------------------------------------------------------------------- 1 | /* 2 | PrimeNos3: by Nick Gammon 3 | Maple Mini port m. ray burnette: Compiled under Arduino 1.6.0rc1 4 | Sketch uses 16,616 bytes (15%) of program storage space. Maximum is 108,000 bytes. 5 | Global variables use 2,624 bytes of dynamic memory. 6 | PUBLIC DOMAIN EXAMPLE 7 | */ 8 | 9 | #define BAUD 9600 10 | const int SHOW_EVERY = 500; // how often to echo a prime to the serial port 11 | int candidate; 12 | int found = 5; // Number we found 13 | int count = found - 1; 14 | 15 | 16 | void setup() 17 | { 18 | // initialize the digital pin as an output. 19 | pinMode(33, OUTPUT); 20 | Serial.begin(BAUD); // BAUD has no effect on USB serial: placeholder for physical UART 21 | // wait for serial monitor to be connected. 22 | while (!Serial) 23 | { 24 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 25 | delay(100); // fast blink 26 | } 27 | Serial.println("Prime Number Generator V2"); 28 | } 29 | 30 | void loop() 31 | { 32 | Serial.println("Prime numbers between 1 and 99999999 are:"); 33 | Serial.println("2 \t"); 34 | for (int i = 3; i < 99999999; i += 2) 35 | { 36 | // This loop stops either when j*j>i or when i is divisible by j. 37 | // The first condition means prime, the second, not prime. 38 | int j = 3; 39 | for (; j * j <= i && i % j != 0; j += 2); // No loop body 40 | 41 | if (j * j > i) Serial.print(i); 42 | Serial.print("\t"); 43 | } 44 | Serial.println("\r\n"); 45 | } 46 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/PrimeNos3/PrimeNos3.ino: -------------------------------------------------------------------------------- 1 | /* 2 | PrimeNos3: by Nick Gammon 3 | Maple Mini port m. ray burnette: Compiled under Arduino 1.6.0rc1 4 | Sketch uses 13,420 bytes (12%) of program storage space. Maximum is 108,000 bytes. 5 | Global variables use 2,600 bytes of dynamic memory. 6 | PUBLIC DOMAIN EXAMPLE 7 | */ 8 | 9 | #define BAUD 9600 10 | const int SHOW_EVERY = 500; // how often to echo a prime to the serial port 11 | int candidate; 12 | int found = 5; // Number we found 13 | int count = found - 1; 14 | 15 | 16 | void setup() 17 | { 18 | // initialize the digital pin as an output. 19 | pinMode(33, OUTPUT); 20 | Serial.begin(BAUD); // BAUD has no effect on USB serial: placeholder for physical UART 21 | // wait for serial monitor to be connected. 22 | while (!Serial) 23 | { 24 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 25 | delay(100); // fast blink 26 | } 27 | Serial.println("Prime Number Generator V2"); 28 | } 29 | 30 | void loop() 31 | { 32 | Serial.println("Prime numbers between 1 and 99999999 are:"); 33 | Serial.println("2 \t"); 34 | for (int i = 3; i < 99999999; i += 2) 35 | { 36 | // This loop stops either when j*j>i or when i is divisible by j. 37 | // The first condition means prime, the second, not prime. 38 | int j = 3; 39 | for (; j * j <= i && i % j != 0; j += 2); // No loop body 40 | 41 | if (j * j > i) Serial.print(i); 42 | Serial.print("\n\r"); 43 | } 44 | Serial.println("\r\n"); 45 | } 46 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/Print_Binary/Print_Binary.ino: -------------------------------------------------------------------------------- 1 | /* PRINT_BINARY - Arduino 1.6.0rc1 2 | Adapted to Maple Mini by m. ray burnette 3 | Sketch uses 11,672 bytes (10%) of program storage space. Maximum is 108,000 bytes. 4 | Global variables use 2,592 bytes of dynamic memory 5 | Prints a positive integer in binary format with a fixed withdth 6 | copyright, Peter H Anderson, Baltimore, MD, Nov, '07 7 | PUBLIC DOMAIN EXAMPLE 8 | */ 9 | 10 | #define BAUD 9600 11 | 12 | void setup() 13 | { 14 | // initialize the digital pin as an output. 15 | pinMode(33, OUTPUT); 16 | Serial.begin(BAUD); // BAUD has no effect on USB serial: placeholder for physical UART 17 | // wait for serial monitor to be connected. 18 | while (!Serial) 19 | { 20 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 21 | delay(100); // fast blink 22 | } 23 | Serial.println("Print Binary Format"); 24 | } 25 | 26 | void loop() 27 | { 28 | while (1) 29 | { 30 | print_binary(1024 + 256 + 63, 12); 31 | Serial.println(); 32 | delay(1000); 33 | 34 | } 35 | } 36 | 37 | void print_binary(int v, int num_places) 38 | { 39 | int mask = 0, n; 40 | 41 | for (n = 1; n <= num_places; n++) 42 | { 43 | mask = (mask << 1) | 0x0001; 44 | } 45 | v = v & mask; // truncate v to specified number of places 46 | 47 | while (num_places) 48 | { 49 | 50 | if (v & (0x0001 << num_places - 1)) 51 | { 52 | Serial.print("1"); 53 | } else 54 | { 55 | Serial.print("0"); 56 | } 57 | 58 | --num_places; 59 | if (((num_places % 4) == 0) && (num_places != 0)) 60 | { 61 | Serial.print("_"); 62 | } 63 | } 64 | } 65 | 66 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/Print_HEX/Print_HEX.ino: -------------------------------------------------------------------------------- 1 | /* 2 | PRINT_HEX - Arduino 1.6.0rc1 3 | Sketch uses 13,336 bytes (12%) of program storage space. Maximum is 108,000 bytes. 4 | Global variables use 2,592 bytes of dynamic memory. 5 | Adapted to the Maple Mini by m. ray burnette 6 | Illustrates how to display a hexadecimal number with a fixed width. 7 | opyright, Peter H Anderson, Baltimore, MD, Nov, '07 8 | PUBLIC DOMAIN EXAMPLE 9 | */ 10 | 11 | #define BAUD 9600 12 | 13 | void setup() // run once, when the sketch starts 14 | { 15 | // initialize the digital pin as an output. 16 | pinMode(33, OUTPUT); 17 | Serial.begin(BAUD); // BAUD has no effect on USB serial: placeholder for physical UART 18 | // wait for serial monitor to be connected. 19 | while (!Serial) 20 | { 21 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 22 | delay(100); // fast blink 23 | } 24 | Serial.println("Print HEX Format"); 25 | } 26 | 27 | void loop() 28 | { 29 | while (1) 30 | { 31 | print_hex(1024 + 256 + 63, 13); 32 | Serial.println(); 33 | delay(1000); 34 | 35 | } 36 | } 37 | 38 | void print_hex(int v, int num_places) 39 | { 40 | int mask = 0, n, num_nibbles, digit; 41 | 42 | for (n = 1; n <= num_places; n++) 43 | { 44 | mask = (mask << 1) | 0x0001; 45 | } 46 | v = v & mask; // truncate v to specified number of places 47 | 48 | num_nibbles = num_places / 4; 49 | if ((num_places % 4) != 0) 50 | { 51 | ++num_nibbles; 52 | } 53 | 54 | do 55 | { 56 | digit = ((v >> (num_nibbles - 1) * 4)) & 0x0f; 57 | Serial.print(digit, HEX); 58 | } while (--num_nibbles); 59 | 60 | } 61 | 62 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/SerialReadUntil/SerialReadUntil.ino: -------------------------------------------------------------------------------- 1 | 2 | // http://arduino.cc/forum/index.php?topic=114035.0 ` 3 | /* Sketch uses 13,836 bytes (12%) of program storage space. Maximum is 108,000 bytes. 4 | Global variables use 3,696 bytes of dynamic memory. 5 | Read an unknown length string of ASCII characters terminated 6 | with a line feed from the UART 7 | */ 8 | 9 | #define BAUD 9600 10 | 11 | void setup() 12 | { 13 | // initialize the digital pin as an output. 14 | pinMode(33, OUTPUT); 15 | Serial.begin(BAUD); // BAUD has no effect on USB serial: placeholder for physical UAR 16 | // wait for serial monitor to be connected. 17 | while (!Serial) 18 | { 19 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 20 | delay(100); // fast blink 21 | } 22 | Serial.println("Serial Read Until Example:"); 23 | Serial.print("Type a few characters & press ENTER\r\n(make certain serial monitor sends CR+LF)"); 24 | } 25 | 26 | void loop() 27 | { 28 | char serialdata[80]; 29 | int lf = 10; 30 | 31 | Serial.readBytesUntil(lf, serialdata, 80); 32 | 33 | Serial.println(serialdata); 34 | 35 | } 36 | 37 | 38 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/General/strtol_DecEquivalents/strtol_DecEquivalents.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Modified for Arduino from: http://www.cplusplus.com/reference/cstdlib/strtol/ 3 | Convert string to long integer: Maple Mini version by m. ray burnette: PUBLIC DOMAIN 4 | Sketch uses 13,924 bytes (12%) of program storage space. Maximum is 108,000 bytes. 5 | Global variables use 2,664 bytes of dynamic memory. 6 | Following C++ libs not needed after Arduino 1.0.2 7 | #include 8 | #include 9 | */ 10 | 11 | template 12 | inline Print &operator<<(Print &obj, T arg) 13 | { 14 | obj.print(arg); 15 | return obj; 16 | } 17 | 18 | char szNumbers[] = "2001 60c0c0 -1101110100110100100000 0x6fffff"; 19 | char *pEnd; 20 | long int li1, li2, li3, li4; 21 | 22 | void setup() 23 | { 24 | // initialize the digital pin as an output. 25 | pinMode(33, OUTPUT); 26 | Serial.begin(9600); 27 | // wait for serial monitor to be connected. 28 | while (!Serial) 29 | { 30 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 31 | delay(100); // fast blink 32 | } 33 | li1 = strtol(szNumbers, &pEnd, 10); // BASE 10 34 | li2 = strtol(pEnd, &pEnd, 16); // HEX 35 | li3 = strtol(pEnd, &pEnd, 2); // Binary 36 | li4 = strtol(pEnd, NULL, 0); // Integer constant with prefixed base Octal or Hex 37 | // Serial.print ("The decimal equivalents are: %ld, %ld, %ld and %ld.\n", li1, li2, li3, li4); 38 | Serial << "The decimal equivalents are: " << li1 << " " << li2 << " " << li3 << " " << li4; 39 | //return 0; 40 | } 41 | 42 | 43 | void loop() 44 | { 45 | // put your main code here, to run repeatedly: 46 | 47 | } 48 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Sensors/HardwareTimerOnePulseMode/HardwareTimerOnePulseMode.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Example of the Timer Input Capture mode combined with one pulse mode 3 | * 4 | * This example uses: 5 | * - Timer2 channel 1 as capture input 6 | * - Timer2 channel 2 to generate the pulses, 7 | * - Timer 3 to generate a PWM trigger signal for capture input 8 | */ 9 | 10 | #include 11 | 12 | const uint16_t pulseDelay = 200; 13 | const uint16_t pulseWidth = 200; 14 | 15 | //----------------------------------------------------------------------------- 16 | void toggle_led() 17 | { 18 | digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); 19 | } 20 | 21 | //----------------------------------------------------------------------------- 22 | void setup() 23 | { 24 | // setup PA1 (Timer2 channel 2) to PWM (one pulse mode) 25 | pinMode(PA1, PWM); 26 | // setup PA0 (Timer 2 channel 1) as input (capture input mode) 27 | pinMode(PA0, INPUT); 28 | 29 | // stop the timers before configuring them 30 | Timer2.pause(); 31 | 32 | Timer2.setPrescaleFactor(72); // 1 µs resolution 33 | Timer2.setCompare(TIMER_CH2, pulseDelay); 34 | Timer2.setOverflow(pulseWidth + pulseDelay - 1); 35 | 36 | // counter setup in one pulse mode, as slave triggered by TI1 37 | TIMER2_BASE->CR1 = (TIMER_CR1_OPM); // one pulse mode 38 | Timer2.setSlaveFlags(TIMER_SMCR_TS_TI1FP1 | TIMER_SMCR_SMS_TRIGGER); 39 | 40 | // channel 1: capture input on rising edge 41 | Timer2.setMode(TIMER_CH1, TIMER_INPUT_CAPTURE); 42 | //Timer2.setPolarity(TIMER_CH1, 1); // trigger on falling edge 43 | // channel 2: invert polarity (we want low for CNT= 1000) 66 | { 67 | t = millis(); 68 | toggle_led(); 69 | } 70 | } 71 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Sensors/Knock/Knock.ino: -------------------------------------------------------------------------------- 1 | /* 2 | Knock Sensor 3 | 4 | This sketch reads a piezo element to detect a knocking sound. It 5 | reads an analog pin and compares the result to a set threshold. If 6 | the result is greater than the threshold, it writes "knock" to the 7 | serial port, and toggles the LED on pin 13. 8 | 9 | The circuit: 10 | * + connection of the piezo attached to analog in 0 11 | * - connection of the piezo attached to ground 12 | * 1-megohm resistor attached from analog in 0 to ground 13 | 14 | http://www.arduino.cc/en/Tutorial/Knock 15 | 16 | created 25 Mar 2007 17 | by David Cuartielles 18 | modified 30 Jun 2009 19 | by Tom Igoe 20 | 21 | Ported to the Maple 22 | by LeafLabs 23 | */ 24 | 25 | // these constants won't change: 26 | const int knockSensor = 0; // the piezo is connected to analog pin 0 27 | const int threshold = 100; // threshold value to decide when the detected sound is a knock or not 28 | 29 | // these variables will change: 30 | int sensorReading = 0; // variable to store the value read from the sensor pin 31 | 32 | void setup() 33 | { 34 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 35 | // Declare the knockSensor as an analog input: 36 | pinMode(knockSensor, INPUT_ANALOG); 37 | // declare the built-in LED pin as an output: 38 | pinMode(33, OUTPUT); 39 | } 40 | 41 | void loop() 42 | { 43 | // read the sensor and store it in the variable sensorReading: 44 | sensorReading = analogRead(knockSensor); 45 | 46 | // if the sensor reading is greater than the threshold: 47 | if (sensorReading >= threshold) 48 | { 49 | // toggle the built-in LED 50 | digitalWrite(33, !digitalRead(33));// Turn the LED from off to on, or on to off 51 | // send the string "Knock!" back to the computer, followed by newline 52 | Serial.println("Knock!"); 53 | } 54 | delay(100); // delay to avoid printing too often 55 | } 56 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Stubs/AnalogReadPWMWrite/AnalogReadPWMWrite.ino: -------------------------------------------------------------------------------- 1 | void setup() 2 | { 3 | pinMode(2, INPUT_ANALOG); 4 | pinMode(6, PWM); 5 | } 6 | 7 | void loop() 8 | { 9 | int sensorValue = analogRead(2); 10 | int ledFadeValue = map(sensorValue, 0, 4095, 0, 65535); 11 | pwmWrite(6, ledFadeValue); 12 | } 13 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Stubs/AnalogReadSerial/AnalogReadSerial.ino: -------------------------------------------------------------------------------- 1 | void setup() 2 | { 3 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 4 | pinMode(0, INPUT_ANALOG); 5 | } 6 | 7 | void loop() 8 | { 9 | int sensorValue = analogRead(0); 10 | Serial.println(sensorValue, DEC); 11 | } 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Stubs/BareMinumum/BareMinumum.ino: -------------------------------------------------------------------------------- 1 | void setup() 2 | { 3 | 4 | } 5 | 6 | void loop() 7 | { 8 | 9 | } 10 | 11 | 12 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Stubs/DigitalReadSerial/DigitalReadSerial.ino: -------------------------------------------------------------------------------- 1 | void setup() 2 | { 3 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 4 | pinMode(2, INPUT); 5 | } 6 | 7 | void loop() 8 | { 9 | int sensorValue = digitalRead(2); 10 | Serial.println(sensorValue, DEC); 11 | } 12 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Stubs/DigitalReadWrite/DigitalReadWrite.ino: -------------------------------------------------------------------------------- 1 | 2 | void setup() 3 | { 4 | pinMode(33, OUTPUT); 5 | } 6 | 7 | void loop() 8 | { 9 | int switchValue = digitalRead(2); 10 | digitalWrite(33, switchValue); 11 | } 12 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/examples/Stubs/HelloWorld/HelloWorld.ino: -------------------------------------------------------------------------------- 1 | void setup() 2 | { 3 | Serial.begin(115200); // Ignored by Maple. But needed by boards using hardware serial via a USB to Serial adaptor 4 | } 5 | 6 | void loop() 7 | { 8 | Serial.println("Hello World!"); 9 | delay(1000); 10 | } 11 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/keywords.txt: -------------------------------------------------------------------------------- 1 | ####################################### 2 | # Syntax Coloring Map 3 | ####################################### 4 | 5 | ####################################### 6 | # Datatypes (KEYWORD1) 7 | ####################################### 8 | 9 | ####################################### 10 | # Constants (LITERAL1) 11 | ####################################### 12 | 13 | OUTPUT_OPEN_DRAIN LITERAL1 14 | INPUT_ANALOG LITERAL1 15 | INPUT_PULLDOWN LITERAL1 16 | PWM LITERAL1 -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/lib/STM32_Examples/library.properties: -------------------------------------------------------------------------------- 1 | name=A_STM32_Examples 2 | version=1.0 3 | author=Various 4 | email= 5 | sentence=STM32 examples 6 | paragraph=STM32 examples 7 | url=www.stm32duino.com 8 | architectures=STM32F1 9 | maintainer= 10 | category=Uncategorized 11 | -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/platformio.ini: -------------------------------------------------------------------------------- 1 | ; PlatformIO Project Configuration File 2 | ; 3 | ; Build options: build flags, source filter 4 | ; Upload options: custom upload port, speed and extra flags 5 | ; Library options: dependencies, extra library storages 6 | ; Advanced options: extra scripting 7 | ; 8 | ; Please visit documentation for the other options and examples 9 | ; https://docs.platformio.org/page/projectconf.html 10 | 11 | [env:genericSTM32F103CB] 12 | platform = ststm32 13 | board = genericSTM32F103CB 14 | framework = arduino 15 | 16 | upload_protocol = stlink 17 | debug_tool = stlink 18 | upload_flags = -c set CPUTAPID 0x2ba01477 -------------------------------------------------------------------------------- /2.Firmware/SimpleFOC_version/Ctrl-FOC-Lite-fw/test/README: -------------------------------------------------------------------------------- 1 | 2 | This directory is intended for PlatformIO Unit Testing and project tests. 3 | 4 | Unit Testing is a software testing method by which individual units of 5 | source code, sets of one or more MCU program modules together with associated 6 | control data, usage procedures, and operating procedures, are tested to 7 | determine whether they are fit for use. Unit testing finds problems early 8 | in the development cycle. 9 | 10 | More information about PlatformIO Unit Testing: 11 | - https://docs.platformio.org/page/plus/unit-testing.html 12 | -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/AS5047P-Datasheet.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/AS5047P-Datasheet.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/MT6816_Rev.1.3.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/MT6816_Rev.1.3.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/Connectors.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/Connectors.SchDoc -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MB1136.PcbDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MB1136.PcbDoc -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MB1136.SCHLIB: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MB1136.SCHLIB -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MB1136.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MB1136.SchDoc -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MB1136.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MB1136.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MCU_64.SchDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/MCU_64.SchDoc -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/Nucleo_64_mechanic_revC.PcbDoc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/Nucleo_64_mechanic_revC.PcbDoc -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/ST_LINK_V2-1.SCHDOC: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/MB1136C_schematic_layout/ST_LINK_V2-1.SCHDOC -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/PinMap1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/PinMap1.png -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/PinMap2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/PinMap2.png -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/STM32 Nucleo/STM32 Nucleo-64 boards.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/STM32 Nucleo/STM32 Nucleo-64 boards.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/drv8301.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/drv8301.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/drv8302.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/drv8302.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/drv8313.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/drv8313.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/ina240.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/ina240.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/me3116.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/me3116.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/stm32f103cb.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/stm32f103cb.pdf -------------------------------------------------------------------------------- /4.Docs/1.Datasheets/tl431.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/1.Datasheets/tl431.pdf -------------------------------------------------------------------------------- /4.Docs/2.Images/img1.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/2.Images/img1.jpg -------------------------------------------------------------------------------- /4.Docs/2.Images/img2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/2.Images/img2.jpg -------------------------------------------------------------------------------- /4.Docs/2.Images/img3.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/peng-zhihui/Ctrl-FOC-Lite/a57dd3b2c3262d97789361c05a2ef86ba6ff8d73/4.Docs/2.Images/img3.jpg -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Ctrl-FOC-Lite评估套件 2 | 3 | 基于[SimpleFOC](https://github.com/simplefoc/Arduino-SimpleFOCShield)的一个修改版项目,官方版本基本都是基于Arduino相关板卡开发(也有基于STM32的,但是都是使用Arduino上层库浪费了很多硬件性能,比如硬件编码器接口、DMA、CAN等),所以本仓库准备在STM32的HAL固件库中移植SimpleFOC固件,同时加入FreeRTOS的支持。 4 | 5 | ![](/4.Docs/2.Images/img1.jpg) 6 | 7 | ![](/4.Docs/2.Images/img3.jpg) 8 | 9 | 硬件设计已经完成并且打样验证过了,使用的是STM32F1系列,后续可以基于本方案轻松扩展到F4等其他系列(因为HAL库很方便移植),并且扩展到多通道(只要硬件定时器够用),扩展到大功率方案(DRV8302+大功率MOS)。本评估板中引出了所有IO资源,相关资源分配可以参考`.ioc`文件: 10 | 11 | ![](/4.Docs/2.Images/img2.jpg) 12 | 13 | 固件使用CLion开发编译,不熟悉的同学可以参考这篇文章: 14 | 15 | [配置CLion用于STM32开发](https://www.zhihu.com/people/zhi-hui-64-54/posts) --------------------------------------------------------------------------------