├── .gitattributes ├── .gitignore ├── LICENSE.txt ├── README.md ├── build ├── buildcnt.pl └── linker_cmd.ld ├── doc ├── block_diagram.pdf └── setup_notes.txt ├── makefile └── src ├── CMSIS ├── ARMCM4.h ├── ARMCM4_FP.h ├── arm_common_tables.c ├── arm_common_tables.h ├── arm_cos_f32.c ├── arm_math.h ├── arm_sin_f32.c ├── cmsis_compiler.h ├── cmsis_gcc.h ├── cmsis_version.h ├── core_cm4.h ├── mpu_armv7.h └── system_ARMCM4.h ├── free_rtos_source ├── croutine.c ├── event_groups.c ├── heap_1.c ├── include │ ├── FreeRTOS.h │ ├── StackMacros.h │ ├── atomic.h │ ├── croutine.h │ ├── deprecated_definitions.h │ ├── event_groups.h │ ├── list.h │ ├── message_buffer.h │ ├── mpu_prototypes.h │ ├── mpu_wrappers.h │ ├── portable.h │ ├── projdefs.h │ ├── queue.h │ ├── semphr.h │ ├── stack_macros.h │ ├── stdint.readme │ ├── stream_buffer.h │ ├── task.h │ └── timers.h ├── list.c ├── portable │ └── GCC │ │ └── ARM_CM4F │ │ ├── port.c │ │ └── portmacro.h ├── queue.c ├── readme.txt ├── stream_buffer.c ├── tasks.c └── timers.c ├── hw_io ├── adc_conversions.cpp ├── adc_conversions.h ├── adc_interface.cpp ├── adc_interface.h ├── dac_interface.cpp ├── dac_interface.h ├── gpio_interface.cpp ├── gpio_interface.h ├── hw_definitions.h ├── i2c_interface.cpp ├── i2c_interface.h ├── physical_inputs.cpp ├── physical_inputs.h ├── pwm_interface.cpp ├── pwm_interface.h ├── tick_timers.cpp ├── tick_timers.h ├── uart_interface.cpp └── uart_interface.h ├── main ├── FreeRTOSConfig.h ├── background_task.cpp ├── background_task.h ├── buildcnt.cpp ├── c_startup.cpp ├── config.h ├── data_logger.cpp ├── data_logger.h ├── global_constants.h ├── global_definitions.h ├── main.cpp ├── os_interface.cpp ├── os_interface.h └── startup_stm32f429xx.s ├── motor_drive ├── angle_estimator_coefficients.h ├── loop_coefficients.h ├── motor_angle_n_speed.cpp ├── motor_angle_n_speed.h ├── motor_constants.h ├── motor_controller.cpp ├── motor_controller.h ├── motor_state_machine.cpp ├── motor_state_machine.h ├── motor_transforms.cpp ├── motor_transforms.h ├── pi_controller.cpp ├── pi_controller.h ├── pll_angle_est.cpp ├── pll_angle_est.h ├── smo_angle_est.cpp ├── smo_angle_est.h ├── zero_sequence_modulator.cpp └── zero_sequence_modulator.h ├── processor_specific ├── STM32F4xx_HAL_Driver │ ├── stm32f4xx_hal.h │ ├── stm32f4xx_hal_conf.h │ ├── stm32f4xx_hal_def.h │ ├── stm32f4xx_ll_adc.c │ ├── stm32f4xx_ll_adc.h │ ├── stm32f4xx_ll_bus.h │ ├── stm32f4xx_ll_cortex.h │ ├── stm32f4xx_ll_crc.c │ ├── stm32f4xx_ll_crc.h │ ├── stm32f4xx_ll_dac.c │ ├── stm32f4xx_ll_dac.h │ ├── stm32f4xx_ll_dma.c │ ├── stm32f4xx_ll_dma.h │ ├── stm32f4xx_ll_dma2d.c │ ├── stm32f4xx_ll_dma2d.h │ ├── stm32f4xx_ll_exti.c │ ├── stm32f4xx_ll_exti.h │ ├── stm32f4xx_ll_fmc.c │ ├── stm32f4xx_ll_fmc.h │ ├── stm32f4xx_ll_fmpi2c.c │ ├── stm32f4xx_ll_fmpi2c.h │ ├── stm32f4xx_ll_fsmc.c │ ├── stm32f4xx_ll_fsmc.h │ ├── stm32f4xx_ll_gpio.c │ ├── stm32f4xx_ll_gpio.h │ ├── stm32f4xx_ll_i2c.c │ ├── stm32f4xx_ll_i2c.h │ ├── stm32f4xx_ll_iwdg.h │ ├── stm32f4xx_ll_lptim.c │ ├── stm32f4xx_ll_lptim.h │ ├── stm32f4xx_ll_pwr.c │ ├── stm32f4xx_ll_pwr.h │ ├── stm32f4xx_ll_rcc.c │ ├── stm32f4xx_ll_rcc.h │ ├── stm32f4xx_ll_rng.c │ ├── stm32f4xx_ll_rng.h │ ├── stm32f4xx_ll_rtc.c │ ├── stm32f4xx_ll_rtc.h │ ├── stm32f4xx_ll_sdmmc.c │ ├── stm32f4xx_ll_sdmmc.h │ ├── stm32f4xx_ll_spi.c │ ├── stm32f4xx_ll_spi.h │ ├── stm32f4xx_ll_system.h │ ├── stm32f4xx_ll_tim.c │ ├── stm32f4xx_ll_tim.h │ ├── stm32f4xx_ll_usart.c │ ├── stm32f4xx_ll_usart.h │ ├── stm32f4xx_ll_usb.c │ ├── stm32f4xx_ll_usb.h │ ├── stm32f4xx_ll_utils.c │ ├── stm32f4xx_ll_utils.h │ └── stm32f4xx_ll_wwdg.h ├── processor.h ├── stm32f429xx.h ├── stm32f4xx.h ├── system_stm32f4xx.c └── system_stm32f4xx.h └── util ├── debouncer.cpp ├── debouncer.h ├── low_pass_filter.cpp ├── low_pass_filter.h ├── math_util.h └── newlib_functions.cpp /.gitattributes: -------------------------------------------------------------------------------- 1 | src/free_rtos_source/* linguist-vendored 2 | src/processor_specific/* linguist-vendored 3 | src/CMSIS/* linguist-vendored 4 | 5 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Ignore all build output 2 | build/depend/ 3 | build/obj/ 4 | build/motor_drive_image/ 5 | 6 | # Ignore Eclipse files 7 | .cproject 8 | .project 9 | .settings/ 10 | 11 | # Ignore MACOS files 12 | .DS_Store 13 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ## Yet Another Motor Drive 2 | Field-oriented control motor drive software for 3-phase permanent magnet 3 | synchronous motors that supports both sensored and sensor-less operation. 4 | 5 | ### Overview 6 | This project contains the software that implements the field-oriented control 7 | (FOC) of a 3-phase permanent magnet synchronous motor (PMSM). Support is 8 | included for controlling the motor either using a physical shaft encoder 9 | ("sensors") or by estimating the motor's shaft angle using other sensed data 10 | ("sensor-less"). 11 | 12 | At present, this software is configured to operate on an STMicro STM32F439 processor. 13 | The supported motor is a Segway I Series PT motor (these can be found on eBay). 14 | The gate drive and power electronics are provide by a Texas Instruments DRV8312EVM 15 | evaluation module (note that the DRV8312 is utilized without a processor installed). 16 | The motor bus is operated nominally at 24.5 volts. A combination of a power supply 17 | and batteries are used to provide the motor bus power. 18 | 19 | Please see the block diagram and setup notes in the documentation folder for more 20 | information about the setup's configuration. 21 | 22 | ### Why Yet Another Motor Drive? 23 | There are many fine motor drive software examples available. Many of the available 24 | examples, however, target very specific low-cost lower capability processors. 25 | As a result, the software must often be coded in such a way to fit within the 26 | constraints of the target processor. These software examples are often marvels 27 | of efficiency but they can often be rather difficult to follow. 28 | 29 | This motor drive project is targeted to a processor that is rather more capable 30 | than the processors often used to control PMSM motors. The software can take 31 | advantage of this extra capability to concentrate on the PMSM FOC algorithms 32 | themselves without having to add the extra complexity required to fit within a 33 | smaller processor's footprint. As a result, the motor control portion of this 34 | software: 35 | * Is not highly optimized for speed or size 36 | * Performs most of its calculations in floating point 37 | * Uses engineering units for most values. For example, bus voltage is expressed 38 | in volts with 1.0 volt being represented by the value 1.0 39 | * Where possible, processor specific items are reserved for the low level 40 | hardware interfaces and are not present in the motor control algorithms 41 | themselves 42 | 43 | ### Status and Future Updates 44 | At present, this software controls a single target motor using either a motor 45 | shaft angle sensed with an analog encoder or an estimated shaft angle computed 46 | using one of two available algorithms. Up to this time all testing and loop tuning 47 | has performed with the motor operating without a load. Data logging is 48 | supported with a basic serial console and a high speed DAC output. 49 | 50 | Planned updates include: 51 | * Verifying and improving performance with the motor under load 52 | * Adding support for a more commonly available motor (for example the Anaheim 53 | Automation motor included with the TI DRV8312EVM kit) 54 | * Improving the external data logging and motor control tools 55 | * More fully documenting the setup and its operation 56 | -------------------------------------------------------------------------------- /build/buildcnt.pl: -------------------------------------------------------------------------------- 1 | #!c:/perl/bin/perl.exe 2 | 3 | my $buildcount = 0; 4 | 5 | open my $ifp,"<./src/main/buildcnt.cpp"; 6 | while (<$ifp>) { 7 | if ($_ =~ m/buildCount\s*=\s*(\d+);/) { 8 | $buildcount = int($1); 9 | } 10 | } 11 | close $ifp; 12 | 13 | $buildcount++; 14 | 15 | open my $ofp,">./src/main/buildcnt.cpp"; 16 | printf $ofp ("// buildcnt.cpp\n"); 17 | printf $ofp ("// Auto Generated\n"); 18 | printf $ofp ("volatile int buildCount = %d;\n", $buildcount); 19 | printf $ofp ("volatile char absoluteBuildTime[] = __TIMESTAMP__;\n", $buildcount); 20 | 21 | close $ofp; 22 | 23 | print "New build count: $buildcount\n"; 24 | -------------------------------------------------------------------------------- /build/linker_cmd.ld: -------------------------------------------------------------------------------- 1 | 2 | /** 3 | * 4 | * The Linker Command File directs the linker where to allocate the various 5 | * items that make up the application in the processor's memories. This 6 | * includes the flash memory that contains the application software and the 7 | * RAM memory used by the application as it executes. 8 | */ 9 | 10 | /* 11 | * We bring in the core C libraries. 12 | */ 13 | GROUP(libgcc.a libc.a) 14 | 15 | /* 16 | * This is the basic memory layout. 17 | */ 18 | MEMORY 19 | { 20 | FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 2048K 21 | SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 192K 22 | CCMRAM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K 23 | } 24 | 25 | 26 | /* 27 | * This symbol is used to initialize the system stack at start-up. 28 | */ 29 | _estack = ORIGIN(CCMRAM) + LENGTH(CCMRAM); 30 | 31 | /* 32 | * This is the where execution starts at reset. 33 | */ 34 | ENTRY(Reset_Handler) 35 | 36 | SECTIONS 37 | { 38 | 39 | ISRvectors : ALIGN(0x10) 40 | { 41 | _vector_table_start = .; 42 | KEEP(*(.isr_vector)) 43 | _vector_table_end = .; 44 | } > FLASH 45 | 46 | .text : ALIGN(0x10) 47 | { 48 | /* 49 | * This is the bulk of the application executable. 50 | */ 51 | *(.text .text.* .text* .gnu.linkonce.t.*) 52 | 53 | /* 54 | * The next group of sections are generated by the tool-chain when it 55 | * builds the application. These are largely derived from provided 56 | * examples. 57 | */ 58 | *(.rodata .rodata.* .gnu.linkonce.r.*) 59 | *(.glue_7) /* glue arm to thumb code */ 60 | *(.glue_7t) /* glue thumb to arm code */ 61 | *(.eh_frame) 62 | KEEP (*(.init)) 63 | KEEP (*(.fini)) 64 | . = ALIGN(4); 65 | } > FLASH 66 | 67 | /* 68 | * for exception handling/unwind - some Newlib functions (in common with 69 | * C++ and STDC++) use this. 70 | */ 71 | .ARM.extab : 72 | { 73 | *(.ARM.extab* .gnu.linkonce.armextab.*) 74 | } > FLASH 75 | 76 | __exidx_start = .; 77 | .ARM.exidx : 78 | { 79 | *(.ARM.exidx* .gnu.linkonce.armexidx.*) 80 | } > FLASH 81 | __exidx_end = .; 82 | 83 | .preinit_array : 84 | { 85 | PROVIDE_HIDDEN (__preinit_array_start = .); 86 | KEEP (*(.preinit_array*)) 87 | PROVIDE_HIDDEN (__preinit_array_end = .); 88 | } >FLASH 89 | 90 | .init_array : 91 | { 92 | PROVIDE_HIDDEN (__init_array_start = .); 93 | KEEP (*(SORT(.init_array.*))) 94 | KEEP (*(.init_array*)) 95 | PROVIDE_HIDDEN (__init_array_end = .); 96 | } > FLASH 97 | 98 | .fini_array : 99 | { 100 | PROVIDE_HIDDEN (__fini_array_start = .); 101 | KEEP (*(.fini_array*)) 102 | KEEP (*(SORT(.fini_array.*))) 103 | PROVIDE_HIDDEN (__fini_array_end = .); 104 | } > FLASH 105 | 106 | /* 107 | * This is the end of flash memory used for code storage. 108 | */ 109 | _endText = .; 110 | 111 | /* 112 | * The data segment stores all items that are initialized to non-zero 113 | * value in their definitions. 114 | */ 115 | .data : ALIGN(0x10) 116 | { 117 | _dataFlashStart = LOADADDR(.data); 118 | _dataRAMStart = ADDR(.data); 119 | 120 | *(.data .data* .data.* .gnu.linkonce.d.*) 121 | KEEP(*(.jcr)) 122 | *(.jcr) 123 | *(.igot.plt) 124 | *(.shdata) 125 | _dataRAMEnd = ALIGN(0x10); 126 | } > SRAM AT > FLASH 127 | 128 | .dma_memory (NOLOAD): ALIGN(0x10) 129 | { 130 | /* 131 | * This segment is used to buffer memory that is accessed by 132 | * the DMA controller. It must be in SRAM as the DMA cannot 133 | * access the CCMRAM. 134 | */ 135 | } AT > SRAM 136 | 137 | /* 138 | * The bss segment stores all items that are assumed to be initialized to 139 | * zero at startup. 140 | */ 141 | .bss : ALIGN(0x10) 142 | { 143 | _bssStart = .; 144 | *(.shbss) 145 | *(.bss .bss* .bss.* .gnu.linkonce.b.*) 146 | *(COMMON) 147 | . = ALIGN(0x10); 148 | _bssEnd = .; 149 | } > SRAM 150 | 151 | /* 152 | * We put the heap and our stacks in the second ram. 153 | */ 154 | _mallocHeapSize = 2K; 155 | _minStackSize = 2K; 156 | 157 | .rtos_heap (NOLOAD): ALIGN(0x10) 158 | { 159 | /* 160 | * We define the heap used by the RTOS. We support memory allocation 161 | * but not memory freeing. 162 | */ 163 | } AT > CCMRAM 164 | 165 | .taskqueues (NOLOAD): ALIGN(0x10) 166 | { 167 | /* 168 | * The memory for each task's message queues is linked here. 169 | */ 170 | *(_taskQueues*) 171 | } AT > CCMRAM 172 | 173 | .taskstacks (NOLOAD): ALIGN(0x10) 174 | { 175 | /* 176 | * Memory for each task's stack is linked here. 177 | */ 178 | *(_taskStacks*) 179 | } AT > CCMRAM 180 | 181 | .the_heap (NOLOAD): ALIGN(0x10) 182 | { 183 | /* 184 | * We define a small heap for malloc. We don't really expect it to be 185 | * used much. In our application memory is only taken, it 186 | * is never returned. 187 | */ 188 | _heap_start = .; 189 | . = _mallocHeapSize; 190 | _heap_end = .; 191 | } AT > CCMRAM 192 | 193 | .the_stack (NOLOAD): ALIGN(0x10) 194 | { 195 | /* 196 | * We define a stack section even though it is not used. This really 197 | * exists to trap a case where we are running out of memory. 198 | */ 199 | . = _minStackSize; 200 | } AT > CCMRAM 201 | } 202 | -------------------------------------------------------------------------------- /doc/block_diagram.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/0x2152Yet/yet_another_motor_drive/257290d5e7559d50ed5bcd64b6ed36717b38edd6/doc/block_diagram.pdf -------------------------------------------------------------------------------- /doc/setup_notes.txt: -------------------------------------------------------------------------------- 1 | At present, the setup consists of the following: 2 | 1 Segway PT I series motor: The motor 3 | 1 STM32F439 Nucleo 144 processor board: The processor 4 | 1 TI DRV8312EVM (Rev. D): Bridge driver and power electronics (no 5 | control card installed) 6 | 1 MIKROE-3299 Knob G click: Quadrature encoded knob for speed command input 7 | 1 EXTECH 283313 power supply: Set at 24.5V, 0.4A. Provides power for drive 8 | electronics and charging batteries 9 | 2 Duracell Dura12-7F AGM lead acid batteries: Power drive electronics and 10 | absorb regen. 11 | 1 Custom motor adapter board: energize motor relays, power motor hall sensors 12 | and convert hall sensor signals to 0V..3.3V range 13 | 14 | The following tools were used for the software development 15 | Developed under MacOS. The MacOS supplied perl and make utility are required 16 | for the build 17 | Compiled with gcc version 9.3.1 20200408 (release) (GNU Arm Embedded 18 | Toolchain 9-2020-q2-update) 19 | Software developed with the Eclipse Embedded CDT (C/C++ Development Tools) IDE 20 | Nucleo on-board STLink updated to Segger J-Link compatibility with the 21 | Segger STLinkReflash utility 22 | JTAG connection to Nucleo processor provided via the Segger J-Link software 23 | and GDB server 24 | 25 | Board setup for STM 32F439 Nucleo 144 26 | Remove solder bridges: 13, 160, 164, 178, 181, 183 27 | Add pins to CN11: 28 | pin 9 (PF6) 29 | pin 31 (PB7) 30 | pin 30 (PA1) 31 | pin 36 (PC1) 32 | Add pins to CN12: 33 | pin 28 (PB14) 34 | pin 35 (PA2) 35 | 36 | ADC channels: 37 | Phase voltage A: ADC CH0 (Nucleo PA0, CN10 pin 29) connect to (DRV8312EVM J5, Pin 36) 38 | Phase voltage B: ADC CH1 (Nucleo PA1, CN11 pin 30) connect to (DRV8312EVM J5, Pin 34) 39 | Phase voltage C: ADC CH4 (Nucleo PF6, CN11 pin 9) connect to (DRV8312EVM J5, Pin 31) 40 | 41 | Phase current A: ADC CH2 (Nucleo PA2, CN12 pin 35) connect to (DRV8312EVM J5, Pin 37) 42 | Phase current B: ADC CH3 (Nucleo PA3, CN9 pin 1) connect to (DRV8312EVM J5, Pin 35) 43 | Phase current C: ADC CH5 (Nucleo PF7, CN9 pin 26) connect to (DRV8312EVM J5, Pin 32) 44 | 45 | Motor Hall A: ADC CH10 (Nucleo PC0, CN9 pin3) connect to (Adapter board, 3.3V Hall 1) 46 | Motor Hall B: ADC CH11 (Nucleo PC1, CN11 pin36) connect to (Adapter board, 3.3V Hall 2) 47 | Motor Hall C: ADC CH6 (Nucleo PF8, CN9 pin 24) connect to (Adapter board, 3.3V Hall 3) 48 | 49 | VBus: ADC CH12 (Nucleo PC2, CN10 pin9) connect to (DRV8312EVM J5, Pin 33) 50 | IBus: ADC CH13 (Nucleo PC3, CN9 pin5) connect to (DRV8312EVM J5, Pin 29) 51 | 52 | DAC outputs 53 | DAC 1: (Nucleo PA4, CN7 pin 17) connect to scope 54 | DAC 2: (Nucleo PA5, CN7 pin 10) connect to scope 55 | 56 | External ADC Trigger (when snooping EVM) 57 | (Nucleo PC11, CN8 pin 8) connect to (DRV8312EVM J5, Pin 24) 58 | 59 | Bridge Enables 60 | ENA: (Nucleo PD14, CN7 pin 16) connect to (DRV8312EVM J5, Pin 6) 61 | ENB: (Nucleo PD15, CN7 pin 18) connect to (DRV8312EVM J5, Pin 9) 62 | ENC: (Nucleo PF12, CN7 pin 20) connect to (DRV8312EVM J5, Pin 12) 63 | 64 | PWM Outputs 65 | PWM A: (Nucleo PE9, CN10 pin 4) connect to (DRV8312EVM J5, Pin 26) 66 | PWM B: (Nucleo PE11, CN10 pin 6) connect to (DRV8312EVM J5, Pin 25) 67 | PWM C: (Nucleo PE13, CN10 pin 10) connect to (DRV8312EVM J5, Pin 28) 68 | 69 | Speed Command Encoder and button 70 | Encoder A output: (Nucleo PC6, CN7 pin1) connect to (MIKROE-3299 ENCA) 71 | Encoder B output: (Nucleo PC8, CN7 pin11) connect to (MIKROE-3299 ENCB) 72 | Encoder push button: (Nucleo PB11, CN10 pin34) connect to (MIKROE-3299 SW) 73 | Power for encoder: (Nucleo CN8 pin7) connect to (MIKROE-3299 3.3V) 74 | Ground for encoder: (Nucleo CN8 pin11) connect to (MIKROE-3299 GND) 75 | 76 | Others 77 | Timing LED: (Nucleo PB7, CN11 pin 21) connect to scope 78 | 79 | -------------------------------------------------------------------------------- /src/CMSIS/ARMCM4.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file ARMCM4.h 3 | * @brief CMSIS Core Peripheral Access Layer Header File for 4 | * ARMCM4 Device (configured for CM4 without FPU) 5 | * @version V5.3.1 6 | * @date 09. July 2018 7 | ******************************************************************************/ 8 | /* 9 | * Copyright (c) 2009-2018 Arm Limited. All rights reserved. 10 | * 11 | * SPDX-License-Identifier: Apache-2.0 12 | * 13 | * Licensed under the Apache License, Version 2.0 (the License); you may 14 | * not use this file except in compliance with the License. 15 | * You may obtain a copy of the License at 16 | * 17 | * www.apache.org/licenses/LICENSE-2.0 18 | * 19 | * Unless required by applicable law or agreed to in writing, software 20 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 21 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 22 | * See the License for the specific language governing permissions and 23 | * limitations under the License. 24 | */ 25 | 26 | #ifndef ARMCM4_H 27 | #define ARMCM4_H 28 | 29 | #ifdef __cplusplus 30 | extern "C" { 31 | #endif 32 | 33 | 34 | /* ------------------------- Interrupt Number Definition ------------------------ */ 35 | 36 | typedef enum IRQn 37 | { 38 | /* ------------------- Processor Exceptions Numbers ----------------------------- */ 39 | NonMaskableInt_IRQn = -14, /* 2 Non Maskable Interrupt */ 40 | HardFault_IRQn = -13, /* 3 HardFault Interrupt */ 41 | MemoryManagement_IRQn = -12, /* 4 Memory Management Interrupt */ 42 | BusFault_IRQn = -11, /* 5 Bus Fault Interrupt */ 43 | UsageFault_IRQn = -10, /* 6 Usage Fault Interrupt */ 44 | SVCall_IRQn = -5, /* 11 SV Call Interrupt */ 45 | DebugMonitor_IRQn = -4, /* 12 Debug Monitor Interrupt */ 46 | PendSV_IRQn = -2, /* 14 Pend SV Interrupt */ 47 | SysTick_IRQn = -1, /* 15 System Tick Interrupt */ 48 | 49 | /* ------------------- Processor Interrupt Numbers ------------------------------ */ 50 | Interrupt0_IRQn = 0, 51 | Interrupt1_IRQn = 1, 52 | Interrupt2_IRQn = 2, 53 | Interrupt3_IRQn = 3, 54 | Interrupt4_IRQn = 4, 55 | Interrupt5_IRQn = 5, 56 | Interrupt6_IRQn = 6, 57 | Interrupt7_IRQn = 7, 58 | Interrupt8_IRQn = 8, 59 | Interrupt9_IRQn = 9 60 | /* Interrupts 10 .. 224 are left out */ 61 | } IRQn_Type; 62 | 63 | 64 | /* ================================================================================ */ 65 | /* ================ Processor and Core Peripheral Section ================ */ 66 | /* ================================================================================ */ 67 | 68 | /* ------- Start of section using anonymous unions and disabling warnings ------- */ 69 | #if defined (__CC_ARM) 70 | #pragma push 71 | #pragma anon_unions 72 | #elif defined (__ICCARM__) 73 | #pragma language=extended 74 | #elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) 75 | #pragma clang diagnostic push 76 | #pragma clang diagnostic ignored "-Wc11-extensions" 77 | #pragma clang diagnostic ignored "-Wreserved-id-macro" 78 | #elif defined (__GNUC__) 79 | /* anonymous unions are enabled by default */ 80 | #elif defined (__TMS470__) 81 | /* anonymous unions are enabled by default */ 82 | #elif defined (__TASKING__) 83 | #pragma warning 586 84 | #elif defined (__CSMC__) 85 | /* anonymous unions are enabled by default */ 86 | #else 87 | #warning Not supported compiler type 88 | #endif 89 | 90 | 91 | /* -------- Configuration of Core Peripherals ----------------------------------- */ 92 | #define __CM4_REV 0x0001U /* Core revision r0p1 */ 93 | #define __MPU_PRESENT 1U /* MPU present */ 94 | #define __VTOR_PRESENT 1U /* VTOR present */ 95 | #define __NVIC_PRIO_BITS 3U /* Number of Bits used for Priority Levels */ 96 | #define __Vendor_SysTickConfig 0U /* Set to 1 if different SysTick Config is used */ 97 | #define __FPU_PRESENT 0U /* no FPU present */ 98 | 99 | #include "core_cm4.h" /* Processor and core peripherals */ 100 | #include "system_ARMCM4.h" /* System Header */ 101 | 102 | 103 | /* -------- End of section using anonymous unions and disabling warnings -------- */ 104 | #if defined (__CC_ARM) 105 | #pragma pop 106 | #elif defined (__ICCARM__) 107 | /* leave anonymous unions enabled */ 108 | #elif (defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) 109 | #pragma clang diagnostic pop 110 | #elif defined (__GNUC__) 111 | /* anonymous unions are enabled by default */ 112 | #elif defined (__TMS470__) 113 | /* anonymous unions are enabled by default */ 114 | #elif defined (__TASKING__) 115 | #pragma warning restore 116 | #elif defined (__CSMC__) 117 | /* anonymous unions are enabled by default */ 118 | #else 119 | #warning Not supported compiler type 120 | #endif 121 | 122 | 123 | #ifdef __cplusplus 124 | } 125 | #endif 126 | 127 | #endif /* ARMCM4_H */ 128 | -------------------------------------------------------------------------------- /src/CMSIS/ARMCM4_FP.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file ARMCM4_FP.h 3 | * @brief CMSIS Core Peripheral Access Layer Header File for 4 | * ARMCM4 Device (configured for CM4 with FPU) 5 | * @version V5.3.1 6 | * @date 09. July 2018 7 | ******************************************************************************/ 8 | /* 9 | * Copyright (c) 2009-2018 Arm Limited. All rights reserved. 10 | * 11 | * SPDX-License-Identifier: Apache-2.0 12 | * 13 | * Licensed under the Apache License, Version 2.0 (the License); you may 14 | * not use this file except in compliance with the License. 15 | * You may obtain a copy of the License at 16 | * 17 | * www.apache.org/licenses/LICENSE-2.0 18 | * 19 | * Unless required by applicable law or agreed to in writing, software 20 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 21 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 22 | * See the License for the specific language governing permissions and 23 | * limitations under the License. 24 | */ 25 | 26 | #ifndef ARMCM4_FP_H 27 | #define ARMCM4_FP_H 28 | 29 | #ifdef __cplusplus 30 | extern "C" { 31 | #endif 32 | 33 | 34 | /* ------------------------- Interrupt Number Definition ------------------------ */ 35 | 36 | typedef enum IRQn 37 | { 38 | /* ------------------- Processor Exceptions Numbers ----------------------------- */ 39 | NonMaskableInt_IRQn = -14, /* 2 Non Maskable Interrupt */ 40 | HardFault_IRQn = -13, /* 3 HardFault Interrupt */ 41 | MemoryManagement_IRQn = -12, /* 4 Memory Management Interrupt */ 42 | BusFault_IRQn = -11, /* 5 Bus Fault Interrupt */ 43 | UsageFault_IRQn = -10, /* 6 Usage Fault Interrupt */ 44 | SVCall_IRQn = -5, /* 11 SV Call Interrupt */ 45 | DebugMonitor_IRQn = -4, /* 12 Debug Monitor Interrupt */ 46 | PendSV_IRQn = -2, /* 14 Pend SV Interrupt */ 47 | SysTick_IRQn = -1, /* 15 System Tick Interrupt */ 48 | 49 | /* ------------------- Processor Interrupt Numbers ------------------------------ */ 50 | Interrupt0_IRQn = 0, 51 | Interrupt1_IRQn = 1, 52 | Interrupt2_IRQn = 2, 53 | Interrupt3_IRQn = 3, 54 | Interrupt4_IRQn = 4, 55 | Interrupt5_IRQn = 5, 56 | Interrupt6_IRQn = 6, 57 | Interrupt7_IRQn = 7, 58 | Interrupt8_IRQn = 8, 59 | Interrupt9_IRQn = 9 60 | /* Interrupts 10 .. 224 are left out */ 61 | } IRQn_Type; 62 | 63 | 64 | /* ================================================================================ */ 65 | /* ================ Processor and Core Peripheral Section ================ */ 66 | /* ================================================================================ */ 67 | 68 | /* ------- Start of section using anonymous unions and disabling warnings ------- */ 69 | #if defined (__CC_ARM) 70 | #pragma push 71 | #pragma anon_unions 72 | #elif defined (__ICCARM__) 73 | #pragma language=extended 74 | #elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) 75 | #pragma clang diagnostic push 76 | #pragma clang diagnostic ignored "-Wc11-extensions" 77 | #pragma clang diagnostic ignored "-Wreserved-id-macro" 78 | #elif defined (__GNUC__) 79 | /* anonymous unions are enabled by default */ 80 | #elif defined (__TMS470__) 81 | /* anonymous unions are enabled by default */ 82 | #elif defined (__TASKING__) 83 | #pragma warning 586 84 | #elif defined (__CSMC__) 85 | /* anonymous unions are enabled by default */ 86 | #else 87 | #warning Not supported compiler type 88 | #endif 89 | 90 | 91 | /* -------- Configuration of Core Peripherals ----------------------------------- */ 92 | #define __CM4_REV 0x0001U /* Core revision r0p1 */ 93 | #define __MPU_PRESENT 1U /* MPU present */ 94 | #define __VTOR_PRESENT 1U /* VTOR present */ 95 | #define __NVIC_PRIO_BITS 3U /* Number of Bits used for Priority Levels */ 96 | #define __Vendor_SysTickConfig 0U /* Set to 1 if different SysTick Config is used */ 97 | #define __FPU_PRESENT 1U /* FPU present */ 98 | 99 | #include "core_cm4.h" /* Processor and core peripherals */ 100 | #include "system_ARMCM4.h" /* System Header */ 101 | 102 | 103 | /* -------- End of section using anonymous unions and disabling warnings -------- */ 104 | #if defined (__CC_ARM) 105 | #pragma pop 106 | #elif defined (__ICCARM__) 107 | /* leave anonymous unions enabled */ 108 | #elif (defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) 109 | #pragma clang diagnostic pop 110 | #elif defined (__GNUC__) 111 | /* anonymous unions are enabled by default */ 112 | #elif defined (__TMS470__) 113 | /* anonymous unions are enabled by default */ 114 | #elif defined (__TASKING__) 115 | #pragma warning restore 116 | #elif defined (__CSMC__) 117 | /* anonymous unions are enabled by default */ 118 | #else 119 | #warning Not supported compiler type 120 | #endif 121 | 122 | 123 | #ifdef __cplusplus 124 | } 125 | #endif 126 | 127 | #endif /* ARMCM4_FP_H */ 128 | -------------------------------------------------------------------------------- /src/CMSIS/arm_cos_f32.c: -------------------------------------------------------------------------------- 1 | /* ---------------------------------------------------------------------- 2 | * Project: CMSIS DSP Library 3 | * Title: arm_cos_f32.c 4 | * Description: Fast cosine calculation for floating-point values 5 | * 6 | * $Date: 18. March 2019 7 | * $Revision: V1.6.0 8 | * 9 | * Target Processor: Cortex-M cores 10 | * -------------------------------------------------------------------- */ 11 | /* 12 | * Copyright (C) 2010-2019 ARM Limited or its affiliates. All rights reserved. 13 | * 14 | * SPDX-License-Identifier: Apache-2.0 15 | * 16 | * Licensed under the Apache License, Version 2.0 (the License); you may 17 | * not use this file except in compliance with the License. 18 | * You may obtain a copy of the License at 19 | * 20 | * www.apache.org/licenses/LICENSE-2.0 21 | * 22 | * Unless required by applicable law or agreed to in writing, software 23 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 24 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 25 | * See the License for the specific language governing permissions and 26 | * limitations under the License. 27 | */ 28 | 29 | #include "arm_math.h" 30 | #include "arm_common_tables.h" 31 | 32 | /** 33 | @ingroup groupFastMath 34 | */ 35 | 36 | /** 37 | @defgroup cos Cosine 38 | 39 | Computes the trigonometric cosine function using a combination of table lookup 40 | and linear interpolation. There are separate functions for 41 | Q15, Q31, and floating-point data types. 42 | The input to the floating-point version is in radians while the 43 | fixed-point Q15 and Q31 have a scaled input with the range 44 | [0 +0.9999] mapping to [0 2*pi). The fixed-point range is chosen so that a 45 | value of 2*pi wraps around to 0. 46 | 47 | The implementation is based on table lookup using 256 values together with linear interpolation. 48 | The steps used are: 49 | -# Calculation of the nearest integer table index 50 | -# Compute the fractional portion (fract) of the table index. 51 | -# The final result equals (1.0f-fract)*a + fract*b; 52 | 53 | where 54 |
 55 |      a = Table[index];
 56 |      b = Table[index+1];
 57 |   
58 | */ 59 | 60 | /** 61 | @addtogroup cos 62 | @{ 63 | */ 64 | 65 | /** 66 | @brief Fast approximation to the trigonometric cosine function for floating-point data. 67 | @param[in] x input value in radians 68 | @return cos(x) 69 | */ 70 | float32_t arm_cos_f32( 71 | float32_t x) 72 | { 73 | float32_t cosVal, fract, in; /* Temporary input, output variables */ 74 | uint16_t index; /* Index variable */ 75 | float32_t a, b; /* Two nearest output values */ 76 | int32_t n; 77 | float32_t findex; 78 | 79 | /* input x is in radians */ 80 | /* Scale input to [0 1] range from [0 2*PI] , divide input by 2*pi, add 0.25 (pi/2) to read sine table */ 81 | in = x * 0.159154943092f + 0.25f; 82 | 83 | /* Calculation of floor value of input */ 84 | n = (int32_t) in; 85 | 86 | /* Make negative values towards -infinity */ 87 | if (in < 0.0f) 88 | { 89 | n--; 90 | } 91 | 92 | /* Map input value to [0 1] */ 93 | in = in - (float32_t) n; 94 | 95 | /* Calculation of index of the table */ 96 | findex = (float32_t)FAST_MATH_TABLE_SIZE * in; 97 | index = (uint16_t)findex; 98 | 99 | /* when "in" is exactly 1, we need to rotate the index down to 0 */ 100 | if (index >= FAST_MATH_TABLE_SIZE) { 101 | index = 0; 102 | findex -= (float32_t)FAST_MATH_TABLE_SIZE; 103 | } 104 | 105 | /* fractional value calculation */ 106 | fract = findex - (float32_t) index; 107 | 108 | /* Read two nearest values of input value from the cos table */ 109 | a = sinTable_f32[index]; 110 | b = sinTable_f32[index+1]; 111 | 112 | /* Linear interpolation process */ 113 | cosVal = (1.0f - fract) * a + fract * b; 114 | 115 | /* Return output value */ 116 | return (cosVal); 117 | } 118 | 119 | /** 120 | @} end of cos group 121 | */ 122 | -------------------------------------------------------------------------------- /src/CMSIS/arm_sin_f32.c: -------------------------------------------------------------------------------- 1 | /* ---------------------------------------------------------------------- 2 | * Project: CMSIS DSP Library 3 | * Title: arm_sin_f32.c 4 | * Description: Fast sine calculation for floating-point values 5 | * 6 | * $Date: 18. March 2019 7 | * $Revision: V1.6.0 8 | * 9 | * Target Processor: Cortex-M cores 10 | * -------------------------------------------------------------------- */ 11 | /* 12 | * Copyright (C) 2010-2019 ARM Limited or its affiliates. All rights reserved. 13 | * 14 | * SPDX-License-Identifier: Apache-2.0 15 | * 16 | * Licensed under the Apache License, Version 2.0 (the License); you may 17 | * not use this file except in compliance with the License. 18 | * You may obtain a copy of the License at 19 | * 20 | * www.apache.org/licenses/LICENSE-2.0 21 | * 22 | * Unless required by applicable law or agreed to in writing, software 23 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 24 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 25 | * See the License for the specific language governing permissions and 26 | * limitations under the License. 27 | */ 28 | 29 | #include "arm_math.h" 30 | #include "arm_common_tables.h" 31 | 32 | /** 33 | @ingroup groupFastMath 34 | */ 35 | 36 | /** 37 | @defgroup sin Sine 38 | 39 | Computes the trigonometric sine function using a combination of table lookup 40 | and linear interpolation. There are separate functions for 41 | Q15, Q31, and floating-point data types. 42 | The input to the floating-point version is in radians while the 43 | fixed-point Q15 and Q31 have a scaled input with the range 44 | [0 +0.9999] mapping to [0 2*pi). The fixed-point range is chosen so that a 45 | value of 2*pi wraps around to 0. 46 | 47 | The implementation is based on table lookup using 256 values together with linear interpolation. 48 | The steps used are: 49 | -# Calculation of the nearest integer table index 50 | -# Compute the fractional portion (fract) of the table index. 51 | -# The final result equals (1.0f-fract)*a + fract*b; 52 | 53 | where 54 |
 55 |      b = Table[index];
 56 |      c = Table[index+1];
 57 |   
58 | */ 59 | 60 | /** 61 | @addtogroup sin 62 | @{ 63 | */ 64 | 65 | /** 66 | @brief Fast approximation to the trigonometric sine function for floating-point data. 67 | @param[in] x input value in radians. 68 | @return sin(x) 69 | */ 70 | 71 | float32_t arm_sin_f32( 72 | float32_t x) 73 | { 74 | float32_t sinVal, fract, in; /* Temporary input, output variables */ 75 | uint16_t index; /* Index variable */ 76 | float32_t a, b; /* Two nearest output values */ 77 | int32_t n; 78 | float32_t findex; 79 | 80 | /* input x is in radians */ 81 | /* Scale input to [0 1] range from [0 2*PI] , divide input by 2*pi */ 82 | in = x * 0.159154943092f; 83 | 84 | /* Calculation of floor value of input */ 85 | n = (int32_t) in; 86 | 87 | /* Make negative values towards -infinity */ 88 | if (in < 0.0f) 89 | { 90 | n--; 91 | } 92 | 93 | /* Map input value to [0 1] */ 94 | in = in - (float32_t) n; 95 | 96 | /* Calculation of index of the table */ 97 | findex = (float32_t)FAST_MATH_TABLE_SIZE * in; 98 | index = (uint16_t)findex; 99 | 100 | /* when "in" is exactly 1, we need to rotate the index down to 0 */ 101 | if (index >= FAST_MATH_TABLE_SIZE) { 102 | index = 0; 103 | findex -= (float32_t)FAST_MATH_TABLE_SIZE; 104 | } 105 | 106 | /* fractional value calculation */ 107 | fract = findex - (float32_t) index; 108 | 109 | /* Read two nearest values of input value from the sin table */ 110 | a = sinTable_f32[index]; 111 | b = sinTable_f32[index+1]; 112 | 113 | /* Linear interpolation process */ 114 | sinVal = (1.0f - fract) * a + fract * b; 115 | 116 | /* Return output value */ 117 | return (sinVal); 118 | } 119 | 120 | /** 121 | @} end of sin group 122 | */ 123 | -------------------------------------------------------------------------------- /src/CMSIS/cmsis_version.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file cmsis_version.h 3 | * @brief CMSIS Core(M) Version definitions 4 | * @version V5.0.4 5 | * @date 23. July 2019 6 | ******************************************************************************/ 7 | /* 8 | * Copyright (c) 2009-2019 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 ( 4U) /*!< [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 | -------------------------------------------------------------------------------- /src/CMSIS/system_ARMCM4.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file system_ARMCM4.h 3 | * @brief CMSIS Device System Header File for 4 | * ARMCM4 Device 5 | * @version V5.3.2 6 | * @date 15. November 2019 7 | ******************************************************************************/ 8 | /* 9 | * Copyright (c) 2009-2019 Arm Limited. All rights reserved. 10 | * 11 | * SPDX-License-Identifier: Apache-2.0 12 | * 13 | * Licensed under the Apache License, Version 2.0 (the License); you may 14 | * not use this file except in compliance with the License. 15 | * You may obtain a copy of the License at 16 | * 17 | * www.apache.org/licenses/LICENSE-2.0 18 | * 19 | * Unless required by applicable law or agreed to in writing, software 20 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 21 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 22 | * See the License for the specific language governing permissions and 23 | * limitations under the License. 24 | */ 25 | 26 | #ifndef SYSTEM_ARMCM4_H 27 | #define SYSTEM_ARMCM4_H 28 | 29 | #ifdef __cplusplus 30 | extern "C" { 31 | #endif 32 | 33 | /** 34 | \brief Exception / Interrupt Handler Function Prototype 35 | */ 36 | typedef void(*VECTOR_TABLE_Type)(void); 37 | 38 | /** 39 | \brief System Clock Frequency (Core Clock) 40 | */ 41 | extern uint32_t SystemCoreClock; 42 | 43 | /** 44 | \brief Setup the microcontroller system. 45 | 46 | Initialize the System and update the SystemCoreClock variable. 47 | */ 48 | extern void SystemInit (void); 49 | 50 | 51 | /** 52 | \brief Update SystemCoreClock variable. 53 | 54 | Updates the SystemCoreClock with current core Clock retrieved from cpu registers. 55 | */ 56 | extern void SystemCoreClockUpdate (void); 57 | 58 | #ifdef __cplusplus 59 | } 60 | #endif 61 | 62 | #endif /* SYSTEM_ARMCM4_H */ 63 | -------------------------------------------------------------------------------- /src/free_rtos_source/heap_1.c: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.3.1 3 | * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | 29 | /* 30 | * The simplest possible implementation of pvPortMalloc(). Note that this 31 | * implementation does NOT allow allocated memory to be freed again. 32 | * 33 | * See heap_2.c, heap_3.c and heap_4.c for alternative implementations, and the 34 | * memory management pages of http://www.FreeRTOS.org for more information. 35 | */ 36 | #include 37 | 38 | /* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining 39 | all the API functions to use the MPU wrappers. That should only be done when 40 | task.h is included from an application file. */ 41 | #define MPU_WRAPPERS_INCLUDED_FROM_API_FILE 42 | 43 | #include "FreeRTOS.h" 44 | #include "task.h" 45 | 46 | #undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE 47 | 48 | #if( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) 49 | #error This file must not be used if configSUPPORT_DYNAMIC_ALLOCATION is 0 50 | #endif 51 | 52 | /* A few bytes might be lost to byte aligning the heap start address. */ 53 | #define configADJUSTED_HEAP_SIZE ( configTOTAL_HEAP_SIZE - portBYTE_ALIGNMENT ) 54 | 55 | /* Allocate the memory for the heap. */ 56 | #if( configAPPLICATION_ALLOCATED_HEAP == 1 ) 57 | /* The application writer has already defined the array used for the RTOS 58 | heap - probably so it can be placed in a special segment or address. */ 59 | extern uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; 60 | #else 61 | static uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; 62 | #endif /* configAPPLICATION_ALLOCATED_HEAP */ 63 | 64 | /* Index into the ucHeap array. */ 65 | static size_t xNextFreeByte = ( size_t ) 0; 66 | 67 | /*-----------------------------------------------------------*/ 68 | 69 | void *pvPortMalloc( size_t xWantedSize ) 70 | { 71 | void *pvReturn = NULL; 72 | static uint8_t *pucAlignedHeap = NULL; 73 | 74 | /* Ensure that blocks are always aligned to the required number of bytes. */ 75 | #if( portBYTE_ALIGNMENT != 1 ) 76 | { 77 | if( xWantedSize & portBYTE_ALIGNMENT_MASK ) 78 | { 79 | /* Byte alignment required. */ 80 | xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); 81 | } 82 | } 83 | #endif 84 | 85 | vTaskSuspendAll(); 86 | { 87 | if( pucAlignedHeap == NULL ) 88 | { 89 | /* Ensure the heap starts on a correctly aligned boundary. */ 90 | pucAlignedHeap = ( uint8_t * ) ( ( ( portPOINTER_SIZE_TYPE ) &ucHeap[ portBYTE_ALIGNMENT ] ) & ( ~( ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) ) ); 91 | } 92 | 93 | /* Check there is enough room left for the allocation. */ 94 | if( ( ( xNextFreeByte + xWantedSize ) < configADJUSTED_HEAP_SIZE ) && 95 | ( ( xNextFreeByte + xWantedSize ) > xNextFreeByte ) )/* Check for overflow. */ 96 | { 97 | /* Return the next free byte then increment the index past this 98 | block. */ 99 | pvReturn = pucAlignedHeap + xNextFreeByte; 100 | xNextFreeByte += xWantedSize; 101 | } 102 | 103 | traceMALLOC( pvReturn, xWantedSize ); 104 | } 105 | ( void ) xTaskResumeAll(); 106 | 107 | #if( configUSE_MALLOC_FAILED_HOOK == 1 ) 108 | { 109 | if( pvReturn == NULL ) 110 | { 111 | extern void vApplicationMallocFailedHook( void ); 112 | vApplicationMallocFailedHook(); 113 | } 114 | } 115 | #endif 116 | 117 | return pvReturn; 118 | } 119 | /*-----------------------------------------------------------*/ 120 | 121 | void vPortFree( void *pv ) 122 | { 123 | /* Memory cannot be freed using this scheme. See heap_2.c, heap_3.c and 124 | heap_4.c for alternative implementations, and the memory management pages of 125 | http://www.FreeRTOS.org for more information. */ 126 | ( void ) pv; 127 | 128 | /* Force an assert as it is invalid to call this function. */ 129 | configASSERT( pv == NULL ); 130 | } 131 | /*-----------------------------------------------------------*/ 132 | 133 | void vPortInitialiseBlocks( void ) 134 | { 135 | /* Only required when static memory is not cleared. */ 136 | xNextFreeByte = ( size_t ) 0; 137 | } 138 | /*-----------------------------------------------------------*/ 139 | 140 | size_t xPortGetFreeHeapSize( void ) 141 | { 142 | return ( configADJUSTED_HEAP_SIZE - xNextFreeByte ); 143 | } 144 | 145 | 146 | 147 | -------------------------------------------------------------------------------- /src/free_rtos_source/include/StackMacros.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.3.1 3 | * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | #ifndef STACK_MACROS_H 29 | #define STACK_MACROS_H 30 | 31 | #ifndef _MSC_VER /* Visual Studio doesn't support #warning. */ 32 | #warning The name of this file has changed to stack_macros.h. Please update your code accordingly. This source file (which has the original name) will be removed in future released. 33 | #endif 34 | 35 | /* 36 | * Call the stack overflow hook function if the stack of the task being swapped 37 | * out is currently overflowed, or looks like it might have overflowed in the 38 | * past. 39 | * 40 | * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check 41 | * the current stack state only - comparing the current top of stack value to 42 | * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 43 | * will also cause the last few stack bytes to be checked to ensure the value 44 | * to which the bytes were set when the task was created have not been 45 | * overwritten. Note this second test does not guarantee that an overflowed 46 | * stack will always be recognised. 47 | */ 48 | 49 | /*-----------------------------------------------------------*/ 50 | 51 | #if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH < 0 ) ) 52 | 53 | /* Only the current stack state is to be checked. */ 54 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 55 | { \ 56 | /* Is the currently saved stack pointer within the stack limit? */ \ 57 | if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ 58 | { \ 59 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 60 | } \ 61 | } 62 | 63 | #endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ 64 | /*-----------------------------------------------------------*/ 65 | 66 | #if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH > 0 ) ) 67 | 68 | /* Only the current stack state is to be checked. */ 69 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 70 | { \ 71 | \ 72 | /* Is the currently saved stack pointer within the stack limit? */ \ 73 | if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ 74 | { \ 75 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 76 | } \ 77 | } 78 | 79 | #endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ 80 | /*-----------------------------------------------------------*/ 81 | 82 | #if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) 83 | 84 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 85 | { \ 86 | const uint32_t * const pulStack = ( uint32_t * ) pxCurrentTCB->pxStack; \ 87 | const uint32_t ulCheckValue = ( uint32_t ) 0xa5a5a5a5; \ 88 | \ 89 | if( ( pulStack[ 0 ] != ulCheckValue ) || \ 90 | ( pulStack[ 1 ] != ulCheckValue ) || \ 91 | ( pulStack[ 2 ] != ulCheckValue ) || \ 92 | ( pulStack[ 3 ] != ulCheckValue ) ) \ 93 | { \ 94 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 95 | } \ 96 | } 97 | 98 | #endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ 99 | /*-----------------------------------------------------------*/ 100 | 101 | #if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) 102 | 103 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 104 | { \ 105 | int8_t *pcEndOfStack = ( int8_t * ) pxCurrentTCB->pxEndOfStack; \ 106 | static const uint8_t ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 107 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 108 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 109 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 110 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ 111 | \ 112 | \ 113 | pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ 114 | \ 115 | /* Has the extremity of the task stack ever been written over? */ \ 116 | if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ 117 | { \ 118 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 119 | } \ 120 | } 121 | 122 | #endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ 123 | /*-----------------------------------------------------------*/ 124 | 125 | /* Remove stack overflow macro if not being used. */ 126 | #ifndef taskCHECK_FOR_STACK_OVERFLOW 127 | #define taskCHECK_FOR_STACK_OVERFLOW() 128 | #endif 129 | 130 | 131 | 132 | #endif /* STACK_MACROS_H */ 133 | 134 | -------------------------------------------------------------------------------- /src/free_rtos_source/include/projdefs.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.3.1 3 | * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | #ifndef PROJDEFS_H 29 | #define PROJDEFS_H 30 | 31 | /* 32 | * Defines the prototype to which task functions must conform. Defined in this 33 | * file to ensure the type is known before portable.h is included. 34 | */ 35 | typedef void (*TaskFunction_t)( void * ); 36 | 37 | /* Converts a time in milliseconds to a time in ticks. This macro can be 38 | overridden by a macro of the same name defined in FreeRTOSConfig.h in case the 39 | definition here is not suitable for your application. */ 40 | #ifndef pdMS_TO_TICKS 41 | #define pdMS_TO_TICKS( xTimeInMs ) ( ( TickType_t ) ( ( ( TickType_t ) ( xTimeInMs ) * ( TickType_t ) configTICK_RATE_HZ ) / ( TickType_t ) 1000 ) ) 42 | #endif 43 | 44 | #define pdFALSE ( ( BaseType_t ) 0 ) 45 | #define pdTRUE ( ( BaseType_t ) 1 ) 46 | 47 | #define pdPASS ( pdTRUE ) 48 | #define pdFAIL ( pdFALSE ) 49 | #define errQUEUE_EMPTY ( ( BaseType_t ) 0 ) 50 | #define errQUEUE_FULL ( ( BaseType_t ) 0 ) 51 | 52 | /* FreeRTOS error definitions. */ 53 | #define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) 54 | #define errQUEUE_BLOCKED ( -4 ) 55 | #define errQUEUE_YIELD ( -5 ) 56 | 57 | /* Macros used for basic data corruption checks. */ 58 | #ifndef configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES 59 | #define configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES 0 60 | #endif 61 | 62 | #if( configUSE_16_BIT_TICKS == 1 ) 63 | #define pdINTEGRITY_CHECK_VALUE 0x5a5a 64 | #else 65 | #define pdINTEGRITY_CHECK_VALUE 0x5a5a5a5aUL 66 | #endif 67 | 68 | /* The following errno values are used by FreeRTOS+ components, not FreeRTOS 69 | itself. */ 70 | #define pdFREERTOS_ERRNO_NONE 0 /* No errors */ 71 | #define pdFREERTOS_ERRNO_ENOENT 2 /* No such file or directory */ 72 | #define pdFREERTOS_ERRNO_EINTR 4 /* Interrupted system call */ 73 | #define pdFREERTOS_ERRNO_EIO 5 /* I/O error */ 74 | #define pdFREERTOS_ERRNO_ENXIO 6 /* No such device or address */ 75 | #define pdFREERTOS_ERRNO_EBADF 9 /* Bad file number */ 76 | #define pdFREERTOS_ERRNO_EAGAIN 11 /* No more processes */ 77 | #define pdFREERTOS_ERRNO_EWOULDBLOCK 11 /* Operation would block */ 78 | #define pdFREERTOS_ERRNO_ENOMEM 12 /* Not enough memory */ 79 | #define pdFREERTOS_ERRNO_EACCES 13 /* Permission denied */ 80 | #define pdFREERTOS_ERRNO_EFAULT 14 /* Bad address */ 81 | #define pdFREERTOS_ERRNO_EBUSY 16 /* Mount device busy */ 82 | #define pdFREERTOS_ERRNO_EEXIST 17 /* File exists */ 83 | #define pdFREERTOS_ERRNO_EXDEV 18 /* Cross-device link */ 84 | #define pdFREERTOS_ERRNO_ENODEV 19 /* No such device */ 85 | #define pdFREERTOS_ERRNO_ENOTDIR 20 /* Not a directory */ 86 | #define pdFREERTOS_ERRNO_EISDIR 21 /* Is a directory */ 87 | #define pdFREERTOS_ERRNO_EINVAL 22 /* Invalid argument */ 88 | #define pdFREERTOS_ERRNO_ENOSPC 28 /* No space left on device */ 89 | #define pdFREERTOS_ERRNO_ESPIPE 29 /* Illegal seek */ 90 | #define pdFREERTOS_ERRNO_EROFS 30 /* Read only file system */ 91 | #define pdFREERTOS_ERRNO_EUNATCH 42 /* Protocol driver not attached */ 92 | #define pdFREERTOS_ERRNO_EBADE 50 /* Invalid exchange */ 93 | #define pdFREERTOS_ERRNO_EFTYPE 79 /* Inappropriate file type or format */ 94 | #define pdFREERTOS_ERRNO_ENMFILE 89 /* No more files */ 95 | #define pdFREERTOS_ERRNO_ENOTEMPTY 90 /* Directory not empty */ 96 | #define pdFREERTOS_ERRNO_ENAMETOOLONG 91 /* File or path name too long */ 97 | #define pdFREERTOS_ERRNO_EOPNOTSUPP 95 /* Operation not supported on transport endpoint */ 98 | #define pdFREERTOS_ERRNO_ENOBUFS 105 /* No buffer space available */ 99 | #define pdFREERTOS_ERRNO_ENOPROTOOPT 109 /* Protocol not available */ 100 | #define pdFREERTOS_ERRNO_EADDRINUSE 112 /* Address already in use */ 101 | #define pdFREERTOS_ERRNO_ETIMEDOUT 116 /* Connection timed out */ 102 | #define pdFREERTOS_ERRNO_EINPROGRESS 119 /* Connection already in progress */ 103 | #define pdFREERTOS_ERRNO_EALREADY 120 /* Socket already connected */ 104 | #define pdFREERTOS_ERRNO_EADDRNOTAVAIL 125 /* Address not available */ 105 | #define pdFREERTOS_ERRNO_EISCONN 127 /* Socket is already connected */ 106 | #define pdFREERTOS_ERRNO_ENOTCONN 128 /* Socket is not connected */ 107 | #define pdFREERTOS_ERRNO_ENOMEDIUM 135 /* No medium inserted */ 108 | #define pdFREERTOS_ERRNO_EILSEQ 138 /* An invalid UTF-16 sequence was encountered. */ 109 | #define pdFREERTOS_ERRNO_ECANCELED 140 /* Operation canceled. */ 110 | 111 | /* The following endian values are used by FreeRTOS+ components, not FreeRTOS 112 | itself. */ 113 | #define pdFREERTOS_LITTLE_ENDIAN 0 114 | #define pdFREERTOS_BIG_ENDIAN 1 115 | 116 | /* Re-defining endian values for generic naming. */ 117 | #define pdLITTLE_ENDIAN pdFREERTOS_LITTLE_ENDIAN 118 | #define pdBIG_ENDIAN pdFREERTOS_BIG_ENDIAN 119 | 120 | 121 | #endif /* PROJDEFS_H */ 122 | 123 | 124 | 125 | -------------------------------------------------------------------------------- /src/free_rtos_source/include/stack_macros.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.3.1 3 | * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | #ifndef STACK_MACROS_H 29 | #define STACK_MACROS_H 30 | 31 | /* 32 | * Call the stack overflow hook function if the stack of the task being swapped 33 | * out is currently overflowed, or looks like it might have overflowed in the 34 | * past. 35 | * 36 | * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check 37 | * the current stack state only - comparing the current top of stack value to 38 | * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 39 | * will also cause the last few stack bytes to be checked to ensure the value 40 | * to which the bytes were set when the task was created have not been 41 | * overwritten. Note this second test does not guarantee that an overflowed 42 | * stack will always be recognised. 43 | */ 44 | 45 | /*-----------------------------------------------------------*/ 46 | 47 | #if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH < 0 ) ) 48 | 49 | /* Only the current stack state is to be checked. */ 50 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 51 | { \ 52 | /* Is the currently saved stack pointer within the stack limit? */ \ 53 | if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ 54 | { \ 55 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 56 | } \ 57 | } 58 | 59 | #endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ 60 | /*-----------------------------------------------------------*/ 61 | 62 | #if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH > 0 ) ) 63 | 64 | /* Only the current stack state is to be checked. */ 65 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 66 | { \ 67 | \ 68 | /* Is the currently saved stack pointer within the stack limit? */ \ 69 | if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ 70 | { \ 71 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 72 | } \ 73 | } 74 | 75 | #endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ 76 | /*-----------------------------------------------------------*/ 77 | 78 | #if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) 79 | 80 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 81 | { \ 82 | const uint32_t * const pulStack = ( uint32_t * ) pxCurrentTCB->pxStack; \ 83 | const uint32_t ulCheckValue = ( uint32_t ) 0xa5a5a5a5; \ 84 | \ 85 | if( ( pulStack[ 0 ] != ulCheckValue ) || \ 86 | ( pulStack[ 1 ] != ulCheckValue ) || \ 87 | ( pulStack[ 2 ] != ulCheckValue ) || \ 88 | ( pulStack[ 3 ] != ulCheckValue ) ) \ 89 | { \ 90 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 91 | } \ 92 | } 93 | 94 | #endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ 95 | /*-----------------------------------------------------------*/ 96 | 97 | #if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) 98 | 99 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 100 | { \ 101 | int8_t *pcEndOfStack = ( int8_t * ) pxCurrentTCB->pxEndOfStack; \ 102 | static const uint8_t ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 103 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 104 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 105 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 106 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ 107 | \ 108 | \ 109 | pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ 110 | \ 111 | /* Has the extremity of the task stack ever been written over? */ \ 112 | if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ 113 | { \ 114 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 115 | } \ 116 | } 117 | 118 | #endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ 119 | /*-----------------------------------------------------------*/ 120 | 121 | /* Remove stack overflow macro if not being used. */ 122 | #ifndef taskCHECK_FOR_STACK_OVERFLOW 123 | #define taskCHECK_FOR_STACK_OVERFLOW() 124 | #endif 125 | 126 | 127 | 128 | #endif /* STACK_MACROS_H */ 129 | 130 | -------------------------------------------------------------------------------- /src/free_rtos_source/include/stdint.readme: -------------------------------------------------------------------------------- 1 | 2 | #ifndef FREERTOS_STDINT 3 | #define FREERTOS_STDINT 4 | 5 | /******************************************************************************* 6 | * THIS IS NOT A FULL stdint.h IMPLEMENTATION - It only contains the definitions 7 | * necessary to build the FreeRTOS code. It is provided to allow FreeRTOS to be 8 | * built using compilers that do not provide their own stdint.h definition. 9 | * 10 | * To use this file: 11 | * 12 | * 1) Copy this file into the directory that contains your FreeRTOSConfig.h 13 | * header file, as that directory will already be in the compilers include 14 | * path. 15 | * 16 | * 2) Rename the copied file stdint.h. 17 | * 18 | */ 19 | 20 | typedef signed char int8_t; 21 | typedef unsigned char uint8_t; 22 | typedef short int16_t; 23 | typedef unsigned short uint16_t; 24 | typedef long int32_t; 25 | typedef unsigned long uint32_t; 26 | 27 | #endif /* FREERTOS_STDINT */ 28 | -------------------------------------------------------------------------------- /src/free_rtos_source/readme.txt: -------------------------------------------------------------------------------- 1 | Each real time kernel port consists of three files that contain the core kernel 2 | components and are common to every port, and one or more files that are 3 | specific to a particular microcontroller and or compiler. 4 | 5 | + The FreeRTOS/Source directory contains the three files that are common to 6 | every port - list.c, queue.c and tasks.c. The kernel is contained within these 7 | three files. croutine.c implements the optional co-routine functionality - which 8 | is normally only used on very memory limited systems. 9 | 10 | + The FreeRTOS/Source/Portable directory contains the files that are specific to 11 | a particular microcontroller and or compiler. 12 | 13 | + The FreeRTOS/Source/include directory contains the real time kernel header 14 | files. 15 | 16 | See the readme file in the FreeRTOS/Source/Portable directory for more 17 | information. -------------------------------------------------------------------------------- /src/hw_io/adc_conversions.cpp: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This file provides the methods for converting values from raw ADC counts 30 | // to actual engineering units. 31 | // 32 | //////////////////////////////////////////////////////////////////////////////// 33 | #include "adc_conversions.h" 34 | #include "global_definitions.h" 35 | 36 | namespace ADCConversions 37 | { 38 | 39 | //////////////////////////////////////////////////////////////////////////////// 40 | // 41 | // This converts a phase current value from raw ADC counts to amperes. 42 | // 43 | //////////////////////////////////////////////////////////////////////////////// 44 | amperes convertPhaseCurrent(const rawADCCounts ADCinput) 45 | { 46 | // 47 | // First, we make sure the input value actually falls within the range 48 | // of an expected ADC input. 49 | // 50 | int32_t adjustedADCInputs; 51 | if (ADCinput > rawADCFullScale) 52 | { 53 | adjustedADCInputs = static_cast(rawADCFullScale); 54 | } 55 | else 56 | { 57 | adjustedADCInputs = static_cast(ADCinput); 58 | } 59 | 60 | // 61 | // Phase current is actually signed so we need to offset the input. 62 | // 63 | adjustedADCInputs = adjustedADCInputs - makeCurrentSignedOffset; 64 | 65 | // 66 | // Now we can convert. 67 | // 68 | const float32_t phaseCurrentADCCountsToAmperes = voltsPerCount * phaseCurrentConversion; 69 | amperes phaseCurrent = static_cast(adjustedADCInputs) * phaseCurrentADCCountsToAmperes; 70 | 71 | // 72 | // We are not quite done. We need to invert the sign of the phase current 73 | // due to the hardware current sense implementation. 74 | // 75 | phaseCurrent = phaseCurrent * correctCurrentInversionGain; 76 | 77 | return phaseCurrent; 78 | } 79 | 80 | //////////////////////////////////////////////////////////////////////////////// 81 | // 82 | // This converts a bus current value from raw ADC counts to amperes. 83 | // 84 | //////////////////////////////////////////////////////////////////////////////// 85 | amperes convertBusCurrent(const rawADCCounts ADCinput) 86 | { 87 | int32_t adjustedADCInputs; 88 | if (ADCinput > rawADCFullScale) 89 | { 90 | adjustedADCInputs = static_cast(rawADCFullScale); 91 | } 92 | else 93 | { 94 | adjustedADCInputs = static_cast(ADCinput); 95 | } 96 | 97 | adjustedADCInputs = adjustedADCInputs - makeCurrentSignedOffset; 98 | 99 | const float32_t busCurrentADCCountsToAmperes = voltsPerCount * busCurrentConversion; 100 | amperes busCurrent = static_cast(adjustedADCInputs) * busCurrentADCCountsToAmperes; 101 | 102 | busCurrent = busCurrent * correctCurrentInversionGain; 103 | 104 | return busCurrent; 105 | } 106 | 107 | //////////////////////////////////////////////////////////////////////////////// 108 | // 109 | // This converts a phase voltage value from raw ADC counts to volts. 110 | // 111 | //////////////////////////////////////////////////////////////////////////////// 112 | volts convertPhaseVoltage(const rawADCCounts ADCinput) 113 | { 114 | int32_t adjustedADCInputs; 115 | if (ADCinput > rawADCFullScale) 116 | { 117 | adjustedADCInputs = static_cast(rawADCFullScale); 118 | } 119 | else 120 | { 121 | adjustedADCInputs = static_cast(ADCinput); 122 | } 123 | 124 | const float32_t phaseVoltageADCCountsToVolts = voltsPerCount * phaseVoltageConversion; 125 | volts phaseVoltage = static_cast(adjustedADCInputs) * phaseVoltageADCCountsToVolts; 126 | 127 | return phaseVoltage; 128 | } 129 | 130 | //////////////////////////////////////////////////////////////////////////////// 131 | // 132 | // This converts a bus voltage value from raw ADC counts to volts. 133 | // 134 | //////////////////////////////////////////////////////////////////////////////// 135 | volts convertBusVoltage(const rawADCCounts ADCinput) 136 | { 137 | int32_t adjustedADCInputs; 138 | if (ADCinput > rawADCFullScale) 139 | { 140 | adjustedADCInputs = static_cast(rawADCFullScale); 141 | } 142 | else 143 | { 144 | adjustedADCInputs = static_cast(ADCinput); 145 | } 146 | 147 | const float32_t busVoltageADCCountsToVolts = voltsPerCount * busVoltageConversion; 148 | volts busVoltage = static_cast(adjustedADCInputs) * busVoltageADCCountsToVolts; 149 | 150 | return busVoltage; 151 | } 152 | } 153 | 154 | -------------------------------------------------------------------------------- /src/hw_io/adc_conversions.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines constants and functions for converting data from ADC counts to 30 | // engineering units. 31 | // 32 | //////////////////////////////////////////////////////////////////////////////// 33 | #pragma once 34 | 35 | #include "global_definitions.h" 36 | 37 | // 38 | // These are types specific to ADC value conversions. 39 | // 40 | typedef uint32_t rawADCCounts; 41 | typedef float32_t ADCCounts; 42 | typedef float32_t ADCVolts; 43 | typedef float32_t ADCCountsPerADCVolt; 44 | typedef float32_t ADCVoltsPerADCCount; 45 | typedef float32_t amperesPerADCVolt; 46 | typedef float32_t voltsPerADCVolt; 47 | 48 | 49 | namespace ADCConversions 50 | { 51 | // 52 | // These items describe the basic relationship between ADC counts and voltages at 53 | // its inputs. 54 | // 55 | const bits ADCResolution = 12U; 56 | const rawADCCounts rawADCFullScale = (1U << ADCResolution) - 1U; 57 | const ADCCounts ADCFullScale = static_cast(rawADCFullScale); 58 | const volts ADCReference = 3.3F; 59 | const ADCCountsPerADCVolt countsPerVolt = static_cast(ADCFullScale) / ADCReference; 60 | const ADCVoltsPerADCCount voltsPerCount = ADCReference / static_cast(ADCFullScale); 61 | 62 | // 63 | // These define the relationship between volts at the ADC's input and 64 | // the equivalent engineering unit. For the present hardware, the derivation 65 | // of these may be found in document "ti_drv8312_evm_scale_factors.pdf", which 66 | // is included with this software. We start with the phase currents. 67 | // 68 | const amperesPerADCVolt phaseCurrentConversion = 5.24F; 69 | const amperesPerADCVolt busCurrentConversion = 5.22F; 70 | const voltsPerADCVolt phaseVoltageConversion = 19.7F; 71 | const voltsPerADCVolt busVoltageConversion = 19.7F; 72 | 73 | // 74 | // These define other factors required to convert ADC values to units. These 75 | // are used to account for fixed offsets and gains in the circuits. These 76 | // should not be confused with offsets and gains that may vary from implementation 77 | // to implementation. Those are not handled here. 78 | // 79 | const int32_t makeCurrentSignedOffset = static_cast(rawADCFullScale) / 2; 80 | const amperesPerADCVolt correctCurrentInversionGain = -1.0F; 81 | 82 | // 83 | // These methods perform the unit conversions. All accept raw ADC counts 84 | // as their inputs and return the appropriate engineering unit. 85 | // 86 | amperes convertPhaseCurrent(const rawADCCounts ADCinput); 87 | amperes convertBusCurrent(const rawADCCounts ADCinput); 88 | volts convertPhaseVoltage(const rawADCCounts ADCinput); 89 | volts convertBusVoltage(const rawADCCounts ADCinput); 90 | } 91 | 92 | -------------------------------------------------------------------------------- /src/hw_io/adc_interface.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the interface to the processor's Analog-to-Digital (ADC) interface 30 | // 31 | // The ADC collects the analog input data required to control the motor. It 32 | // is configured to collect that data near the center of the PWM cycle to 33 | // avoid noise issues that can occur when the PWMs change state. 34 | // 35 | //////////////////////////////////////////////////////////////////////////////// 36 | #pragma once 37 | 38 | #include "adc_conversions.h" 39 | #include "global_definitions.h" 40 | #include "processor.h" 41 | 42 | class ADCInterface 43 | { 44 | public: 45 | ADCInterface(); 46 | ~ADCInterface() {}; 47 | 48 | // 49 | // This prepares the ADC interface for operation. It sets everything 50 | // up but it does not start actual data collection and the 51 | // associated interrupts. 52 | // 53 | void initializeADCInterface(); 54 | 55 | // 56 | // This starts ADC data collection. As a result, ADC data-ready interrupts 57 | // will be processed and the motor controller will be invoked. This would 58 | // normally be called once during system start-up. 59 | // 60 | void startADCCollections(); 61 | 62 | // 63 | // This processes a new frame of ADC data. It is expected that this is 64 | // called from an ISR. In addition to managing the ADC, this invokes the 65 | // motor controller. It is expected that the motor controller will call 66 | // commandADCDataCollection once it has retrieved the data it requires. 67 | // 68 | void processADCDataReady(); 69 | 70 | // 71 | // This is the data structure used to provide basic motor control data. 72 | // 73 | typedef struct 74 | { 75 | rawADCCounts currentA; 76 | rawADCCounts currentB; 77 | rawADCCounts currentC; 78 | rawADCCounts voltageA; 79 | rawADCCounts voltageB; 80 | rawADCCounts voltageC; 81 | rawADCCounts busCurrent; 82 | rawADCCounts busVoltage; 83 | } rawMotorData; 84 | 85 | // 86 | // These provide the most recently collected ADC data in ADC counts. 87 | // Note that some of these items may not exist in certain hardware 88 | // configurations. It is important that these be called soon after 89 | // processADCDataReady has been called to start a new frame's processing. 90 | // However, these should also be called before commandADCDataCollection is 91 | // called to start the next ADC update. Calling any of these after 92 | // commandADCDataCollection could lead to a data collision with the DMA 93 | // controllers that move data from the ADC to the local storage buffers. 94 | // 95 | void getRawMotorData(rawMotorData &newMotorData); 96 | void getRawAnalogHallInputs( 97 | rawADCCounts &hallA, 98 | rawADCCounts &hallB, 99 | rawADCCounts &hallC); 100 | 101 | // 102 | // This commands the next data collection. 103 | // 104 | void commandADCDataCollection(); 105 | 106 | private: 107 | 108 | }; 109 | 110 | #ifdef __cplusplus 111 | extern "C" { 112 | #endif 113 | 114 | // 115 | // This is the ISR for the DMA's new-ADC-data-is-ready interrupt. 116 | // 117 | void DMA2_Stream0_IRQHandler(void); 118 | 119 | #ifdef __cplusplus 120 | } 121 | #endif 122 | 123 | // 124 | // We create a single instance of this class that may be referenced 125 | // globally. 126 | // 127 | extern ADCInterface theADCInterface; 128 | -------------------------------------------------------------------------------- /src/hw_io/dac_interface.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the interface to the processor's Digital-to-Analog Converter (DAC) 30 | // 31 | // The DAC is used to output analog data at a high rate. It uses may include 32 | // algorithm development. 33 | // 34 | //////////////////////////////////////////////////////////////////////////////// 35 | #pragma once 36 | 37 | #include "global_definitions.h" 38 | #include "processor.h" 39 | 40 | namespace DACDefinitions 41 | { 42 | // 43 | // These items describe the relationship between DAC counts and voltages at 44 | // its outputs. 45 | // 46 | const volts DACReferenceVoltage = 3.3F; 47 | const float32_t DACFullScale_counts = 4096.0F; 48 | const float32_t DACCountsPerVolt = DACFullScale_counts / DACReferenceVoltage; 49 | const float32_t DACVoltsPerCount = DACReferenceVoltage / DACFullScale_counts; 50 | } 51 | 52 | class DACInterface 53 | { 54 | public: 55 | DACInterface(); 56 | ~DACInterface() {}; 57 | 58 | // 59 | // This prepares the DAC for operation. 60 | // 61 | void initializeDACInterface(); 62 | 63 | // 64 | // These set the conversion factors for each DAC channel. These may be 65 | // updated at any time. These are used to convert the values sent to 66 | // the DAC to the appropriate counts range for the DAC. The minimum 67 | // and maximum values should be set to the expected range of the values 68 | // provided to sentToDACn. The DAC output will be scaled such that 69 | // DAC1MinValue will produce zero volts at the output and DAC1MaxValue 70 | // will produce dacReferenceVoltage volts at the output. 71 | // 72 | void setDAC1ConversionFactors(const float32_t DAC1MinValue, const float32_t DAC1MaxValue); 73 | void setDAC2ConversionFactors(const float32_t DAC2MinValue, const float32_t DAC2MaxValue); 74 | 75 | // 76 | // These update the values sent out the DAC. The appropriate gain and 77 | // offset are applied to the provided value to convert the value to 78 | // counts for the DAC. 79 | // 80 | void sendToDAC1(const float32_t outputValue); 81 | void sendToDAC2(const float32_t outputValue); 82 | 83 | private: 84 | 85 | // 86 | // These latch the conversion factors for each DAC channel. 87 | // 88 | float32_t dac1Gain; 89 | float32_t dac1Offset; 90 | float32_t dac2Gain; 91 | float32_t dac2Offset; 92 | }; 93 | 94 | // 95 | // We create a single instance of this class that may be referenced 96 | // globally. 97 | // 98 | extern DACInterface theDACInterface; 99 | 100 | -------------------------------------------------------------------------------- /src/hw_io/gpio_interface.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the interface to the processor's discrete GPIOs 30 | // 31 | //////////////////////////////////////////////////////////////////////////////// 32 | #pragma once 33 | 34 | #include "hw_definitions.h" 35 | #include "processor.h" 36 | 37 | using namespace GPIODefinitions; 38 | 39 | class GPIOInterface 40 | { 41 | public: 42 | GPIOInterface(); 43 | ~GPIOInterface() {}; 44 | 45 | // 46 | // This prepares the GPIO interface for operation. 47 | // 48 | void initializeGPIOInterface(); 49 | 50 | // 51 | // These enable/disable the bridge driver. If the bridge driver faults 52 | // disabling it will reset any fault condition. 53 | // 54 | static void disableBridgeOutput () 55 | { 56 | LL_GPIO_ResetOutputPin(bridgeDriverControlPort1, phaseAControlPin); 57 | LL_GPIO_ResetOutputPin(bridgeDriverControlPort1, phaseBControlPin); 58 | LL_GPIO_ResetOutputPin(bridgeDriverControlPort2, phaseCControlPin); 59 | } 60 | 61 | static void enableBridgeOutput () 62 | { 63 | LL_GPIO_SetOutputPin(bridgeDriverControlPort1, phaseAControlPin); 64 | LL_GPIO_SetOutputPin(bridgeDriverControlPort1, phaseBControlPin); 65 | LL_GPIO_SetOutputPin(bridgeDriverControlPort2, phaseCControlPin); 66 | } 67 | 68 | // 69 | // These provide the present state of the physical push-buttons 70 | // 71 | static bool onBoardButtonIsPressed() 72 | { return (LL_GPIO_IsInputPinSet(onBoardPushButtonPort, onBoardpushButtonPin) == 1U); } 73 | static bool externalButtonIsPressed() 74 | { return (LL_GPIO_IsInputPinSet(externalPushButtonPort, externalPushButtonPin) == 0U); } 75 | 76 | // 77 | // These control the LEDs. 78 | // 79 | static void turnStatusLEDOff() { LL_GPIO_ResetOutputPin(statusLEDPort, statusLEDPin ); } 80 | static void turnStatusLEDOn() { LL_GPIO_SetOutputPin(statusLEDPort, statusLEDPin ); } 81 | static void toggleStatusLED() { LL_GPIO_TogglePin(statusLEDPort, statusLEDPin ); } 82 | static void turnTimingLEDOff() { LL_GPIO_ResetOutputPin(timingLEDPort, timingLEDPin ); } 83 | static void turnTimingLEDOn() { LL_GPIO_SetOutputPin(timingLEDPort, timingLEDPin ); } 84 | static void toggleTimingLED() { LL_GPIO_TogglePin(timingLEDPort, timingLEDPin ); } 85 | static void turnTriggerLEDOff() { LL_GPIO_ResetOutputPin(triggerLEDPort, triggerLEDPin ); } 86 | static void turnTriggerLEDOn() { LL_GPIO_SetOutputPin(triggerLEDPort, triggerLEDPin ); } 87 | static void toggleTriggerLED() { LL_GPIO_TogglePin(triggerLEDPort, triggerLEDPin ); } 88 | 89 | private: 90 | 91 | // 92 | // These initialize the various types of GPIOs. 93 | // 94 | void initializeDigitalOutputs(); 95 | void initializeDigitalInputs(); 96 | void initializeAnalogPins(); 97 | void initializeTimerPins(); 98 | void initializeUARTPins(); 99 | void initializeI2CPins(); 100 | }; 101 | 102 | // 103 | // We create a single instance of this class that may be referenced 104 | // globally. 105 | // 106 | extern GPIOInterface theGPIOInterface; 107 | -------------------------------------------------------------------------------- /src/hw_io/i2c_interface.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the interface to the processor's I2C bus 30 | // 31 | // At present, this is a very simply interface that only supports writing 32 | // to devices on the bus. 33 | // 34 | // This is a polling interface. Some of the calls may take a while to return. 35 | // 36 | //////////////////////////////////////////////////////////////////////////////// 37 | #pragma once 38 | 39 | #include "global_definitions.h" 40 | #include "processor.h" 41 | 42 | class I2CInterface 43 | { 44 | public: 45 | I2CInterface(); 46 | ~I2CInterface() {}; 47 | 48 | // 49 | // This prepares the I2C interface for operation. 50 | // 51 | void initializeI2CInterface(); 52 | 53 | // 54 | // This writes a buffer of bytes to an I2C device. The device address 55 | // should be in an 8 bit form. In other words, the LSB should not be 56 | // part of the device address. 57 | // 58 | void writeToI2CDevice( 59 | const uint8_t deviceAddress, 60 | const uint8_t *const dataToSend, 61 | const uint32_t numBytesToSend); 62 | 63 | private: 64 | 65 | // 66 | // These manage the portions of the transfer. 67 | // 68 | bool sendAddress(const uint8_t deviceAddress, const bool isWrite); 69 | bool sendData(const uint8_t *const dataToSend, const uint8_t numBytesToSend); 70 | bool waitForIdleBus(); 71 | bool waitForStartSent(); 72 | bool waitForByteSent(); 73 | 74 | }; 75 | 76 | // 77 | // We create a single instance of this class that may be referenced 78 | // globally. 79 | // 80 | extern I2CInterface theI2CInterface; 81 | -------------------------------------------------------------------------------- /src/hw_io/physical_inputs.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the interfaces to physical processor input controls. This include 30 | // items such as push-buttons and a speed control knob. 31 | // 32 | //////////////////////////////////////////////////////////////////////////////// 33 | #pragma once 34 | 35 | #include "debouncer.h" 36 | #include "global_definitions.h" 37 | 38 | class PhysicalInputs 39 | { 40 | public: 41 | PhysicalInputs(); 42 | ~PhysicalInputs() {}; 43 | 44 | // 45 | // This prepares the various physical input devices for operation. 46 | // 47 | void initializePhysicalInputs(); 48 | 49 | // 50 | // This updates the push-button states. It should be called at a periodic rate 51 | // so that it may debounce the buttons. 52 | // 53 | void updatePushButtons(); 54 | 55 | // 56 | // These indicate if a push-button input is pressed. This will be true 57 | // only on the first call after updatePushButton determines that the button is 58 | // pressed. Note that a button press is declared when the button is released. 59 | // If the button is pushed and held, this will not return true. In button-hold 60 | // cases, calls to pushButtonIsHeld eventually will return true. 61 | // 62 | bool onboardPushButtonIsPressed() { return onboardButtonState.buttonIsPressed(); }; 63 | bool externalPushButtonIsPressed() { return externalButtonState.buttonIsPressed(); }; 64 | 65 | // 66 | // These indicate if a push button is held. Again, this will be true on only 67 | // the first call after updatePushButton determines that the button is 68 | // held. 69 | // 70 | bool onboardPushButtonIsHeld() { return onboardButtonState.buttonIsHeld(); }; 71 | bool externalPushButtonIsHeld() { return externalButtonState.buttonIsHeld(); }; 72 | 73 | // 74 | // This resets the speed command reported counts back to zero. 75 | // 76 | void resetSpeedCommand(); 77 | 78 | // 79 | // This provides the present speed command input, in unit-less signed ticks. 80 | // 81 | int32_t getPresentSpeedCommandCounts(); 82 | 83 | private: 84 | 85 | // 86 | // These items are used to interface with on-board and external push-buttons. 87 | // 88 | debouncer onboardButtonState; 89 | debouncer externalButtonState; 90 | 91 | // 92 | // Our encoder timer wraps when the counter hits its limits. We don't 93 | // want to propagate that behavior, so we keep a logical counter that 94 | // we return to the consumer which we clamp. 95 | // 96 | int32_t encoderCommandCounts; 97 | int32_t lastEncoderCounts; 98 | }; 99 | 100 | // 101 | // We create a single instance of this class that may be referenced 102 | // globally. 103 | // 104 | extern PhysicalInputs thePhysicalInputs; 105 | -------------------------------------------------------------------------------- /src/hw_io/pwm_interface.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the interface to the processor's PWM generator 30 | // 31 | // This class controls a fairly "textbook" PMSM motor drive center-based 32 | // PWM. It supports 3 complimentary outputs with a blanking period (AKA dead 33 | // band). In addition it generates a signal to start ADC sampling at the center 34 | // of the PWM pulse-train. It is up to other code to configure the IO pins, etc. 35 | // 36 | //////////////////////////////////////////////////////////////////////////////// 37 | #pragma once 38 | 39 | #include "global_definitions.h" 40 | #include "processor.h" 41 | 42 | namespace PWMConsts 43 | { 44 | // 45 | // This defines the absolute range of the duty cycle commands. Duty 46 | // cycles are provided as a percentage. For example if a 30% duty cycle 47 | // value is desired, a value of 0.3 should be provided. 48 | // 49 | const dutyCycle_pct minDutyCycleCommand = 0.0F; 50 | const dutyCycle_pct maxDutyCycleCommand = 1.0F; 51 | 52 | // 53 | // This is the nominal duty cycle that is assumed to result in a phase 54 | // current that is close to 0 amps. 55 | // 56 | const dutyCycle_pct nominalDutyCycle = 0.5F; 57 | } 58 | 59 | class PWMInterface 60 | { 61 | public: 62 | PWMInterface(); 63 | ~PWMInterface() {}; 64 | 65 | // 66 | // This prepares the PWM interface for operation. The PWM outputs 67 | // are disabled when this returns. The PWM limit is defined as a 68 | // percentage from 0.0 to 1.0. This limit is applied to both the 69 | // maximum and minimum duty cycle. For example, if a limit of 0.1 (10%) 70 | // is provided, the duty cycle commands will be allowed to range from 71 | // 0.1 to 0.9 (10% to 90%). 72 | // 73 | void initializePWMInterface( 74 | const frequency_Hz desiredPWMCarrierFrequency, 75 | const time_s PWMBlankingPeriod, 76 | const dutyCycle_pct dutyCycleLimit_pct); 77 | 78 | // 79 | // This disables the PWM output. All signals are forced low. 80 | // 81 | void disablePWMOutputs(); 82 | 83 | // 84 | // This enables the PWM output. If the nominal value is not desired, the 85 | // duty cycle should be 86 | // duty cycle. 87 | // 88 | void enablePWMOutputs( 89 | const dutyCycle_pct initialDutyCycleA = PWMConsts::nominalDutyCycle, 90 | const dutyCycle_pct initialDutyCycleB = PWMConsts::nominalDutyCycle, 91 | const dutyCycle_pct initialDutyCycleC = PWMConsts::nominalDutyCycle); 92 | 93 | // 94 | // This commands a duty cycle for each PWM phase. Each duty cycle 95 | // is provided as a percentage. The nominal is 0.0 to 1.0 (0% to 96 | // 100%). The dutyCycleLimit_pct provided when the interface was 97 | // initialized will be enforced. 98 | // 99 | void setPWMDutyCycles( 100 | const dutyCycle_pct desiredDutyCycleA, 101 | const dutyCycle_pct desiredDutyCycleB, 102 | const dutyCycle_pct desiredDutyCycleC); 103 | 104 | // 105 | // These provide access to the PWM state and the last commanded duty cycles. 106 | // 107 | bool thePWMsAreEnabled() { return pwmsAreEnabled; } 108 | dutyCycle_pct getLastDutyACommand() { return lastDutyACommand; } 109 | dutyCycle_pct getLastDutyBCommand() { return lastDutyBCommand; } 110 | dutyCycle_pct getLastDutyCCommand() { return lastDutyCCommand; } 111 | 112 | private: 113 | 114 | // 115 | // These latch the PWM parameters after they have been converted from 116 | // the units provided in the interface to the count values required by 117 | // the hardware. 118 | // 119 | bool pwmsAreEnabled; 120 | float32_t dutyPctToCountsConversion; 121 | uint32_t nominalDutyCommand_counts; 122 | uint32_t minDutyCommand_counts; 123 | uint32_t maxDutyCommand_counts; 124 | 125 | // 126 | // We latch the last PWM command as a convenience for the consumer. 127 | // 128 | dutyCycle_pct lastDutyACommand; 129 | dutyCycle_pct lastDutyBCommand; 130 | dutyCycle_pct lastDutyCCommand; 131 | }; 132 | 133 | // 134 | // We create a single instance of this class that may be referenced 135 | // globally. 136 | // 137 | extern PWMInterface thePWMInterface; 138 | 139 | -------------------------------------------------------------------------------- /src/hw_io/tick_timers.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Provides a number of timer utilities 30 | // 31 | // This class provides a number of time bases and utilities for using them. 32 | // The highest precision timer is implemented using a processor tick timer and 33 | // is always available. The lower precision timers are based off of the 34 | // RTOS scheduler's timer and are only available when the RTOS is running. 35 | // 36 | //////////////////////////////////////////////////////////////////////////////// 37 | #pragma once 38 | 39 | #include "global_definitions.h" 40 | 41 | namespace TimerDefs 42 | { 43 | // 44 | // These are the various timer frequencies and periods. 45 | // 46 | const float32_t highResTimerFrequency_Hz = 1000000.0F; 47 | const float32_t medResTimerFrequency_Hz = 1000.0F; 48 | const float32_t lowResTimerFrequency_Hz = 1.0F; 49 | const float32_t highResTimerPeriod_sec = 1.0F / highResTimerFrequency_Hz; 50 | const float32_t medResTimerPeriod_sec = 1.0F / medResTimerFrequency_Hz; 51 | const float32_t lowResTimerPeriod_sec = 1.0F / lowResTimerFrequency_Hz; 52 | } 53 | 54 | class TickTimers 55 | { 56 | public: 57 | TickTimers(); 58 | ~TickTimers() {}; 59 | 60 | // 61 | // This initializes the timers and starts the high precision timer. 62 | // 63 | void initTimers(); 64 | 65 | // 66 | // These get the available timers (high, medium, and low resolution). 67 | // The RTOS scheduler must be running for the medium and low resolution 68 | // timers to operate. 69 | // 70 | tickTime_us getHighResTime(); 71 | tickTime_ms getMedResTime(); 72 | tickTime_s getLowResTime(); 73 | 74 | // 75 | // These provide delta-times at the available resolutions. 76 | // 77 | tickTime_us getHighResDelta(const tickTime_us fromTime); 78 | tickTime_ms getMedResDelta(const tickTime_ms fromTime); 79 | tickTime_s getLowResDelta(const tickTime_s fromTime); 80 | 81 | // 82 | // This performs a polling delay using the high resolution timer. It does 83 | // not yield the processor (nor does it require the RTOS scheduler to be 84 | // operating). 85 | // 86 | void performPollingDelay(const tickTime_us timeToDelay); 87 | }; 88 | 89 | // 90 | // We create a single instance of this class that may be referenced 91 | // globally. 92 | // 93 | extern TickTimers theTimers; 94 | 95 | extern "C" 96 | { 97 | // 98 | // Some of the time bases are created by hooking the RTOS tick timer callback. 99 | // 100 | void vApplicationTickHook(void); 101 | } 102 | -------------------------------------------------------------------------------- /src/hw_io/uart_interface.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the interface to the processor's test support UART (serial interface) 30 | // 31 | // The UART is used to send commands to the processor and for it to output 32 | // status and data. 33 | // 34 | //////////////////////////////////////////////////////////////////////////////// 35 | #pragma once 36 | 37 | #include "global_definitions.h" 38 | #include "processor.h" 39 | 40 | class UARTInterface 41 | { 42 | public: 43 | UARTInterface(); 44 | ~UARTInterface() {}; 45 | 46 | // 47 | // This prepares the UART interface for operation. Once this is called 48 | // serial data may be to to/from the UART. 49 | // 50 | void initializeUARTInterface(); 51 | 52 | // 53 | // This sends data out the UART. This will return before the data is 54 | // actually transferred. The data transfer is managed internally. 55 | // 56 | void sendToUART(uint8_t *const dataToSend, uint32_t numberBytesToSend); 57 | 58 | private: 59 | 60 | // 61 | // This will poll until a previously commanded transfer has 62 | // completed. 63 | // 64 | void waitForLastTransferToComplete(); 65 | 66 | }; 67 | 68 | #ifdef __cplusplus 69 | extern "C" { 70 | #endif 71 | 72 | // 73 | // This queues data for output via the UART. This exists to support 74 | // printf character output. 75 | // 76 | void sendCharsToUart(char *const dataToSend, uint32_t numberCharsToSend); 77 | 78 | #ifdef __cplusplus 79 | } 80 | #endif 81 | 82 | // 83 | // We create a single instance of this class that may be referenced 84 | // globally. 85 | // 86 | extern UARTInterface theUARTInterface; 87 | -------------------------------------------------------------------------------- /src/main/FreeRTOSConfig.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.3.1 3 | * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | #ifndef FREERTOS_CONFIG_H 29 | #define FREERTOS_CONFIG_H 30 | 31 | /*----------------------------------------------------------- 32 | * Application specific definitions. 33 | * 34 | * These definitions should be adjusted for your particular hardware and 35 | * application requirements. 36 | * 37 | * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE 38 | * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. 39 | * 40 | * See http://www.freertos.org/a00110.html 41 | *----------------------------------------------------------*/ 42 | 43 | #include 44 | #include "system_stm32f4xx.h" 45 | 46 | // 47 | // There is a "chicken-and-egg" issue with the way TickType_t is defined. 48 | // We add this to work around knowing that in our case, the tick type is a 49 | // uint32_t. 50 | // 51 | #ifndef TickType_t 52 | typedef uint32_t TickType_t; 53 | #endif 54 | 55 | #define configUSE_PREEMPTION 1 56 | #define configUSE_IDLE_HOOK 0 57 | #define configUSE_TICK_HOOK 1 58 | #define configCPU_CLOCK_HZ ( SystemCoreClock ) 59 | #define configTICK_RATE_HZ ( ( TickType_t ) 1000 ) 60 | #define configMAX_PRIORITIES ( 10 ) 61 | #define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) 62 | #define configTOTAL_HEAP_SIZE ( ( size_t ) ( 16384 ) ) 63 | #define configMAX_TASK_NAME_LEN ( 10 ) 64 | #define configUSE_TRACE_FACILITY 0 65 | #define configUSE_16_BIT_TICKS 0 66 | #define configIDLE_SHOULD_YIELD 1 67 | #define configUSE_MUTEXES 1 68 | #define configQUEUE_REGISTRY_SIZE 8 69 | #define configCHECK_FOR_STACK_OVERFLOW 2 70 | #define configUSE_RECURSIVE_MUTEXES 1 71 | #define configUSE_MALLOC_FAILED_HOOK 1 72 | #define configUSE_APPLICATION_TASK_TAG 0 73 | #define configUSE_COUNTING_SEMAPHORES 1 74 | #define configGENERATE_RUN_TIME_STATS 0 75 | #define configSUPPORT_STATIC_ALLOCATION 1 76 | #define configSUPPORT_DYNAMIC_ALLOCATION 1 77 | #define configENABLE_FPU 1 78 | #define configAPPLICATION_ALLOCATED_HEAP 1 79 | 80 | 81 | 82 | /* Co-routine definitions. */ 83 | #define configUSE_CO_ROUTINES 0 84 | #define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) 85 | 86 | /* Software timer definitions. */ 87 | #define configUSE_TIMERS 0 88 | #define configTIMER_TASK_PRIORITY ( 2 ) 89 | #define configTIMER_QUEUE_LENGTH 5 90 | #define configTIMER_TASK_STACK_DEPTH ( configMINIMAL_STACK_SIZE * 2 ) 91 | 92 | /* Set the following definitions to 1 to include the API function, or zero 93 | to exclude the API function. */ 94 | #define INCLUDE_vTaskPrioritySet 1 95 | #define INCLUDE_uxTaskPriorityGet 1 96 | #define INCLUDE_vTaskDelete 1 97 | #define INCLUDE_vTaskCleanUpResources 1 98 | #define INCLUDE_vTaskSuspend 1 99 | #define INCLUDE_vTaskDelayUntil 1 100 | #define INCLUDE_vTaskDelay 1 101 | 102 | /* Cortex-M specific definitions. */ 103 | #ifdef __NVIC_PRIO_BITS 104 | /* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */ 105 | #define configPRIO_BITS __NVIC_PRIO_BITS 106 | #else 107 | #define configPRIO_BITS 4 /* 15 priority levels */ 108 | #endif 109 | 110 | /* The lowest interrupt priority that can be used in a call to a "set priority" 111 | function. */ 112 | #define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 0x0f 113 | 114 | /* The highest interrupt priority that can be used by any interrupt service 115 | routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL 116 | INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER 117 | PRIORITY THAN THIS! (higher priorities are lower numeric values. */ 118 | #define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 10 119 | 120 | /* Interrupt priorities used by the kernel port layer itself. These are generic 121 | to all Cortex-M ports, and do not rely on any particular library functions. */ 122 | #define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) 123 | /* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!! 124 | See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */ 125 | #define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) 126 | 127 | /* Normal assert() semantics without relying on the provision of an assert.h 128 | header file. */ 129 | #define configASSERT( x ) if( ( x ) == 0 ) { taskDISABLE_INTERRUPTS(); for( ;; ); } 130 | 131 | /* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS 132 | standard names. */ 133 | #define vPortSVCHandler SVC_Handler 134 | #define xPortPendSVHandler PendSV_Handler 135 | #define xPortSysTickHandler SysTick_Handler 136 | 137 | #endif /* FREERTOS_CONFIG_H */ 138 | -------------------------------------------------------------------------------- /src/main/background_task.cpp: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Lowest priority application task 30 | // 31 | // This task performs background activities that do not have any particular 32 | // timing requirement. The only thing lower priority is the OS idle task. 33 | // 34 | //////////////////////////////////////////////////////////////////////////////// 35 | #include "background_task.h" 36 | 37 | #include "data_logger.h" 38 | #include "os_interface.h" 39 | #include "uart_interface.h" 40 | 41 | #include 42 | 43 | // 44 | // We create the class that manages the interface with the UART. 45 | // 46 | UARTInterface theUARTInterface; 47 | 48 | // 49 | // We print these at startup. 50 | // 51 | extern volatile int buildCount; 52 | extern volatile char absoluteBuildTime[]; 53 | 54 | //////////////////////////////////////////////////////////////////////////////// 55 | // 56 | // Class constructor 57 | // 58 | //////////////////////////////////////////////////////////////////////////////// 59 | BackgroundTask::BackgroundTask() 60 | { 61 | } 62 | 63 | //////////////////////////////////////////////////////////////////////////////// 64 | // 65 | // Performs initializations required before the scheduler is started 66 | // 67 | //////////////////////////////////////////////////////////////////////////////// 68 | void BackgroundTask::initBackgroundTask() 69 | { 70 | // 71 | // We register this task with the OS. 72 | // 73 | theOSInterface.createTask( 74 | theBackgroundTask.backgroundTaskEntryPoint, 75 | taskInfo::BackgroundTaskPriority, 76 | taskInfo::BackgroundTaskStackSizeLongwords, 77 | this, 78 | taskInfo::BackgroundTaskName); 79 | } 80 | 81 | //////////////////////////////////////////////////////////////////////////////// 82 | // 83 | // Static entry point required by the OS 84 | // 85 | // This should be provided a pointer to the actual instance of the 86 | // task class. It will call the main loop by reference. 87 | // 88 | //////////////////////////////////////////////////////////////////////////////// 89 | void BackgroundTask::backgroundTaskEntryPoint(void * const thisPtr) 90 | { 91 | if (thisPtr != nullptr) 92 | { 93 | // 94 | // We call the main loop using the passed in "this" pointer. 95 | // 96 | BackgroundTask *const thisTaskPointer = 97 | reinterpret_cast(thisPtr); 98 | thisTaskPointer->BackgroundTaskLoop(); 99 | } 100 | 101 | // 102 | // This call should not get here. If it does, we'll loop with a delay 103 | // to support debugging. 104 | // 105 | while (true) 106 | { 107 | OSInterface::delay(1000U); 108 | } 109 | } 110 | 111 | //////////////////////////////////////////////////////////////////////////////// 112 | // 113 | // Main loop for the Background task 114 | // 115 | // This is invoked by the static task entry point. It is scheduled by 116 | // the RTOS and never exits 117 | // 118 | //////////////////////////////////////////////////////////////////////////////// 119 | void BackgroundTask::BackgroundTaskLoop() 120 | { 121 | 122 | // 123 | // We initialize the test support UART. 124 | // 125 | theUARTInterface.initializeUARTInterface(); 126 | 127 | // 128 | // We display build date, time, etc. 129 | // 130 | printBuildInfo(); 131 | 132 | // 133 | // This is the main background loop. 134 | // 135 | while (true) 136 | { 137 | OSInterface::delay(2U); 138 | 139 | // 140 | // We print the contents of the data log if there is data in it. 141 | // 142 | theDataLogger.printDataLogBuffer(); 143 | 144 | // 145 | // We print the low rate data if there is any to print. 146 | // 147 | theDataLogger.printLowRateItems(); 148 | } 149 | } 150 | 151 | //////////////////////////////////////////////////////////////////////////////// 152 | // 153 | // Prints general build information 154 | // 155 | //////////////////////////////////////////////////////////////////////////////// 156 | void BackgroundTask::printBuildInfo() 157 | { 158 | printf("\r\n\n"); 159 | printf(" Yet Another Motor Drive \r\n"); 160 | printf(" Copyright (c) 2021, Michael F. Kaufman\r\n"); 161 | printf(" 0xEB90, 0x2152-yet. \r\n\n"); 162 | 163 | printf("Build time : %s\r\n", absoluteBuildTime); 164 | printf("Build count : %d\r\n\n", static_cast(buildCount)); 165 | 166 | fflush(stdout); 167 | } 168 | 169 | -------------------------------------------------------------------------------- /src/main/background_task.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Lowest priority application task 30 | // 31 | // This task performs background activities that do not have any particular 32 | // timing requirement. The only thing lower priority is the OS idle task. 33 | // 34 | //////////////////////////////////////////////////////////////////////////////// 35 | #pragma once 36 | 37 | class BackgroundTask 38 | { 39 | public: 40 | BackgroundTask(); 41 | ~BackgroundTask() {}; 42 | 43 | // 44 | // This performs initializations required before the scheduler is 45 | // started. 46 | // 47 | void initBackgroundTask(); 48 | 49 | // 50 | // This is a static function intended to be provided to the OS at 51 | // initialization. 52 | // 53 | static void backgroundTaskEntryPoint(void * const thisPtr); 54 | 55 | private: 56 | 57 | // 58 | // This is the task's main loop. 59 | // 60 | void BackgroundTaskLoop(); 61 | 62 | // 63 | // This prints build information at startup. 64 | // 65 | void printBuildInfo(); 66 | 67 | }; 68 | 69 | // 70 | // We create a single instance of this class that may be referenced 71 | // globally. 72 | // 73 | extern BackgroundTask theBackgroundTask; 74 | -------------------------------------------------------------------------------- /src/main/buildcnt.cpp: -------------------------------------------------------------------------------- 1 | // buildcnt.cpp 2 | // Auto Generated 3 | volatile int buildCount = 56; 4 | volatile char absoluteBuildTime[] = __TIMESTAMP__; 5 | -------------------------------------------------------------------------------- /src/main/config.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the software configuration options. Note this file does not 30 | // define motor specific constants (those may be found in motor_constants.h). 31 | // 32 | //////////////////////////////////////////////////////////////////////////////// 33 | #pragma once 34 | #include "global_definitions.h" 35 | #include "gpio_interface.h" 36 | 37 | namespace SystemConfig 38 | { 39 | // 40 | // The software may be configured to "snoop" data provided by another 41 | // motor controller. In this configuration, the software will not output 42 | // PWMs or motor enable signals. While "snooping" another controller, the 43 | // software will still sample and process all of it its inputs. When snooping 44 | // another controller, the software will utilize an external synchronization 45 | // pulse to control when the ADC's sample their inputs (normally, the 46 | // software configures the ADC synchronize its samples with the software's 47 | // locally generated PWM signals). 48 | // 49 | const bool snoopRemoteMotorController = false; 50 | 51 | // 52 | // The timing LED can be configured to blink around different events. 53 | // These select which events should blink the LED. Note that we use 54 | // a bitmap so that multiple events may be selected simultaneously. 55 | // 56 | const uint32_t timeNoEvent = 0x00000000U; 57 | const uint32_t timeADCInterrupt = 0x00000001U; 58 | const uint32_t timeMotorControlTask = 0x00000002U; 59 | const uint32_t timeBackgroundTask = 0x00000004U; 60 | const uint32_t timeStateChanges = 0x00000008U; 61 | 62 | const uint32_t eventsToTimeWithLED = timeADCInterrupt; 63 | 64 | // 65 | // These are helper methods for controlling the timing LED. The 66 | // code responsible for a given event should bracket the event 67 | // with these calls while passing in the appropriate event identifier. 68 | // 69 | inline void turnTimingLEDOnForEvent (const uint32_t desiredEvent) 70 | { 71 | if ((desiredEvent & eventsToTimeWithLED) != 0U) 72 | { 73 | GPIOInterface::turnTimingLEDOn(); 74 | } 75 | } 76 | 77 | inline void turnTimingLEDOffForEvent (const uint32_t desiredEvent) 78 | { 79 | if ((desiredEvent & eventsToTimeWithLED) != 0U) 80 | { 81 | GPIOInterface::turnTimingLEDOff(); 82 | } 83 | } 84 | } 85 | -------------------------------------------------------------------------------- /src/main/data_logger.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This class logs and outputs data for test support. At present, two 30 | // forms of logging are provided: The first log is a data buffer of N data 31 | // items are stored at a high rate and then printed to the console once 32 | // the buffer is full. The second "log" comprises two DAC outputs that 33 | // are updated after each motor drive state machine update. 34 | // 35 | // Note that data is always sent to the DAC every update. 36 | // 37 | // In addition to the above logs, a number of general status items are printed 38 | // to the console at a low rate whenever high speed log buffer data is not 39 | // being printed. 40 | // 41 | // This data log class is added as a "friend" to each other system class. 42 | // This allows this class to access private data for logging purposes. 43 | // 44 | //////////////////////////////////////////////////////////////////////////////// 45 | #pragma once 46 | 47 | #include "global_definitions.h" 48 | #include "motor_constants.h" 49 | 50 | class dataLogger 51 | { 52 | public: 53 | dataLogger(); 54 | ~dataLogger() {}; 55 | 56 | // 57 | // This prepares the data log for operation. 58 | // 59 | void initializeDataLog(); 60 | 61 | // 62 | // This should be called at the end of each motor state machine update 63 | // so that logging data may be processed. 64 | // 65 | void updateDataLog(); 66 | 67 | // 68 | // This is used to start the buffering of log data. Once the buffer is 69 | // full its contents will be printed. This needs to be called every 70 | // time a buffer of data is required. 71 | // 72 | void startBufferingData() { saveLogData = true; } 73 | 74 | // 75 | // This prints the contents of the data log buffer to the console. This 76 | // should be called periodically by a low priority task. Note that this 77 | // may block the caller for an extended period of time if there is a buffer 78 | // of data to print. 79 | // 80 | void printDataLogBuffer(); 81 | 82 | // 83 | // This prints low rate items. These are printed to the console periodically 84 | // whenever there is not something else going out. 85 | // 86 | void printLowRateItems(); 87 | 88 | private: 89 | 90 | // 91 | // These are used to track the contents of the data log buffer. 92 | // 93 | struct logDataStruct 94 | { 95 | tickTime_us time; 96 | float32_t item1; 97 | float32_t item2; 98 | float32_t item3; 99 | float32_t item4; 100 | float32_t item5; 101 | float32_t item6; 102 | float32_t item7; 103 | float32_t item8; 104 | }; 105 | 106 | static const uint32_t itemsToBuffer = 100U; 107 | logDataStruct logData[itemsToBuffer]; 108 | uint32_t dataLogIndex; 109 | bool saveLogData; 110 | bool dataInLog; 111 | 112 | // 113 | // These support downsampling from the maximum update rate. 114 | // 115 | static const uint32_t downsampleFrames = 0U; 116 | uint32_t downsampleCounter; 117 | 118 | // 119 | // These define periodic items that are printed at a low 120 | // rate whenever there is not something else going to the 121 | // console. 122 | // 123 | static const uint32_t lowRateItemDownsample = 15000U; 124 | uint32_t lowRateItemDownsampleCounter; 125 | uint32_t lowRateItemUpdateCounter; 126 | uint32_t lastLowRateItemUpdateCounter; 127 | tickTime_us lowRateUpdateTime; 128 | float32_t lowRateItem1; 129 | float32_t lowRateItem2; 130 | float32_t lowRateItem3; 131 | float32_t lowRateItem4; 132 | float32_t lowRateItem5; 133 | 134 | // 135 | // These are used to display the motor shaft angle on 136 | // an LED display. 137 | // 138 | void displayMotorAngle(); 139 | electricalAngle_rad angleForDisplay; 140 | electricalSpeed_RPM speedForDisplay; 141 | electricalAngle_rad reducedAngle; 142 | tickTime_ms lastDisplayUpdateTime; 143 | uint8_t lastPositionLED; 144 | 145 | }; 146 | 147 | // 148 | // We create a single instance of this class that may be referenced 149 | // globally. 150 | // 151 | extern dataLogger theDataLogger; 152 | -------------------------------------------------------------------------------- /src/main/global_constants.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Provides constants common to the entire application 30 | // 31 | //////////////////////////////////////////////////////////////////////////////// 32 | #pragma once 33 | #include "global_definitions.h" 34 | 35 | namespace GlobalConstants 36 | { 37 | // 38 | // These items are general constants. 39 | // 40 | const float32_t Pi = 3.1415926F; 41 | const float32_t twoPi = 2.0F * Pi; 42 | const float32_t PiOver2 = Pi / 2.0F; 43 | const float32_t radiansToDegrees = (360.0F / twoPi); 44 | const float32_t degreesToRadians = (twoPi / 360.0F); 45 | 46 | 47 | const float32_t sqrtOf3 = 1.732051F; 48 | const float32_t oneOverSqrt3 = 1.0F / sqrtOf3; 49 | const float32_t sqrt3Over2 = sqrtOf3 / 2.0F; 50 | const float32_t sqrt3Over3 = sqrtOf3 / 3.0F; 51 | 52 | const float32_t oneThird = 1.0F / 3.0F; 53 | const float32_t twoThirds = 2.0F / 3.0F; 54 | 55 | const time_s secondsPerMinute = 60.0F; 56 | const float32_t millisecondsPerSecond = 1000.0F; 57 | const float32_t secondsPerMillisecone = 1.0F / millisecondsPerSecond; 58 | 59 | const float32_t revolutionsPerRPM = 1000.0F; 60 | } 61 | 62 | -------------------------------------------------------------------------------- /src/main/global_definitions.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Provides type definitions common to the entire application 30 | // 31 | //////////////////////////////////////////////////////////////////////////////// 32 | #pragma once 33 | #include 34 | 35 | // 36 | // These define floating point types. For the present processor, single 37 | // precision float is preferred as the processor can perform basic floating 38 | // point operations (add, multiply, etc.) in a single processor cycle. Double 39 | // precision requires software float point libraries. 40 | // 41 | typedef float float32_t; 42 | typedef double float64_t; 43 | 44 | // 45 | // These type defines define basic engineering units. These are all defined 46 | // such that a value of 1.0 refers to 1.0 units. 47 | // 48 | typedef float32_t volts; 49 | typedef float32_t amperes; 50 | typedef float32_t resistance_Ohms; 51 | typedef float32_t inductance_H; 52 | 53 | // 54 | // This is used to define motor back EMF coefficients. 55 | // 56 | typedef float32_t voltsPer1000MechanicalRPM; 57 | 58 | // 59 | // These items define angles and angular rates. 60 | // 61 | typedef float32_t electricalAngle_rad; 62 | typedef float32_t electricalAngle_deg; 63 | typedef float32_t electricalSpeed_RPS; 64 | typedef float32_t electricalSpeed_RPM; 65 | typedef float32_t acceleration_RotationsPerSec2; 66 | 67 | // 68 | // Current controller output commands are expressed as duty cycles. These 69 | // express what percentage of the available DC bus should be used to control 70 | // the motor. Initially, the duty cycles are signed values that range 71 | // nominally from -1.0 to 1.0. In this form a value of zero indicates that 72 | // none of the bus should be used, a value of -1 indicates that the bus should 73 | // be driven in its full negative direction, and a value of +1 indicates that the 74 | // bus should be driven in its full positive direction. 75 | // 76 | typedef float32_t signedDutyCycle; 77 | 78 | // 79 | // The final form of the current controller output command is an unsigned 80 | // duty cycle percentage that ranges from 0.0 to 1.0. This commands the actual 81 | // duty cycle of each PWM signal that is sent to the bridge driver. A value 82 | // of zero commands a 0% duty cycle while a value of 1.0 commands a 100% 83 | // duty cycle. Note that limits are usually placed on the final commands that 84 | // disallow 0% or 100% duty cycles. 85 | // 86 | typedef float32_t dutyCycle_pct; 87 | 88 | // 89 | // These are for time values. These include frequencies, "real" time periods 90 | // (engineering unit times), and tick times. Tick times are integer 91 | // values that start at zero and increment at the particular time period. 92 | // If the system runs for a long enough period, the tick timers will roll- 93 | // over. 94 | // 95 | typedef float32_t frequency_Hz; 96 | typedef float32_t time_s; 97 | typedef float32_t time_ms; 98 | typedef float32_t time_us; 99 | 100 | typedef uint32_t tickTime_s; 101 | typedef uint32_t tickTime_ms; 102 | typedef uint32_t tickTime_us; 103 | typedef uint32_t bitsPerSecond; 104 | 105 | // 106 | // These define types of other items. 107 | // 108 | typedef uint32_t bits; 109 | -------------------------------------------------------------------------------- /src/main/os_interface.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This class provides a very thin wrapper around the RTOS functions that we 30 | // use. It also includes definitions for our tasking configuration and provides 31 | // some utility functions required by the RTOS. 32 | // 33 | //////////////////////////////////////////////////////////////////////////////// 34 | #pragma once 35 | 36 | #include "FreeRTOS.h" 37 | #include "global_definitions.h" 38 | #include "task.h" 39 | 40 | // 41 | // This namespace defines parameters related to the various tasks. 42 | // 43 | namespace taskInfo 44 | { 45 | // 46 | // These define the configuration of each task. 47 | // 48 | const uint32_t MotorControlTaskStackSizeLongwords = 1024U; 49 | const uint32_t MotorControlTaskPriority = configMAX_PRIORITIES - 4U; 50 | const char *const MotorControlTaskName = "MtrCtrl"; 51 | 52 | const uint32_t BackgroundTaskStackSizeLongwords = 1024U; 53 | const uint32_t BackgroundTaskPriority = MotorControlTaskPriority - 1U; 54 | const char *const BackgroundTaskName = "BkGnd"; 55 | } 56 | 57 | 58 | class OSInterface 59 | { 60 | public: 61 | OSInterface(); 62 | ~OSInterface() {}; 63 | 64 | // 65 | // This should be called by each task to create itself before the OS 66 | // scheduler is started. This requires the following items: 67 | // A function pointer to the task's static entry point 68 | // The task's priority 69 | // The task's stack size in longwords 70 | // A parameter to pass the static entry point. This is usually the 71 | // task's class "this" pointer. 72 | // A name to give the task 73 | // 74 | void createTask( 75 | TaskFunction_t taskStaticEntryPointPtr, 76 | uint32_t taskPriority, 77 | uint32_t taskStackSize_longwords, 78 | void * const taskParameter, 79 | const char * const taskName); 80 | 81 | // 82 | // This starts the OS scheduler. This method does not return to the 83 | // caller. 84 | // 85 | static void startScheduler(); 86 | 87 | // 88 | // This performs a yielding delay. The calling task sleeps for at least 89 | // the provided time period. 90 | // 91 | static void delay(const time_ms delayTime); 92 | 93 | private: 94 | 95 | 96 | }; 97 | 98 | extern "C" 99 | { 100 | // 101 | // These may be called from within ISRs to mask and restore all system 102 | // interrupts. They should be used with great care and only very briefly. 103 | // Note that if these are called from non-ISRs, the code will likely trap. 104 | // 105 | uint32_t maskAllInterruptsFromISR() __attribute__((naked)); 106 | void restoreInterruptMaskFromISR(uint32_t originalMask) __attribute__((naked)); 107 | 108 | // 109 | // These are hooks and callbacks the RTOS requires. 110 | // 111 | void vApplicationMallocFailedHook(void); 112 | void vApplicationStackOverflowHook(TaskHandle_t pxTask, char *pcTaskName); 113 | void vApplicationGetIdleTaskMemory( 114 | StaticTask_t **ppxIdleTaskTCBBuffer, 115 | StackType_t **ppxIdleTaskStackBuffer, 116 | uint32_t *pulIdleTaskStackSize); 117 | } 118 | 119 | // 120 | // We create a single instance of this class that may be referenced 121 | // globally. 122 | // 123 | extern OSInterface theOSInterface; 124 | -------------------------------------------------------------------------------- /src/motor_drive/angle_estimator_coefficients.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This file provides constants related to sensor-less motor shaft angle 30 | // estimators. 31 | // 32 | // A note on how these were determined: This is a work-in-progress. At 33 | // present, both estimators will determine a useable shaft angle across a 34 | // range of motor speeds. So far, all of this has been done without any 35 | // motor load. It is expected that these values may change based on the 36 | // motor's actual operating environment. 37 | // 38 | // All of the tuning was performed while controlling the motor with an external 39 | // shaft encoder. The "ground truth" angle from the shaft encoder was 40 | // compared with the output from the estimators to determine the appropriate 41 | // coefficients and "adjustment factors" (shaft angle offsets, polynomial 42 | // correction coefficients, etc.) 43 | // 44 | //////////////////////////////////////////////////////////////////////////////// 45 | #pragma once 46 | #include "global_definitions.h" 47 | #include "motor_constants.h" 48 | 49 | namespace angleEstimatorCoefficients 50 | { 51 | // 52 | // These are constants specific to the sliding mode observer. 53 | // 54 | // These are the observers controller gain and filter coefficient. 55 | // 56 | const float32_t slidingControlCurrentErrorLimit = 0.08F; 57 | const float32_t slidingControlGain = 6.0F; 58 | const frequency_Hz smoBackEMFFilterCutoffFrequency = 100.0F; 59 | 60 | // 61 | // The filtering in observer will cause the estimated angle to 62 | // lag the true angle. This varies with the motor's speed. 63 | // We use a polynomial correction to adjust the angle. The polynomial 64 | // coefficients were determined by comparing the motor's true angle to 65 | // the estimated angle at a number of different speeds. 66 | // 67 | const float32_t posSpeedAngleAdjustmentK1 = 1.455E-11F; 68 | const float32_t posSpeedAngleAdjustmentK2 = -4.923E-8F; 69 | const float32_t posSpeedAngleAdjustmentK3 = 0.0002F; 70 | const float32_t posSpeedAngleAdjustmentK4 = 3.6179F; 71 | 72 | const float32_t negSpeedAngleAdjustmentK1 = -6.51E-12F; 73 | const float32_t negSpeedAngleAdjustmentK2 = 2.843E-9F; 74 | const float32_t negSpeedAngleAdjustmentK3 = -0.0001F; 75 | const float32_t negSpeedAngleAdjustmentK4 = -0.3621F; 76 | 77 | // 78 | // These are coefficients associated with the Phase Locked Loop (PLL) 79 | // angle estimator. 80 | // 81 | // This the filter constant used to filter the back EMF estimates. 82 | // 83 | const frequency_Hz pllBackEMFFilterCutoffFrequency = 1000.0F; 84 | 85 | // 86 | // This is the offset used to adjust the PLL estimator's output angle 87 | // so that is properly aligned to the motor's back EMF. This was determined 88 | // by comparing the angle computed by the estimator with an angle measured 89 | // with a motor's encoder. 90 | // 91 | const electricalAngle_rad pllPositiveSpeedShaftAngleOffset = 0.3F; 92 | const electricalAngle_rad pllNegativeSpeedShaftAngleOffset = 93 | pllPositiveSpeedShaftAngleOffset * 2.0F; 94 | } 95 | 96 | -------------------------------------------------------------------------------- /src/motor_drive/motor_controller.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This defines the "outer" motor controller. This contains the entry point 30 | // and external interfaces for the motor controller. 31 | // 32 | // The motor controller has two threads-of-control. There is the high speed 33 | // code that commutates the motor and closes its various loops. There is a lower 34 | // speed task that manages the motor's high-level state machine and also manages 35 | // the interface to the "outside world". The high speed code executes during 36 | // the interrupt that occurs whenever new motor data is available from the ADC. 37 | // The low speed task operates as an endless loop that is scheduled by the 38 | // operating system. 39 | // 40 | //////////////////////////////////////////////////////////////////////////////// 41 | #pragma once 42 | 43 | #include "data_logger.h" 44 | #include "global_definitions.h" 45 | #include "motor_state_machine.h" 46 | 47 | 48 | class MotorController 49 | { 50 | public: 51 | MotorController(); 52 | ~MotorController() {}; 53 | 54 | // 55 | // This prepares the motor controller for operation. This must be called 56 | // before the RTOS scheduler is started. 57 | // 58 | void initializeMotorController(); 59 | 60 | // 61 | // This is the motor controller's high-speed entry point. It is invoked 62 | // by the ISR that services the new-ADC-data-is-available interrupt. 63 | // Most of the actual closed-loop motor control software is invoked by this 64 | // function. 65 | // 66 | void updateMotorController(); 67 | 68 | // 69 | // This is a static function intended to be provided to the OS at 70 | // initialization. It invokes the motor controller's lower speed task. 71 | // 72 | static void motorControlTaskEntryPoint(void * const thisPtr); 73 | 74 | private: 75 | 76 | // 77 | // This is the state machine that performs most of the motor control. 78 | // It runs under the context of an interrupt service routine. 79 | // 80 | motorStateMachine theMotorStateMachine; 81 | 82 | // 83 | // This is the motor controller lower-speed, low priority control task. 84 | // 85 | void motorControlTaskLoop(); 86 | 87 | // 88 | // These are used to change the speed command based on physical command 89 | // inputs. 90 | // 91 | void determineSpeedCommand(); 92 | electricalSpeed_RPM desiredSpeed; 93 | electricalSpeed_RPM lastSpeedCommand; 94 | electricalSpeed_RPM speedCommandOffset; 95 | tickTime_ms speedToggleCommandTime; 96 | tickTime_ms lastSpeedCommandUpdateTime; 97 | 98 | // 99 | // These are used to communicate commands between the controller task 100 | // and the high-speed ISR motor controller. We use a simple circular 101 | // buffer of commands. 102 | // 103 | enum controllerCommands 104 | { 105 | noCommand, 106 | startCommand, 107 | stopCommand, 108 | speedCommand, 109 | startLoggingCommand 110 | }; 111 | 112 | struct motorCommandStruct 113 | { 114 | motorCommandStruct() : 115 | desiredCommand(noCommand), 116 | commandParameter(0.0F) 117 | { 118 | } 119 | 120 | void clearCommand() 121 | { 122 | desiredCommand = noCommand; 123 | commandParameter = 0.0F; 124 | } 125 | 126 | controllerCommands desiredCommand; 127 | float32_t commandParameter; 128 | }; 129 | 130 | void addCommandToBuffer( 131 | const controllerCommands command, const float32_t parameter = 0.0F); 132 | void getNextCommandFromBuffer( 133 | controllerCommands &command, float32_t ¶meter); 134 | 135 | static const uint32_t commandsInBuffer = 10U; 136 | motorCommandStruct commandBuffer[commandsInBuffer]; 137 | volatile uint32_t commandReadIndex; 138 | volatile uint32_t commandWriteIndex; 139 | 140 | // 141 | // These are status items latched by the high speed controller 142 | // that are monitored by the low-speed controller. 143 | // 144 | volatile bool isMotorError; 145 | volatile bool motorIsEnabled; 146 | volatile bool motorIsRunning; 147 | 148 | // 149 | // We make the data logger a friend class so that it can access 150 | // private members for logging. 151 | // 152 | friend class dataLogger; 153 | }; 154 | 155 | extern "C" 156 | { 157 | // 158 | // This shuts off the motor power electronics. This may be called when 159 | // ever an error or fault condition is detected. 160 | // 161 | void shutOffMotor(void); 162 | } 163 | 164 | // 165 | // We create a single instance of this class that may be referenced 166 | // globally. 167 | // 168 | extern MotorController theMotorController; 169 | 170 | 171 | -------------------------------------------------------------------------------- /src/motor_drive/motor_transforms.cpp: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This file implements several transformations that are used in the motor 30 | // control process. 31 | // 32 | //////////////////////////////////////////////////////////////////////////////// 33 | #include "arm_math.h" 34 | #include "global_constants.h" 35 | #include "global_definitions.h" 36 | #include "motor_transforms.h" 37 | 38 | //////////////////////////////////////////////////////////////////////////////// 39 | // 40 | // Class constructor 41 | // 42 | //////////////////////////////////////////////////////////////////////////////// 43 | motorTransforms::motorTransforms() : 44 | referenceSine(0.0F), 45 | referenceCosine(0.0F) 46 | { 47 | } 48 | 49 | //////////////////////////////////////////////////////////////////////////////// 50 | // 51 | // Computes the trigonometric values based on a rotating coordinate frame's 52 | // present angle. 53 | // 54 | //////////////////////////////////////////////////////////////////////////////// 55 | void motorTransforms::provideRotatingFrameAngle ( 56 | const electricalAngle_rad rotatingFrameAngle) 57 | { 58 | // 59 | // We make sure the angle falls in the expected range. 60 | // 61 | float32_t adjustedAngle; 62 | 63 | if (rotatingFrameAngle < 0.0) 64 | { 65 | adjustedAngle = 0.0F; 66 | } 67 | else if (rotatingFrameAngle > GlobalConstants::twoPi) 68 | { 69 | adjustedAngle = GlobalConstants::twoPi; 70 | } 71 | else 72 | { 73 | adjustedAngle = rotatingFrameAngle; 74 | } 75 | 76 | // 77 | // We compute the sines and cosines that are required by the 78 | // transformations between rotating and stationary frames. 79 | // 80 | referenceSine = arm_sin_f32(adjustedAngle); 81 | referenceCosine = arm_cos_f32(adjustedAngle); 82 | } 83 | 84 | //////////////////////////////////////////////////////////////////////////////// 85 | // 86 | // Computes the reduced Clarke Transformation. This transforms 3-phase 87 | // ABC input data into two-phase AlphaBeta data, both in the stationary 88 | // reference frame. This particular implementation assumes one is providing 89 | // A and B phase inputs. Note that the A, B, and C inputs must sum to zero 90 | // for the proper operation of this transform. 91 | // 92 | //////////////////////////////////////////////////////////////////////////////// 93 | void motorTransforms::performReducedClarkeTransformation ( 94 | const float32_t inputA, 95 | const float32_t inputB, 96 | float32_t &resultAlpha, 97 | float32_t &resultBeta) const 98 | { 99 | resultAlpha = inputA; 100 | resultBeta = (inputA + (2.0F * inputB)) * GlobalConstants::oneOverSqrt3; 101 | } 102 | 103 | //////////////////////////////////////////////////////////////////////////////// 104 | // 105 | // Computes the Park Transformation. The Park transform transforms data from 106 | // two-phase AlphaBeta form in the stationary frame to two components DQ of 107 | // a vector in the rotating frame. 108 | // 109 | //////////////////////////////////////////////////////////////////////////////// 110 | void motorTransforms::performParkTransformation ( 111 | const float32_t inputAlpha, 112 | const float32_t inputBeta, 113 | float32_t &result_D, 114 | float32_t &result_Q) const 115 | { 116 | // 117 | // This transform requires the values based on the reference angle 118 | // provided earlier. 119 | // 120 | result_D = (inputAlpha * referenceSine) - (inputBeta * referenceCosine); 121 | result_Q = (inputAlpha * referenceCosine) + (inputBeta * referenceSine); 122 | } 123 | 124 | //////////////////////////////////////////////////////////////////////////////// 125 | // 126 | // Computes the Inverse Park Transformation. It transforms the DQ 127 | // vector components in the rotating frame to a two-phase AlphaBeta 128 | // representation in the stationary frame. 129 | // 130 | //////////////////////////////////////////////////////////////////////////////// 131 | void motorTransforms::performInverseParkTransformation ( 132 | const float32_t inputD, 133 | const float32_t inputQ, 134 | float32_t &resultAlpha, 135 | float32_t &resultBeta) const 136 | { 137 | resultAlpha = (inputQ * referenceCosine) + (inputD * referenceSine); 138 | resultBeta = (inputQ * referenceSine) - (inputD * referenceCosine); 139 | } 140 | 141 | //////////////////////////////////////////////////////////////////////////////// 142 | // 143 | // Computes the inverse Clarke Transformation. This transforms 144 | // two-phase AlphaBeta form data in the stationary frame back to the 145 | // three phase ABC form, also in the stationary frame. 146 | // 147 | //////////////////////////////////////////////////////////////////////////////// 148 | void motorTransforms::performInverseClarkeTransformation ( 149 | const float32_t inputAlpha, 150 | const float32_t inputBeta, 151 | float32_t &resultA, 152 | float32_t &resultB, 153 | float32_t &resultC) const 154 | { 155 | resultA = inputAlpha; 156 | resultB = (-0.5F * inputAlpha) + (inputBeta * GlobalConstants::sqrt3Over2); 157 | resultC = (-0.5F * inputAlpha) - (inputBeta * GlobalConstants::sqrt3Over2); 158 | } 159 | 160 | -------------------------------------------------------------------------------- /src/motor_drive/pi_controller.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This class defines a Proportional-Integral (PI) control loop. 30 | // 31 | // This particular implementation is fairly standard and includes an 32 | // integrator that saturates. 33 | // 34 | //////////////////////////////////////////////////////////////////////////////// 35 | #pragma once 36 | 37 | #include "global_definitions.h" 38 | 39 | 40 | 41 | class PIController 42 | { 43 | public: 44 | 45 | PIController(); 46 | ~PIController() {}; 47 | 48 | // 49 | // This method initializes the control loop. It should be called at least 50 | // once before the loop is used. The controller supports an optional slew 51 | // limit on the target command. If a slew-limit is desired, set the 52 | // commandSlewLimit to a value other than noCommandSlewLimit. Note that 53 | // if the slew limit is enabled, it does not apply to the commandTarget 54 | // that is provided to initializePIController. In this case the loop's 55 | // initial target will be the provided value -- it will not be slewed in. 56 | // 57 | static constexpr float32_t noCommandSlewLimit = 0.0F; 58 | 59 | void initializePIController( 60 | const float32_t proportionalGain, 61 | const float32_t integralGain, 62 | const float32_t commandTarget, 63 | const float32_t maximumOutput, 64 | const float32_t maximumIntegrator, 65 | const float32_t commandSlewLimit = noCommandSlewLimit); 66 | 67 | // 68 | // This method re-initializes the controller. An initial value for the 69 | // loop target and the integrator may be provided to minimize startup 70 | // transients. Note that the loops target will be immediately set to 71 | // the provided value. It will not be slewed. 72 | // 73 | void reInitializePIController( 74 | const float32_t initialTarget = 0.0F, 75 | const float32_t initialIntegrator = 0.0F); 76 | 77 | // 78 | // This method performs a control loop update. 79 | // 80 | void updatePIController(const float32_t feedbackInput, float32_t &commandOutput); 81 | 82 | // 83 | // This method allows the caller to update the loop's target. If a slew limit 84 | // was provided when the controller was initialized, the loop's target 85 | // will be slewed to this value as necessary. 86 | // 87 | void setPIControllerTarget(const float32_t commandTarget) { target = commandTarget; } 88 | 89 | // 90 | // This allows the caller to update the loops gains and settings. 91 | // 92 | void updatePIControllerSettings( 93 | const float32_t proportionalGain, 94 | const float32_t integralGain, 95 | const float32_t maximumOutput, 96 | const float32_t integratorLimit); 97 | 98 | // 99 | // These provide loop status etc. to support test and integration. 100 | // 101 | bool loopIsSaturated() const 102 | { return (loopSaturatedPositive || loopSaturatedNegative); } 103 | float32_t getLastTarget() const { return target; } 104 | float32_t getLastCommandOutput() const { return lastOutput; } 105 | float32_t getLastFeedbackInput() const { return presentFeedback; } 106 | float32_t getLoopError() const { return presentError; } 107 | float32_t getLoopIntegrator() const { return static_cast(integratedError); } 108 | 109 | 110 | private: 111 | 112 | // 113 | // These latch the loops settings. 114 | // 115 | float32_t PGain; 116 | float32_t IGain; 117 | float32_t target; 118 | float32_t outputLimit; 119 | float64_t integratorLimit; 120 | float32_t targetSlewLimit; 121 | 122 | // 123 | // These track the loop's state. 124 | // 125 | float32_t slewedTarget; 126 | float32_t presentFeedback; 127 | float32_t presentError; 128 | float64_t integratedError; 129 | float32_t lastOutput; 130 | bool loopSaturatedPositive; 131 | bool loopSaturatedNegative; 132 | 133 | // 134 | // We make the data logger a friend class so that it can access 135 | // private members for logging. 136 | // 137 | friend class dataLogger; 138 | 139 | }; 140 | -------------------------------------------------------------------------------- /src/motor_drive/pll_angle_est.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This file describes the interface to a Phased Locked Loop (PLL) motor 30 | // shaft angle estimator. 31 | // 32 | // The PLL estimator is one of several algorithms used in sensor-less motor 33 | // drives to estimate the motor's shaft angle. This estimator does use measured 34 | // motor currents and bus voltage. This is combined with the commanded voltage 35 | // and a motor model to estimate the motor's back EMF, and from that, the shaft 36 | // angle. 37 | // 38 | // The PLL estimator requires a minimum motor speed to work and does not allow 39 | // for motor torque control at lower speeds. For this reason, the estimator 40 | // cannot be used to start a stationary motor. Some other technique must be 41 | // used to control the motor a low speed. 42 | // 43 | // The software implemented in this class is based on the algorithm described 44 | // in the following Microchip application note: 45 | // 46 | // "DSO1292A: Sensorless Field Oriented Control (FOC) for a Permanent Magnet 47 | // Synchronous Motor (PMSM) Using a PLL Estimator and Field Weakening (FW)" 48 | // Copyright 2009 Mihai Cheles, Microchip Technology 49 | // 50 | //////////////////////////////////////////////////////////////////////////////// 51 | #pragma once 52 | 53 | #include "data_logger.h" 54 | #include "global_definitions.h" 55 | #include "low_pass_filter.h" 56 | #include "motor_transforms.h" 57 | 58 | class PLLAngleEstimator 59 | { 60 | public: 61 | 62 | PLLAngleEstimator(); 63 | ~PLLAngleEstimator() {}; 64 | 65 | // 66 | // This prepares the estimator for operation. It requires several motor 67 | // specific parameters. 68 | // 69 | void initializePLLEstimtor( 70 | const resistance_Ohms statorResistance, 71 | const inductance_H statorInductance, 72 | const voltsPer1000MechanicalRPM motorBackEMFConstant, 73 | const float32_t motorPolePairs, 74 | const frequency_Hz sampleFrequency); 75 | 76 | // 77 | // This computes an updated angle estimate. The feedback current data should 78 | // be the same values used in the motor's current control loops. The phase 79 | // voltage data may either be sampled or estimated using prior motor commands. 80 | // Note that the voltage alpha and beta values should be signed such that 81 | // zero is mid-scale. 82 | // 83 | void updatePLLAngleEstimate( 84 | const float32_t feedbackCurrentAlpha, 85 | const float32_t feedbackCurrentBeta, 86 | const amperes phaseVoltageAlpha, 87 | const amperes phaseVoltageBeta, 88 | const volts busVoltage); 89 | 90 | electricalAngle_rad getPLLAngleEstimate() const { return estimatedAngle; } 91 | 92 | 93 | 94 | private: 95 | 96 | // 97 | // This is the result from the angle estimation. 98 | // 99 | electricalAngle_rad estimatedAngle; 100 | 101 | // 102 | // These are the motor specific parameters. 103 | // 104 | float32_t pllEstimatorStatorResistance; 105 | float32_t pllEstimatorInductancePerUpdate; 106 | float32_t pllEstimatorBackEMFToSpeedConversion; 107 | float32_t pllSpeedToAngleConversion; 108 | 109 | // 110 | // These are the estimator's intermediate terms. 111 | // 112 | electricalAngle_rad rawEstimatedAngle; 113 | electricalSpeed_RPM pllSpeedEstimate; 114 | lowPassFilter filteredBackEMF_D; 115 | lowPassFilter filteredBackEMF_Q; 116 | float32_t lastFeedbackCurrentAlpha; 117 | float32_t lastFeedbackCurrentBeta; 118 | 119 | // 120 | // The PLL estimator requires its own set of coordinate transforms. It 121 | // may not necessarily be able to use the same reference angle as that 122 | // used to control the motor. 123 | // 124 | motorTransforms estimatorTransforms; 125 | 126 | // 127 | // This is a WIP -- we try do determine with the angle estimate is 128 | // useable. 129 | // 130 | float32_t pllEstimatorGoodnessMetric; 131 | 132 | // 133 | // We make the data logger a friend class so that it can access 134 | // private members for logging. 135 | // 136 | friend class dataLogger; 137 | 138 | }; 139 | 140 | -------------------------------------------------------------------------------- /src/motor_drive/smo_angle_est.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This file describes the interface to a Sliding Mode Observer (SMO) motor 30 | // shaft angle estimator. Some articles also refer to this as a Sliding Mode 31 | // Controller. 32 | // 33 | // The SMO is one of several algorithms used in sensor-less motor drives to 34 | // estimate the motor's shaft angle. The SMO does use measured motor currents 35 | // and bus voltage. This is combined with the commanded voltage and a motor 36 | // model to estimate the motor's back EMF, and from that, the shaft angle. 37 | // 38 | // The SMO requires a minimum motor speed to work and does not allow for motor 39 | // torque control at lower speeds. For this reason, the SMO cannot be used 40 | // to start a stationary motor. Some other technique must be used to control 41 | // the motor a low speed. 42 | // 43 | // This implementation was based on documentation and example software from both 44 | // Texas Instruments and Microchip. The following application notes may be 45 | // referenced for more detail: 46 | // 47 | // "AN1078: Sensorless Field Oriented Control of a PMSM" 48 | // Copyright 2010 Jorge Zambada and Debraj Deb, Microchip Technology Inc. 49 | // 50 | // "8015.smopos.pdf: Sliding-Mode Rotor Position Observer of PMSM" 51 | // Digital Control Systems (DCS) Group, Texas Instruments. 52 | // 53 | //////////////////////////////////////////////////////////////////////////////// 54 | #pragma once 55 | 56 | #include "data_logger.h" 57 | #include "global_definitions.h" 58 | #include "low_pass_filter.h" 59 | 60 | class slidingModeObserverAngleEstimator 61 | { 62 | public: 63 | 64 | slidingModeObserverAngleEstimator(); 65 | ~slidingModeObserverAngleEstimator() {}; 66 | 67 | // 68 | // This prepares the SMO for operation. It requires several motor specific 69 | // parameters. 70 | // 71 | void initializeSMO( 72 | const resistance_Ohms statorResistance, 73 | const inductance_H statorInductance, 74 | const frequency_Hz sampleFrequency); 75 | 76 | // 77 | // This computes an updated angle estimate. The feedback current data should 78 | // be the same values used in the motor's current control loops. The phase 79 | // voltage data may either be sampled or estimated using prior motor commands. 80 | // Note that the voltage alpha and beta values should be signed such that 81 | // zero is mid-scale. The motor speed is used to adjust the angle estimate 82 | // for changes that occur as the motor's speed changes. This speed may 83 | // derived by using the angle values previously computed with the SMO. 84 | // 85 | void updateSMOAngleEstimate( 86 | const float32_t feedbackCurrentAlpha, 87 | const float32_t feedbackCurrentBeta, 88 | const amperes phaseVoltageAlpha, 89 | const amperes phaseVoltageBeta, 90 | const electricalSpeed_RPM motorSpeed); 91 | 92 | electricalAngle_rad getSlidingModeAngleEstimate() const { return estimatedAngle; } 93 | 94 | 95 | 96 | private: 97 | 98 | // 99 | // This is the result from the SMO calculation. 100 | // 101 | electricalAngle_rad estimatedAngle; 102 | 103 | // 104 | // These are the motor specific gains. 105 | // 106 | float32_t motorControlGain; 107 | float32_t plantGain; 108 | 109 | // 110 | // These are the intermediate terms in the SMO calculation. 111 | // 112 | float32_t alphaAxisSlidingControl; 113 | float32_t betaAxisSlidingControl; 114 | float32_t estimatedCurrentAlpha; 115 | float32_t estimatedCurrentBeta; 116 | float32_t estimatedBackEMFAlpha; 117 | float32_t estimatedBackEMFBeta; 118 | lowPassFilter filteredBackEMFAlpha; 119 | lowPassFilter filteredBackEMFBeta; 120 | lowPassFilter filteredBackEMFAlphaSecondPole; 121 | lowPassFilter filteredBackEMFBetaSecondPole; 122 | float32_t finalEstimatedBackEMFAlpha; 123 | float32_t finalEstimatedBackEMFBeta; 124 | 125 | // 126 | // The angle estimate has a speed-dependent offset from the motor's 127 | // true shaft angle. 128 | // 129 | void adjustAngleEstimateForSpeedLag(const electricalSpeed_RPM motorSpeed); 130 | 131 | // 132 | // We make the data logger a friend class so that it can access 133 | // private members for logging. 134 | // 135 | friend class dataLogger; 136 | 137 | }; 138 | 139 | -------------------------------------------------------------------------------- /src/motor_drive/zero_sequence_modulator.cpp: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This class implements the midpoint clamp type zero sequence modulation 30 | // function. Zero sequence modulation adjusts duty cycle commands so that 31 | // they can utilize the full capability of the DC bus voltage. 32 | // 33 | //////////////////////////////////////////////////////////////////////////////// 34 | #include "global_constants.h" 35 | #include "global_definitions.h" 36 | #include "math_util.h" 37 | #include "motor_constants.h" 38 | #include "zero_sequence_modulator.h" 39 | 40 | /////////////////////////////////////////////////////////////////////////////// 41 | // 42 | // Class constructor 43 | // 44 | //////////////////////////////////////////////////////////////////////////////// 45 | zeroSequenceModulator::zeroSequenceModulator() 46 | { 47 | } 48 | 49 | //////////////////////////////////////////////////////////////////////////////// 50 | // 51 | // Performs the zero sequence modulation. 52 | // 53 | // This implements a midpoint clamp zero sequence modulation. This is a 54 | // straightforward way to implement a Conventional Space Vector PWM technique. 55 | // This particular algorithm is a good general purpose choice because it is 56 | // fairly easy to compute. Other types my be more desrable to reduce 57 | // switching losses, for example, in higher voltage systems. 58 | // 59 | //////////////////////////////////////////////////////////////////////////////// 60 | void zeroSequenceModulator::performZeroSequenceModulation ( 61 | const signedDutyCycle inputA, 62 | const signedDutyCycle inputB, 63 | const signedDutyCycle inputC, 64 | dutyCycle_pct &resultDutyCycleA, 65 | dutyCycle_pct &resultDutyCycleB, 66 | dutyCycle_pct &resultDutyCycleC) 67 | { 68 | signedDutyCycle minDuty; 69 | signedDutyCycle maxDuty; 70 | 71 | // 72 | // The input duty cycles range from nominally from -1.0 to 1.0 (that is 73 | // the output range of the inverse Clarke transformation that produced 74 | // them). We need them to range from 0.0 to 1.0 so we re-scale them. 75 | // 76 | float32_t scaledInputA; 77 | float32_t scaledInputB; 78 | float32_t scaledInputC; 79 | scaleDutyCycles( 80 | inputA, 81 | inputB, 82 | inputC, 83 | scaledInputA, 84 | scaledInputB, 85 | scaledInputC); 86 | 87 | // 88 | // We compute a normalization offset for the duty 89 | // cycles. This normalization groups them around their 90 | // approximate midpoint between the enforced duty cycle limits. 91 | // 92 | minDuty = min(scaledInputA, scaledInputB); 93 | minDuty = min(minDuty, scaledInputC); 94 | 95 | maxDuty = max(scaledInputA, scaledInputB); 96 | maxDuty = max(maxDuty, scaledInputC); 97 | 98 | float32_t dutyNormalization = (minDuty + maxDuty) / 2.0F; 99 | 100 | // 101 | // We adjust the normalization offset for the limits on the duty cycle. 102 | // If the duty cycle limits are symmetrical around the duty cycle midpoint, 103 | // this will offset the final duty cycles around that midpoint. If the 104 | // duty cycle limits are not symmetrical (for example 0.1 to 0.8) this 105 | // will offset the final duty cycles around the midpoint of the final 106 | // allowed range (0.45 in this example). 107 | // 108 | const float32_t dutyCycleLimitAverage = 109 | (MotorConstants::minDutyCycleCommand + 110 | MotorConstants::maxDutyCycleCommand) / 2.0F; 111 | 112 | dutyNormalization = dutyNormalization - dutyCycleLimitAverage; 113 | 114 | // 115 | // Now we apply the normalization offset to each duty cycle. 116 | // 117 | resultDutyCycleA = scaledInputA - dutyNormalization; 118 | resultDutyCycleB = scaledInputB - dutyNormalization; 119 | resultDutyCycleC = scaledInputC - dutyNormalization; 120 | } 121 | 122 | //////////////////////////////////////////////////////////////////////////////// 123 | // 124 | // This function re-scales the duty cycles that are computed by the 125 | // inverse Clarke Transform to fit the input range needed by the zero 126 | // sequence modulation functions. 127 | // 128 | //////////////////////////////////////////////////////////////////////////////// 129 | void zeroSequenceModulator::scaleDutyCycles ( 130 | const signedDutyCycle inputA, 131 | const signedDutyCycle inputB, 132 | const signedDutyCycle inputC, 133 | signedDutyCycle &resultA, 134 | signedDutyCycle &resultB, 135 | signedDutyCycle &resultC) 136 | { 137 | resultA = (inputA + 1.0F) / 2.0F; 138 | resultB = (inputB + 1.0F) / 2.0F; 139 | resultC = (inputC + 1.0F) / 2.0F; 140 | } 141 | -------------------------------------------------------------------------------- /src/motor_drive/zero_sequence_modulator.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This class provides a midpoint clamp type zero sequence modulator (ZSM). 30 | // The zero sequence modulator accepts duty cycle inputs for each of the 31 | // three motor phases (A, B, and C). The modulator shifts these duty cycles 32 | // in unison as the motor commutates so that they make full use of the 33 | // available motor DC bus voltage and fall in the input range required by the 34 | // physical PWM interface. 35 | // 36 | // Note that the midpoint clamp type zero sequence modulation produces the same 37 | // result as conventional space vector pulse width modulation (CSVPWM) often 38 | // referred to more simply as space vector modulation (SVM). 39 | // 40 | // An excellent description of zero sequence modulation, its possible variants 41 | // and why one would choose the midpoint clamp type may be found at: 42 | // https://microchipdeveloper.com/mct5001:start 43 | // 44 | //////////////////////////////////////////////////////////////////////////////// 45 | #pragma once 46 | 47 | #include "data_logger.h" 48 | #include "global_constants.h" 49 | #include "global_definitions.h" 50 | 51 | class zeroSequenceModulator 52 | { 53 | public: 54 | 55 | zeroSequenceModulator(); 56 | ~zeroSequenceModulator() {}; 57 | 58 | // 59 | // This method performs the zero sequence modulation. The inputs are 60 | // duty cycles that should nominally be in the range of -1.0 to 1.0 but 61 | // may extend slighly beyond to take advantage of some overmodulation. 62 | // The outputs are duty cycles in a form appropriate to be sent to the 63 | // PWM controller hardware. 64 | // 65 | void performZeroSequenceModulation( 66 | const signedDutyCycle inputA, 67 | const signedDutyCycle inputB, 68 | const signedDutyCycle inputC, 69 | dutyCycle_pct &resultDutyCycleA, 70 | dutyCycle_pct &resultDutyCycleB, 71 | dutyCycle_pct &resultDutyCycleC); 72 | 73 | private: 74 | 75 | // 76 | // This scales the duty cycles into the range required for the 77 | // zero sequence modulation. 78 | // 79 | void scaleDutyCycles ( 80 | const signedDutyCycle inputA, 81 | const signedDutyCycle inputB, 82 | const signedDutyCycle inputC, 83 | signedDutyCycle &resultA, 84 | signedDutyCycle &resultB, 85 | signedDutyCycle &resultC); 86 | 87 | // 88 | // We make the data logger a friend class so that it can access 89 | // private members for logging. 90 | // 91 | friend class dataLogger; 92 | }; 93 | 94 | 95 | -------------------------------------------------------------------------------- /src/processor_specific/STM32F4xx_HAL_Driver/stm32f4xx_ll_crc.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f4xx_ll_crc.c 4 | * @author MCD Application Team 5 | * @brief CRC LL module driver. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

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

11 | * 12 | * This software component is licensed by ST under BSD 3-Clause license, 13 | * the "License"; You may not use this file except in compliance with the 14 | * License. You may obtain a copy of the License at: 15 | * opensource.org/licenses/BSD-3-Clause 16 | * 17 | ****************************************************************************** 18 | */ 19 | #if defined(USE_FULL_LL_DRIVER) 20 | 21 | /* Includes ------------------------------------------------------------------*/ 22 | #include "stm32f4xx_ll_crc.h" 23 | #include "stm32f4xx_ll_bus.h" 24 | 25 | #ifdef USE_FULL_ASSERT 26 | #include "stm32_assert.h" 27 | #else 28 | #define assert_param(expr) ((void)0U) 29 | #endif 30 | 31 | /** @addtogroup STM32F4xx_LL_Driver 32 | * @{ 33 | */ 34 | 35 | #if defined (CRC) 36 | 37 | /** @addtogroup CRC_LL 38 | * @{ 39 | */ 40 | 41 | /* Private types -------------------------------------------------------------*/ 42 | /* Private variables ---------------------------------------------------------*/ 43 | /* Private constants ---------------------------------------------------------*/ 44 | /* Private macros ------------------------------------------------------------*/ 45 | /* Private function prototypes -----------------------------------------------*/ 46 | 47 | /* Exported functions --------------------------------------------------------*/ 48 | /** @addtogroup CRC_LL_Exported_Functions 49 | * @{ 50 | */ 51 | 52 | /** @addtogroup CRC_LL_EF_Init 53 | * @{ 54 | */ 55 | 56 | /** 57 | * @brief De-initialize CRC registers (Registers restored to their default values). 58 | * @param CRCx CRC Instance 59 | * @retval An ErrorStatus enumeration value: 60 | * - SUCCESS: CRC registers are de-initialized 61 | * - ERROR: CRC registers are not de-initialized 62 | */ 63 | ErrorStatus LL_CRC_DeInit(CRC_TypeDef *CRCx) 64 | { 65 | ErrorStatus status = SUCCESS; 66 | 67 | /* Check the parameters */ 68 | assert_param(IS_CRC_ALL_INSTANCE(CRCx)); 69 | 70 | if (CRCx == CRC) 71 | { 72 | /* Force CRC reset */ 73 | LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_CRC); 74 | 75 | /* Release CRC reset */ 76 | LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_CRC); 77 | } 78 | else 79 | { 80 | status = ERROR; 81 | } 82 | 83 | return (status); 84 | } 85 | 86 | /** 87 | * @} 88 | */ 89 | 90 | /** 91 | * @} 92 | */ 93 | 94 | /** 95 | * @} 96 | */ 97 | 98 | #endif /* defined (CRC) */ 99 | 100 | /** 101 | * @} 102 | */ 103 | 104 | #endif /* USE_FULL_LL_DRIVER */ 105 | 106 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 107 | 108 | -------------------------------------------------------------------------------- /src/processor_specific/STM32F4xx_HAL_Driver/stm32f4xx_ll_crc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f4xx_ll_crc.h 4 | * @author MCD Application Team 5 | * @brief Header file of CRC LL module. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

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

11 | * 12 | * This software component is licensed by ST under BSD 3-Clause license, 13 | * the "License"; You may not use this file except in compliance with the 14 | * License. You may obtain a copy of the License at: 15 | * opensource.org/licenses/BSD-3-Clause 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef STM32F4xx_LL_CRC_H 22 | #define STM32F4xx_LL_CRC_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "stm32f4xx.h" 30 | 31 | /** @addtogroup STM32F4xx_LL_Driver 32 | * @{ 33 | */ 34 | 35 | #if defined(CRC) 36 | 37 | /** @defgroup CRC_LL CRC 38 | * @{ 39 | */ 40 | 41 | /* Private types -------------------------------------------------------------*/ 42 | /* Private variables ---------------------------------------------------------*/ 43 | /* Private constants ---------------------------------------------------------*/ 44 | /* Private macros ------------------------------------------------------------*/ 45 | 46 | /* Exported types ------------------------------------------------------------*/ 47 | /* Exported constants --------------------------------------------------------*/ 48 | /** @defgroup CRC_LL_Exported_Constants CRC Exported Constants 49 | * @{ 50 | */ 51 | 52 | /** 53 | * @} 54 | */ 55 | 56 | /* Exported macro ------------------------------------------------------------*/ 57 | /** @defgroup CRC_LL_Exported_Macros CRC Exported Macros 58 | * @{ 59 | */ 60 | 61 | /** @defgroup CRC_LL_EM_WRITE_READ Common Write and read registers Macros 62 | * @{ 63 | */ 64 | 65 | /** 66 | * @brief Write a value in CRC register 67 | * @param __INSTANCE__ CRC Instance 68 | * @param __REG__ Register to be written 69 | * @param __VALUE__ Value to be written in the register 70 | * @retval None 71 | */ 72 | #define LL_CRC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, __VALUE__) 73 | 74 | /** 75 | * @brief Read a value in CRC register 76 | * @param __INSTANCE__ CRC Instance 77 | * @param __REG__ Register to be read 78 | * @retval Register value 79 | */ 80 | #define LL_CRC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) 81 | /** 82 | * @} 83 | */ 84 | 85 | /** 86 | * @} 87 | */ 88 | 89 | 90 | /* Exported functions --------------------------------------------------------*/ 91 | /** @defgroup CRC_LL_Exported_Functions CRC Exported Functions 92 | * @{ 93 | */ 94 | 95 | /** @defgroup CRC_LL_EF_Configuration CRC Configuration functions 96 | * @{ 97 | */ 98 | 99 | /** 100 | * @brief Reset the CRC calculation unit. 101 | * @note If Programmable Initial CRC value feature 102 | * is available, also set the Data Register to the value stored in the 103 | * CRC_INIT register, otherwise, reset Data Register to its default value. 104 | * @rmtoll CR RESET LL_CRC_ResetCRCCalculationUnit 105 | * @param CRCx CRC Instance 106 | * @retval None 107 | */ 108 | __STATIC_INLINE void LL_CRC_ResetCRCCalculationUnit(CRC_TypeDef *CRCx) 109 | { 110 | SET_BIT(CRCx->CR, CRC_CR_RESET); 111 | } 112 | 113 | /** 114 | * @} 115 | */ 116 | 117 | /** @defgroup CRC_LL_EF_Data_Management Data_Management 118 | * @{ 119 | */ 120 | 121 | /** 122 | * @brief Write given 32-bit data to the CRC calculator 123 | * @rmtoll DR DR LL_CRC_FeedData32 124 | * @param CRCx CRC Instance 125 | * @param InData value to be provided to CRC calculator between between Min_Data=0 and Max_Data=0xFFFFFFFF 126 | * @retval None 127 | */ 128 | __STATIC_INLINE void LL_CRC_FeedData32(CRC_TypeDef *CRCx, uint32_t InData) 129 | { 130 | WRITE_REG(CRCx->DR, InData); 131 | } 132 | 133 | /** 134 | * @brief Return current CRC calculation result. 32 bits value is returned. 135 | * @rmtoll DR DR LL_CRC_ReadData32 136 | * @param CRCx CRC Instance 137 | * @retval Current CRC calculation result as stored in CRC_DR register (32 bits). 138 | */ 139 | __STATIC_INLINE uint32_t LL_CRC_ReadData32(CRC_TypeDef *CRCx) 140 | { 141 | return (uint32_t)(READ_REG(CRCx->DR)); 142 | } 143 | 144 | /** 145 | * @brief Return data stored in the Independent Data(IDR) register. 146 | * @note This register can be used as a temporary storage location for one byte. 147 | * @rmtoll IDR IDR LL_CRC_Read_IDR 148 | * @param CRCx CRC Instance 149 | * @retval Value stored in CRC_IDR register (General-purpose 8-bit data register). 150 | */ 151 | __STATIC_INLINE uint32_t LL_CRC_Read_IDR(CRC_TypeDef *CRCx) 152 | { 153 | return (uint32_t)(READ_REG(CRCx->IDR)); 154 | } 155 | 156 | /** 157 | * @brief Store data in the Independent Data(IDR) register. 158 | * @note This register can be used as a temporary storage location for one byte. 159 | * @rmtoll IDR IDR LL_CRC_Write_IDR 160 | * @param CRCx CRC Instance 161 | * @param InData value to be stored in CRC_IDR register (8-bit) between Min_Data=0 and Max_Data=0xFF 162 | * @retval None 163 | */ 164 | __STATIC_INLINE void LL_CRC_Write_IDR(CRC_TypeDef *CRCx, uint32_t InData) 165 | { 166 | *((uint8_t __IO *)(&CRCx->IDR)) = (uint8_t) InData; 167 | } 168 | /** 169 | * @} 170 | */ 171 | 172 | #if defined(USE_FULL_LL_DRIVER) 173 | /** @defgroup CRC_LL_EF_Init Initialization and de-initialization functions 174 | * @{ 175 | */ 176 | 177 | ErrorStatus LL_CRC_DeInit(CRC_TypeDef *CRCx); 178 | 179 | /** 180 | * @} 181 | */ 182 | #endif /* USE_FULL_LL_DRIVER */ 183 | 184 | /** 185 | * @} 186 | */ 187 | 188 | /** 189 | * @} 190 | */ 191 | 192 | #endif /* defined(CRC) */ 193 | 194 | /** 195 | * @} 196 | */ 197 | 198 | #ifdef __cplusplus 199 | } 200 | #endif 201 | 202 | #endif /* STM32F4xx_LL_CRC_H */ 203 | 204 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 205 | -------------------------------------------------------------------------------- /src/processor_specific/STM32F4xx_HAL_Driver/stm32f4xx_ll_pwr.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f4xx_ll_pwr.c 4 | * @author MCD Application Team 5 | * @brief PWR LL module driver. 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 | #if defined(USE_FULL_LL_DRIVER) 20 | 21 | /* Includes ------------------------------------------------------------------*/ 22 | #include "stm32f4xx_ll_pwr.h" 23 | #include "stm32f4xx_ll_bus.h" 24 | 25 | /** @addtogroup STM32F4xx_LL_Driver 26 | * @{ 27 | */ 28 | 29 | #if defined(PWR) 30 | 31 | /** @defgroup PWR_LL PWR 32 | * @{ 33 | */ 34 | 35 | /* Private types -------------------------------------------------------------*/ 36 | /* Private variables ---------------------------------------------------------*/ 37 | /* Private constants ---------------------------------------------------------*/ 38 | /* Private macros ------------------------------------------------------------*/ 39 | /* Private function prototypes -----------------------------------------------*/ 40 | 41 | /* Exported functions --------------------------------------------------------*/ 42 | /** @addtogroup PWR_LL_Exported_Functions 43 | * @{ 44 | */ 45 | 46 | /** @addtogroup PWR_LL_EF_Init 47 | * @{ 48 | */ 49 | 50 | /** 51 | * @brief De-initialize the PWR registers to their default reset values. 52 | * @retval An ErrorStatus enumeration value: 53 | * - SUCCESS: PWR registers are de-initialized 54 | * - ERROR: not applicable 55 | */ 56 | ErrorStatus LL_PWR_DeInit(void) 57 | { 58 | /* Force reset of PWR clock */ 59 | LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_PWR); 60 | 61 | /* Release reset of PWR clock */ 62 | LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_PWR); 63 | 64 | return SUCCESS; 65 | } 66 | 67 | /** 68 | * @} 69 | */ 70 | 71 | /** 72 | * @} 73 | */ 74 | 75 | /** 76 | * @} 77 | */ 78 | #endif /* defined(PWR) */ 79 | /** 80 | * @} 81 | */ 82 | 83 | #endif /* USE_FULL_LL_DRIVER */ 84 | 85 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 86 | -------------------------------------------------------------------------------- /src/processor_specific/STM32F4xx_HAL_Driver/stm32f4xx_ll_rng.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f4xx_ll_rng.c 4 | * @author MCD Application Team 5 | * @brief RNG LL module driver. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

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

11 | * 12 | * This software component is licensed by ST under BSD 3-Clause license, 13 | * the "License"; You may not use this file except in compliance with the 14 | * License. You may obtain a copy of the License at: 15 | * opensource.org/licenses/BSD-3-Clause 16 | * 17 | ****************************************************************************** 18 | */ 19 | #if defined(USE_FULL_LL_DRIVER) 20 | 21 | /* Includes ------------------------------------------------------------------*/ 22 | #include "stm32f4xx_ll_rng.h" 23 | #include "stm32f4xx_ll_bus.h" 24 | 25 | #ifdef USE_FULL_ASSERT 26 | #include "stm32_assert.h" 27 | #else 28 | #define assert_param(expr) ((void)0U) 29 | #endif 30 | 31 | /** @addtogroup STM32F4xx_LL_Driver 32 | * @{ 33 | */ 34 | 35 | #if defined (RNG) 36 | 37 | /** @addtogroup RNG_LL 38 | * @{ 39 | */ 40 | 41 | /* Private types -------------------------------------------------------------*/ 42 | /* Private variables ---------------------------------------------------------*/ 43 | /* Private constants ---------------------------------------------------------*/ 44 | /* Private macros ------------------------------------------------------------*/ 45 | /* Private function prototypes -----------------------------------------------*/ 46 | 47 | /* Exported functions --------------------------------------------------------*/ 48 | /** @addtogroup RNG_LL_Exported_Functions 49 | * @{ 50 | */ 51 | 52 | /** @addtogroup RNG_LL_EF_Init 53 | * @{ 54 | */ 55 | 56 | /** 57 | * @brief De-initialize RNG registers (Registers restored to their default values). 58 | * @param RNGx RNG Instance 59 | * @retval An ErrorStatus enumeration value: 60 | * - SUCCESS: RNG registers are de-initialized 61 | * - ERROR: not applicable 62 | */ 63 | ErrorStatus LL_RNG_DeInit(RNG_TypeDef *RNGx) 64 | { 65 | /* Check the parameters */ 66 | assert_param(IS_RNG_ALL_INSTANCE(RNGx)); 67 | #if !defined (RCC_AHB2_SUPPORT) 68 | /* Enable RNG reset state */ 69 | LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_RNG); 70 | 71 | /* Release RNG from reset state */ 72 | LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_RNG); 73 | #else 74 | /* Enable RNG reset state */ 75 | LL_AHB2_GRP1_ForceReset(LL_AHB2_GRP1_PERIPH_RNG); 76 | 77 | /* Release RNG from reset state */ 78 | LL_AHB2_GRP1_ReleaseReset(LL_AHB2_GRP1_PERIPH_RNG); 79 | #endif 80 | return (SUCCESS); 81 | } 82 | 83 | /** 84 | * @} 85 | */ 86 | 87 | /** 88 | * @} 89 | */ 90 | 91 | /** 92 | * @} 93 | */ 94 | 95 | #endif /* RNG */ 96 | 97 | /** 98 | * @} 99 | */ 100 | 101 | #endif /* USE_FULL_LL_DRIVER */ 102 | 103 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 104 | 105 | -------------------------------------------------------------------------------- /src/processor_specific/processor.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Defines the processor and includes files specific to the processor 30 | // 31 | //////////////////////////////////////////////////////////////////////////////// 32 | #pragma once 33 | 34 | #if __cplusplus > 199711L 35 | #define register // Deprecated in C++11 but it is used by the ST libraries 36 | #endif 37 | 38 | #include "stm32f4xx_ll_adc.h" 39 | #include "stm32f4xx_ll_bus.h" 40 | #include "stm32f4xx_ll_dac.h" 41 | #include "stm32f4xx_ll_dma.h" 42 | #include "stm32f4xx_ll_exti.h" 43 | #include "stm32f4xx_ll_gpio.h" 44 | #include "stm32f4xx_ll_i2c.h" 45 | #include "stm32f4xx_ll_rcc.h" 46 | #include "stm32f4xx_ll_system.h" 47 | #include "stm32f4xx_ll_tim.h" 48 | #include "stm32f4xx_ll_usart.h" 49 | #include "system_stm32f4xx.h" 50 | -------------------------------------------------------------------------------- /src/processor_specific/stm32f4xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/0x2152Yet/yet_another_motor_drive/257290d5e7559d50ed5bcd64b6ed36717b38edd6/src/processor_specific/stm32f4xx.h -------------------------------------------------------------------------------- /src/processor_specific/system_stm32f4xx.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file system_stm32f4xx.h 4 | * @author MCD Application Team 5 | * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© COPYRIGHT(c) 2017 STMicroelectronics

10 | * 11 | * Redistribution and use in source and binary forms, with or without modification, 12 | * are permitted provided that the following conditions are met: 13 | * 1. Redistributions of source code must retain the above copyright notice, 14 | * this list of conditions and the following disclaimer. 15 | * 2. Redistributions in binary form must reproduce the above copyright notice, 16 | * this list of conditions and the following disclaimer in the documentation 17 | * and/or other materials provided with the distribution. 18 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 19 | * may be used to endorse or promote products derived from this software 20 | * without specific prior written permission. 21 | * 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 23 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 24 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 25 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 26 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 27 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 28 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 30 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 31 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 32 | * 33 | ****************************************************************************** 34 | */ 35 | 36 | /** @addtogroup CMSIS 37 | * @{ 38 | */ 39 | 40 | /** @addtogroup stm32f4xx_system 41 | * @{ 42 | */ 43 | 44 | /** 45 | * @brief Define to prevent recursive inclusion 46 | */ 47 | #ifndef __SYSTEM_STM32F4XX_H 48 | #define __SYSTEM_STM32F4XX_H 49 | 50 | #ifdef __cplusplus 51 | extern "C" { 52 | #endif 53 | 54 | /** @addtogroup STM32F4xx_System_Includes 55 | * @{ 56 | */ 57 | 58 | /** 59 | * @} 60 | */ 61 | 62 | 63 | /** @addtogroup STM32F4xx_System_Exported_types 64 | * @{ 65 | */ 66 | /* This variable is updated in three ways: 67 | 1) by calling CMSIS function SystemCoreClockUpdate() 68 | 2) by calling HAL API function HAL_RCC_GetSysClockFreq() 69 | 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency 70 | Note: If you use this function to configure the system clock; then there 71 | is no need to call the 2 first functions listed above, since SystemCoreClock 72 | variable is updated automatically. 73 | */ 74 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ 75 | 76 | extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ 77 | extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ 78 | 79 | /** 80 | * @} 81 | */ 82 | 83 | /** @addtogroup STM32F4xx_System_Exported_Constants 84 | * @{ 85 | */ 86 | 87 | /** 88 | * @} 89 | */ 90 | 91 | /** @addtogroup STM32F4xx_System_Exported_Macros 92 | * @{ 93 | */ 94 | 95 | /** 96 | * @} 97 | */ 98 | 99 | /** @addtogroup STM32F4xx_System_Exported_Functions 100 | * @{ 101 | */ 102 | 103 | extern void SystemInit(void); 104 | extern void SystemCoreClockUpdate(void); 105 | /** 106 | * @} 107 | */ 108 | 109 | #ifdef __cplusplus 110 | } 111 | #endif 112 | 113 | #endif /*__SYSTEM_STM32F4XX_H */ 114 | 115 | /** 116 | * @} 117 | */ 118 | 119 | /** 120 | * @} 121 | */ 122 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 123 | -------------------------------------------------------------------------------- /src/util/debouncer.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This class provides a simple button debouncer. This should be invoked 30 | // at a periodic rate with the present button input state. The button state 31 | // will be debounced and transformed into one of several logical button states. 32 | // 33 | //////////////////////////////////////////////////////////////////////////////// 34 | #pragma once 35 | 36 | #include "global_definitions.h" 37 | 38 | class debouncer 39 | { 40 | public: 41 | // 42 | // A filter coefficient may be optionally provided to the constructor. 43 | // 44 | debouncer(); 45 | ~debouncer() {}; 46 | 47 | // 48 | // This should be called periodically with the latest sampled button 49 | // state. 50 | // 51 | void updateDebouncer(const bool buttonIsActive); 52 | 53 | // 54 | // These indicate if a push-button input is pressed. This will be true 55 | // only on the first call after updateDebouncer determines that the button is 56 | // pressed. Note that a button press is declared when the button is released. 57 | // If the button is pushed and held, this will not return true. In button-hold 58 | // cases, calls to pushButtonIsHeld eventually will return true. 59 | // 60 | bool buttonIsPressed(); 61 | 62 | // 63 | // This indicate if a button is held. Again, this will be true on only 64 | // the first call after updateDebouncer determines that the button is 65 | // held. 66 | // 67 | bool buttonIsHeld(); 68 | 69 | private: 70 | 71 | enum pushButtonStates 72 | { 73 | idle, 74 | active, 75 | held, 76 | waitingForIdle 77 | }; 78 | 79 | pushButtonStates buttonState; 80 | tickTime_ms buttonStateStartTime; 81 | uint32_t buttonDebounceCount; 82 | bool buttonPressed; 83 | bool buttonHeld; 84 | }; 85 | -------------------------------------------------------------------------------- /src/util/low_pass_filter.cpp: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This class implements a simple single-pole low pass filter. 30 | // 31 | //////////////////////////////////////////////////////////////////////////////// 32 | 33 | #include "global_constants.h" 34 | #include "global_definitions.h" 35 | #include "low_pass_filter.h" 36 | 37 | #include 38 | 39 | //////////////////////////////////////////////////////////////////////////////// 40 | // 41 | // Class constructor 42 | // 43 | //////////////////////////////////////////////////////////////////////////////// 44 | lowPassFilter::lowPassFilter(const float32_t initFilterCoefficient) : 45 | filteredValue(0.0F), 46 | filterCoefficient (initFilterCoefficient) 47 | { 48 | } 49 | 50 | //////////////////////////////////////////////////////////////////////////////// 51 | // 52 | // This computes the filter coefficient based on the passed in cutoff 53 | // frequency and filter update frequency. 54 | // 55 | //////////////////////////////////////////////////////////////////////////////// 56 | void lowPassFilter::computeFilterCoefficient( 57 | const frequency_Hz cutoffFrequency, 58 | const frequency_Hz updateFrequency) 59 | { 60 | // 61 | // We compute our filter coefficient. 62 | // 63 | filterCoefficient = 64 | expf((-1.0F * (cutoffFrequency * GlobalConstants::twoPi)) * (1.0F / updateFrequency)); 65 | } 66 | 67 | //////////////////////////////////////////////////////////////////////////////// 68 | // 69 | // This updates the filter. 70 | // 71 | //////////////////////////////////////////////////////////////////////////////// 72 | void lowPassFilter::updateFilter(const float32_t newSample, float32_t &filteredSample) 73 | { 74 | // 75 | // This an optimized version of a 1-alpha filter. With some algebra, 76 | // one can hoist out the filter coefficient. 77 | // 78 | filteredValue = newSample + (filterCoefficient * (filteredValue - newSample)); 79 | filteredSample = filteredValue; 80 | } 81 | -------------------------------------------------------------------------------- /src/util/low_pass_filter.h: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // This class provides a simple single-pole low pass filter. In addition 30 | // to the filter, a method is provided to compute the filter coefficient. 31 | // 32 | //////////////////////////////////////////////////////////////////////////////// 33 | #pragma once 34 | 35 | #include "global_definitions.h" 36 | 37 | class lowPassFilter 38 | { 39 | public: 40 | // 41 | // A filter coefficient may be optionally provided to the constructor. 42 | // 43 | lowPassFilter(const float32_t initFilterCoefficient = 0.0F); 44 | ~lowPassFilter() {}; 45 | 46 | // 47 | // This allows the caller to provide a predefined filter coefficient. 48 | // 49 | void setFilterCoefficient (const float32_t newFilterCoefficient) { filterCoefficient = newFilterCoefficient; } 50 | 51 | // 52 | // This computes the filter coefficient based on the provided parameters. 53 | // 54 | void computeFilterCoefficient ( 55 | const frequency_Hz cutoffFrequency, 56 | const frequency_Hz updateFrequency); 57 | 58 | // 59 | // This updates the filter with the provided sample. 60 | // 61 | void updateFilter (const float32_t newSample, float32_t &filteredSample); 62 | 63 | // 64 | // This gets the present filter state. 65 | // 66 | float32_t getFilterState() const { return filteredValue; } 67 | 68 | // 69 | // This sets the filter's state to a particular value. This is useful for 70 | // initializing the filter on system state transitions. 71 | // 72 | void setFilterState(const float32_t newState) { filteredValue = newState; } 73 | 74 | private: 75 | // 76 | // These store the filter state and the filter coefficient. 77 | // 78 | float32_t filteredValue; 79 | float32_t filterCoefficient; 80 | 81 | }; 82 | -------------------------------------------------------------------------------- /src/util/newlib_functions.cpp: -------------------------------------------------------------------------------- 1 | //////////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Yet Another Motor Drive 4 | // 5 | // MIT License 6 | // 7 | // Copyright (c) 2021 Michael F. Kaufman 8 | // 9 | // Permission is hereby granted, free of charge, to any person obtaining a copy 10 | // of this software and associated documentation files (the "Software"), to deal 11 | // in the Software without restriction, including without limitation the rights 12 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 13 | // copies of the Software, and to permit persons to whom the Software is 14 | // furnished to do so, subject to the following conditions: 15 | // 16 | // The above copyright notice and this permission notice shall be included in all 17 | // copies or substantial portions of the Software. 18 | // 19 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 20 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 21 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 22 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 23 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 24 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 25 | // SOFTWARE. 26 | // 27 | //////////////////////////////////////////////////////////////////////////////// 28 | // 29 | // Provides functions required by the compiler's "newlib". 30 | // 31 | // Most of these are stubs (items for file I/O, etc.) However support 32 | // does exist for printf and a very basic malloc, 33 | // 34 | //////////////////////////////////////////////////////////////////////////////// 35 | 36 | #include 37 | #include 38 | #include 39 | #include 40 | 41 | #include "global_definitions.h" 42 | #include "uart_interface.h" 43 | 44 | #ifdef __cplusplus 45 | extern "C" 46 | { 47 | #endif 48 | 49 | // 50 | // These are linker defined symbols that provide the location of the heap 51 | // in the processor's memory space. 52 | // 53 | extern uint32_t _heap_start; 54 | extern uint32_t _heap_end; 55 | 56 | // 57 | // These are the prototypes for the items newlib requires. These must be 58 | // defined in order for the build to link. 59 | // 60 | 61 | // 62 | // _sbrk is required by malloc. 63 | // 64 | caddr_t _sbrk(const int32_t Increment); 65 | 66 | // 67 | // _write, _isatty, _close, and _fstat are required by printf. 68 | // 69 | int _write(int file, 70 | char *ptr, 71 | int len); 72 | int _isatty(int file); 73 | int _close(int file); 74 | int _fstat(int file, 75 | struct stat *st); 76 | 77 | // 78 | // The rest are stubs. 79 | // 80 | 81 | int _getpid(); 82 | int _kill(int pid, 83 | int sig); 84 | int _read(int file, 85 | char *ptr, 86 | int len); 87 | int _lseek(int file, 88 | int ptr, 89 | int dir); 90 | 91 | //////////////////////////////////////////////////////////////////////////////// 92 | // 93 | // Memory pool manager for malloc 94 | // 95 | // This function provides memory to malloc from a pool created by the linker. 96 | // We do not support freeing memory in this application. 97 | // 98 | //////////////////////////////////////////////////////////////////////////////// 99 | caddr_t _sbrk(const int32_t Increment) 100 | { 101 | static caddr_t theHeap = reinterpret_cast(&_heap_start); 102 | static bool outOfHeap = false; 103 | caddr_t returnHeap; 104 | 105 | if (outOfHeap) 106 | { 107 | returnHeap = NULL; 108 | } 109 | else 110 | { 111 | // 112 | // "theHeap" always points to the next free block; 113 | // 114 | returnHeap = theHeap; 115 | 116 | // 117 | // We move the free-heap pointer to the next 8 byte boundary past 118 | // the desired increment. 119 | // 120 | theHeap = reinterpret_cast( 121 | (reinterpret_cast(theHeap + Increment) + 7U) & ~7U); 122 | 123 | // 124 | // We check to see if we've run out of heap. 125 | // 126 | if (theHeap >= reinterpret_cast(&_heap_end)) 127 | { 128 | outOfHeap = true; 129 | returnHeap = NULL; 130 | } 131 | } 132 | 133 | return reinterpret_cast(returnHeap); 134 | } 135 | 136 | //////////////////////////////////////////////////////////////////////////////// 137 | // 138 | // Outputs characters for printf 139 | // 140 | // This is called by printf once it has formatted its output string. We 141 | // pass the data to the USART driver. 142 | // 143 | //////////////////////////////////////////////////////////////////////////////// 144 | int _write(int file, char *ptr, int len) 145 | { 146 | theUARTInterface.sendToUART( 147 | reinterpret_cast(ptr), 148 | static_cast(len)); 149 | 150 | return len; 151 | } 152 | 153 | //////////////////////////////////////////////////////////////////////////////// 154 | // 155 | // Stub functions for printf 156 | // 157 | // These must be present for printf to link, but we do not require their 158 | // functionality. 159 | // 160 | //////////////////////////////////////////////////////////////////////////////// 161 | int _isatty(int file) 162 | { 163 | return 1; 164 | } 165 | 166 | int _fstat(int file, struct stat *st) 167 | { 168 | st->st_mode = S_IFCHR; 169 | return 0; 170 | } 171 | 172 | //////////////////////////////////////////////////////////////////////////////// 173 | // 174 | // Stubs for other functions required by the newlib. 175 | // All of these that return, return an "error" status. 176 | // 177 | //////////////////////////////////////////////////////////////////////////////// 178 | int _lseek(int file, int ptr, int dir) 179 | { 180 | return -1; 181 | } 182 | 183 | void _exit(int status) 184 | { 185 | // 186 | // There is no exit... 187 | // 188 | while(true) 189 | { 190 | } 191 | } 192 | 193 | int _close(int file) 194 | { 195 | return -1; 196 | } 197 | 198 | int _getpid() 199 | { 200 | return -1; 201 | } 202 | 203 | int _kill(int pid, int sig) 204 | { 205 | return -1; 206 | } 207 | 208 | int _read(int file, char *ptr, int len) 209 | { 210 | return -1; 211 | } 212 | 213 | #ifdef __cplusplus 214 | } 215 | #endif /* extern "C" */ 216 | --------------------------------------------------------------------------------