├── LICENSE ├── README.md ├── examples ├── Calibrate_spreadCycle │ └── Calibrate_spreadCycle.ino ├── Live_tune │ └── Live_tune.ino ├── Simple │ └── Simple.ino ├── Software_SPI │ └── Software_SPI.ino ├── StallGuard │ └── StallGuard.ino └── TMC2130_AccelStepper │ └── TMC2130_AccelStepper.ino ├── extras ├── Fritzing │ ├── SilentStepStick-TMC2130-part.fzpz │ ├── TMC2130-breadboard.svg │ ├── TMC2130-sample-circuit .fzz │ ├── TMC2130-sample-circuit .png │ └── TMC2130-schematic.svg └── TMC5130_TMC2130_TMC2100_Calculations.xlsx ├── keywords.txt ├── library.properties └── src ├── TMC2130Stepper.h ├── TMC2130Stepper_REGDEFS.h ├── TMC2130Stepper_UTILITY.h └── source ├── SW_SPI.cpp ├── SW_SPI.h ├── TMC2130Stepper.cpp ├── TMC2130Stepper_CHOPCONF.cpp ├── TMC2130Stepper_COOLCONF.cpp ├── TMC2130Stepper_DRV_STATUS.cpp ├── TMC2130Stepper_GCONF.cpp ├── TMC2130Stepper_IHOLD_IRUN.cpp ├── TMC2130Stepper_MACROS.h └── TMC2130Stepper_PWMCONF.cpp /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2023 teemuatlut 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | This library has been superseded by the newer [TMCStepper library](https://github.com/teemuatlut/TMCStepper) which supports many more of the Trinamic stepper drivers and more MCU architectures. 2 | 3 | # TMC2130Stepper 4 | Arduino library for Trinamic TMC2130 Stepper driver 5 | 6 | ## Installation: 7 | 8 | Use the Arduino IDE library manager (Sketch -> Include library -> Manage libraries...) 9 | 10 | Search for TMC2130Stepper and then install. 11 | 12 | Or download the zip file from Github and extract it to
13 | your-scetchbook-location/libraries
14 | and restart the IDE. 15 | 16 | or goto to you arduino libraries folder and in command line 17 | git clone https://github.com/teemuatlut/TMC2130Stepper.git 18 | 19 | ## What works: 20 | Nearly all the features in the registeries are configurable through get/set functions. See below for a list of functions. Datasheet ([link](https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC2130_datasheet.pdf)) from Trinamic also provides further detail into the settings available. 21 | 22 | ## Simple example 23 | ```cpp 24 | /* 25 | Initializes the library and turns the motor in alternating directions. 26 | */ 27 | #define EN_PIN 38 // Nano v3: 16 Mega: 38 //enable (CFG6) 28 | #define DIR_PIN 55 // 19 55 //direction 29 | #define STEP_PIN 54 // 18 54 //step 30 | #define CS_PIN 40 // 17 64 //chip select 31 | 32 | bool dir = true; 33 | 34 | 35 | #include 36 | TMC2130Stepper TMC2130 = TMC2130Stepper(EN_PIN, DIR_PIN, STEP_PIN, CS_PIN); 37 | 38 | void setup() { 39 | Serial.begin(9600); 40 | TMC2130.begin(); // Initiate pins and registeries 41 | TMC2130.SilentStepStick2130(600); // Set stepper current to 600mA 42 | TMC2130.stealthChop(1); // Enable extremely quiet stepping 43 | 44 | digitalWrite(EN_PIN, LOW); 45 | } 46 | 47 | void loop() { 48 | digitalWrite(STEP_PIN, HIGH); 49 | delayMicroseconds(10); 50 | digitalWrite(STEP_PIN, LOW); 51 | delayMicroseconds(10); 52 | uint32_t ms = millis(); 53 | static uint32_t last_time = 0; 54 | if ((ms - last_time) > 2000) { 55 | if (dir) { 56 | Serial.println("Dir -> 0"); 57 | TMC2130.shaft_dir(0); 58 | } else { 59 | Serial.println("Dir -> 1"); 60 | TMC2130.shaft_dir(1); 61 | } 62 | dir = !dir; 63 | Serial.println(TMC2130.GCONF(), BIN); 64 | last_time = ms; 65 | } 66 | } 67 | ``` 68 | 69 | ## Current calculations 70 | 71 | A simple way to set the current is to use the setCurrent() method. 72 | 73 | I_rms = (CS+1)/32 * V_fs/(R_sense+0.02mOhm) * 1/sqrt(2) 74 | I_motor = I_sine/248 * (CS+1/32) * V_fs/(R_sense+0.02mOhm) 75 | 76 | Where:
77 | I_rms is the rms current
78 | I_motor is the motor current
79 | CS is the Current Scale value
80 | V_fs is the voltage determined by v_sense
81 | R_sense is the chosen sense resistor
82 | I_sine is the current position in the sine table. I_motor reaches peak value at I_sine = 248

83 | 84 | If external_ref is enabled, V_fs is scaled by V_ain/2.5V 85 | 86 | ## Functions 87 | 88 | Function | Argument range | Returns | Description 89 | --------------------|-----|---|----------------------------- 90 | begin | - | - | Initialized pins Enable, Direction, Step and Chip Select.
Initialized the SPI pins MOSI, MISO and SCK.
Calls spi.begin()
Sets off_time = 2 and blank_time = 24 91 | setCurrent | 0..2000
0.1 .. 1
0..1 | - | Helper function to set the motor RMS current.
Arguments:
uint16_t Desired current in milliamps
float Sense resistor value
float Multiplier for holding current
Example for SilentStepStick2130: setCurrent(1200, 0.11, 0.5)

Makes use of the run_current() and hold_current() funtions. 92 | SilentStepStick2130 | 0..2000 | - | Calls the begin() functions and according to the argument sets the current with sense resistor being 0.11 and multiplier being 0.5 93 | 94 | ## Register functions: 95 | 96 | Note: You can read the saved value by calling a function without providing an argument. 97 | 98 | ### GCONF register 99 | Function | Argument range | Returns | Description 100 | --------------------|-----|---------|----------------------------- 101 | GCONF | - | uint32_t| Read actual bits from the register 102 | external_ref | 0/1 | bool | Use external voltage reference for coil currents 103 | internal_sense_R | 0/1 | bool | Use internal sense resistors 104 | stealthChop | 0/1 | bool | Enable stealthChop (dependant on velocity thresholds) 105 | commutation | 0/1 | bool | Enable commutation by full step encoder 106 | shaft_dir | 0/1 | bool | Inverse motor direction 107 | diag0_errors | 0/1 | bool | Enable DIAG0 active on driver errors: Over temperature (ot), short to GND (s2g), undervoltage chargepump (uv_cp) 108 | diag0_temp_prewarn | 0/1 | bool | Enable DIAG0 active on driver over temperature prewarning 109 | diag0_stall | 0/1 | bool | Enable DIAG0 active on motor stall (set TCOOLTHRS before using this feature) 110 | diag1_stall | 0/1 | bool | Enable DIAG1 active on motor stall (set TCOOLTHRS before using this feature) 111 | diag1_index | 0/1 | bool | Enable DIAG1 active on index position (microstep look up table position 0) 112 | diag1_chopper_on | 0/1 | bool | Enable DIAG1 active when chopper is on 113 | diag1_steps_skipped | 0/1 | bool | Enable output toggle when steps are skipped in dcStep mode (increment of LOST_STEPS). Do not enable in conjunction with other DIAG1 options. 114 | diag0_active_high | 0/1 | bool | Set DIAG0 to active high 115 | diag1_active_high | 0/1 | bool | Set DIAG1 to active high 116 | small_hysteresis | 0/1 | bool | 0: Hysteresis for step frequency comparison is 1/16
1: Hysteresis for step frequency comparison is 1/32 117 | stop_enable | 0/1 | bool | Emergency stop: DCIN stops the sequencer when tied high (no steps become executed by the sequencer, motor goes to standstill state). 118 | direct_mode | 0/1 | bool | Motor coil currents and polarity are directly controlled by the SPI interface. 119 | 120 | ### IHOLD_IRUN register 121 | Function | Argument | Returns | Description 122 | ----------------|-----------|---------|----------------------------- 123 | hold_current | 0..31 | uint8_t | Standstill current (0=1/32…31=32/32) 124 | run_current | 0..31 | uint8_t | Motor run current (0=1/32…31=32/32) 125 | hold_delay | 0..15 | uint8_t | Controls the number of clock cycles for motor power down after a motion as soon as standstill is detected (stst=1) and TPOWERDOWN has expired. 126 | 127 | ### REG_TPOWERDOWN register 128 | Function | Argument | Returns | Description 129 | -----------------|----------|-----------|----------------------------- 130 | power_down_delay | 0..255 | uint8_t | power_down_delay sets the delay time after stand still (stst) of the motor to motor current power down. Time range is about 0 to 4 seconds.
0…((2^8)-1) * 2^18 tCLK 131 | 132 | ### REG_TSTEP register 133 | Function | Argument | Returns | Description 134 | ----------------|-----------|----------|----------------------------- 135 | microstep_time | - | uint32_t | Read the actual measured time between two 1/256 microsteps derived from the step input frequency in units of 1/fCLK. 136 | 137 | ### REG_TPWMTHRS register 138 | Function | Argument | Returns | Description 139 | --------------------|---------------|-----------|----------------------------- 140 | stealth_max_speed | 0..1,048,575 | uint32_t | This is the upper velocity for stealthChop voltage PWM mode. TSTEP ≥ TPWMTHRS - stealthChop PWM mode is enabled, if configured - dcStep is disabled 141 | 142 | ### REG_TCOOLTHRS register 143 | Function | Argument | Returns | Description 144 | --------------------|---------------|-----------|----------------------------- 145 | coolstep_min_speed | 0..1,048,575 | uint32_t | This is the lower threshold velocity for switching on smart energy coolStep and stallGuard feature. 146 | 147 | ### REG_THIGH register 148 | Function | Argument | Returns | Description 149 | ----------------|---------------|-----------|----------------------------- 150 | mode_sw_speed | 0..1,048,575 | uint32_t | This velocity setting allows velocity dependent switching into a different chopper mode and fullstepping to maximize torque. 151 | 152 | ### REG_XDRIRECT register 153 | Function | Argument | Returns | Description 154 | ----------------|---------------|-----------|----------------------------- 155 | coil_A_current | -255..+255 | int16_t | Specifies Motor coil currents and polarity directly programmed via the serial interface. In this mode, the current is scaled by IHOLD setting. 156 | coil_B_current | -255..+255 | int16_t | As above. 157 | 158 | ### REG_VDCMIN register 159 | Function | Argument | Returns | Description 160 | --------------------|---------------|-----------|----------------------------- 161 | DCstep_min_speed | 0..8,388,607 | uint32_t | The automatic commutation dcStep becomes enabled by the external signal DCEN. VDCMIN is used as the minimum step velocity when the motor is heavily loaded.
Hint: Also set DCCTRL parameters in order to operate dcStep. 162 | 163 | ### REG_CHOPCONF register 164 | Function | Argument | Returns | Description 165 | ------------------------|-----------|-----------|----------------------------- 166 | CHOPCONF | - | uint32_t | Read actual bits from the register 167 | off_time | 0..15 | uint8_t | Off time setting controls duration of slow decay phase
NCLK= 12 + 32*TOFF
Initialized to value 2 (NCLK = 76) by begin() 168 | hysteresis_start | 1..8 | uint8_t | Add 1, 2, …, 8 to hysteresis low value HEND (1/512 of this setting adds to current setting) Attention: Effective HEND+HSTRT ≤ 16. Hint: Hysteresis decrement is done each 16 clocks 169 | fast_decay_time | 0..15 | uint8_t | Fast decay time setting TFD with NCLK= 32*HSTRT 170 | hysteresis_end | -3..12 | int8_t | This is the hysteresis value which becomes used for the hysteresis chopper. 171 | sine_offset | -3..12 | int8_t | This is the sine wave offset and 1/512 of the value becomes added to the absolute value of each sine wave entry. 172 | disable_I_comparator | 0/1 | bool | 1: Disables current comparator usage for termination of the fast decay cycle.
chopper_mode needs to be 1. 173 | random_off_time | 0/1 | bool | 0: Chopper off time is fixed as set by TOFF
1: Random mode, TOFF is random modulated by dNCLK= -12 … +3 clocks. 174 | chopper_mode | 0/1 | uint8_t | 0: Standard mode (spreadCycle)
1: Constant off time with fast decay time.
Fast decay time is also terminated when the negative nominal current is reached. Fast decay is after on time. 175 | blank_time | 16, 24,
36, 54| uint8_t | Set comparator blank time to 16, 24, 36 or 54 clocks.
Hint: 24 or 36 is recommended for most applications
Initialized to 36 (register value = 3) by begin() 176 | high_sense_R | 0/1 | bool | 0: Low sensitivity, high sense resistor voltage
1: High sensitivity, low sense resistor voltage 177 | fullstep_threshold | 0/1 | bool | This bit enables switching to fullstep, when VHIGH is exceeded. Switching takes place only at 45° position. The fullstep target current uses the current value from the microstep table at the 45° position. 178 | high_speed_mode | 0/1 | bool | This bit enables switching to chm=1 and fd=0, when VHIGH is exceeded. This way, a higher velocity can be achieved. Can be combined with vhighfs=1. If set, the TOFF setting automatically becomes doubled during high velocity operation in order to avoid doubling of the chopper frequency. 179 | sync_phases | 0..15 | bool | Synchronization of the chopper for both phases of a two phase motor in order to avoid the occurrence of a beat, especially at low motor velocities. It is automatically switched off above VHIGH. 180 | microsteps | 255, 128, 64, 32, 16,
8, 4, 2, 0 (FULLSTEP) | uint8_t | Reduced microstep resolution for Step/Dir operation. The resolution gives the number of microstep entries per sine quarter wave. 181 | interpolate | 0/1 | bool | The actual microstep resolution becomes extrapolated to 256 microsteps for smoothest motor operation. 182 | double_edge_step | 0/1 | bool | Enable step impulse at each step edge to reduce step frequency requirement. 183 | disable_short_protection| 0/1 | bool | 0: Short to GND protection is on
1: Short to GND protection is disabled 184 | 185 | ### REG_COOLCONF register 186 | Function | Argument | Returns | Description 187 | --------------------|------------|----------|----------------------------- 188 | COOLCONF | - | uint32_t | Read actual bits from the register 189 | sg_min | 0..15 | uint8_t | If the stallGuard2 result falls below sg_min*32, the motor current becomes increased to reduce motor load angle. 190 | sg_max | 0..15 | uint8_t | If the stallGuard2 result is equal to or above (sg_min+sg_max+1)*32, the motor current becomes decreased to save energy. 191 | sg_step_width | 1, 2, 4, 8 | uint8_t | Current increment steps per measured stallGuard2 value 192 | sg_current_decrease | 1, 2, 8, 32| uint8_t | For each (value) stallGuard2 values decrease by one 193 | smart_min_current | uint8_t | uint8_t | 0: 1/2 of current setting (IRUN)
1: 1/4 of current setting (IRUN) 194 | sg_stall_value | int8_t | int8_t | This signed value controls stallGuard2 level for stall output and sets the optimum measurement range for readout. A lower value gives a higher sensitivity. Zero is the starting value working with most motors. -64 to +63: A higher value makes stallGuard2 less sensitive and requires more torque to indicate a stall. 195 | sg_filter | uint8_t | uint8_t | 0: Standard mode, high time resolution for stallGuard2
1: Filtered mode, stallGuard2 signal updated for each four fullsteps (resp. six fullsteps for 3 phase motor) only to compensate for motor pole tolerances 196 | 197 | ### REG_PWMCONF register 198 | Function | Argument | Returns | Description 199 | --------------------|-----------|----------|----------------------------- 200 | PWMCONF | - | uint32_t | Read actual bits from the register 201 | stealth_amplitude | 0..255 | uint8_t | pwm_ autoscale=0
User defined PWM amplitude offset (0-255) The resulting amplitude (limited to 0…255) is: PWM_AMPL + PWM_GRAD * 256 / TSTEP

pwm_ autoscale=1
User defined maximum PWM amplitude when switching back from current chopper mode to voltage PWM mode (switch over velocity defined by TPWMTHRS). Do not set too low values, as the regulation cannot measure the current when the actual PWM value goes below a setting specific value. Settings above 0x40 recommended. 202 | stealth_gradient | 0..255 | uint8_t | pwm_ autoscale=0
Velocity dependent gradient for PWM amplitude: PWM_GRAD * 256 / TSTEP is added to PWM_AMPL

pwm_ autoscale=1
User defined maximum PWM amplitude change per half wave (1 to 15) 203 | stealth_freq | 0..3 | uint8_t | 0: fPWM=2/1024 fCLK
1: fPWM=2/683 fCLK
2: fPWM=2/512 fCLK
3: fPWM=2/410 fCLK 204 | stealth_autoscale | 0/1 | bool | 0: User defined PWM amplitude. The current settings have no influence.
1: Enable automatic current control Attention: When using a user defined sine wave table, the amplitude of this sine wave table should not be less than 244. Best results are obtained with 247 to 252 as peak values. 205 | stealth_symmetric | 0/1 | bool | 0: The PWM value may change within each PWM cycle (standard mode)
1: A symmetric PWM cycle is enforced 206 | standstill_mode | 0..3 | uint8_t | Stand still option when motor current setting is zero (I_HOLD=0).
0: Normal operation
1: Freewheeling
2: Coil shorted using LS drivers
3: Coil shorted using HS drivers 207 | 208 | ### REG_DRVSTATUS register 209 | Function | Argument | Returns | Description 210 | ------------|-----------|-----------|----------------------------- 211 | DRVSTATUS | - | uint32_t | Read actual bits from the register 212 | 213 | ### REG_PWM_SCALE register 214 | Function | Argument | Returns | Description 215 | ------------|-----------|-----------|----------------------------- 216 | PWM_SCALE | - | uint32_t | Read actual bits from the register 217 | 218 | ### REG_ENCM_CTRL register 219 | Function | Argument | Returns | Description 220 | ----------------|-----------|-----------|----------------------------- 221 | invert_encoder | 0/1 | bool | Invert encoder inputs 222 | maxspeed | 0/1 | bool | Ignore Step input. If set, the hold current IHOLD determines the motor current, unless a step source is activated 223 | 224 | ### REG_LOST_STEPS register 225 | Function | Argument | Returns | Description 226 | ------------|-----------|-----------|----------------------------- 227 | LOST_STEPS | - | uint32_t | Read actual bits from the register 228 | 229 | ### Read raw registry: 230 | -------------------------------------------------------------------------------- /examples/Calibrate_spreadCycle/Calibrate_spreadCycle.ino: -------------------------------------------------------------------------------- 1 | /* 2 | * Author: Teemu Mäntykallio 3 | */ 4 | 5 | #include 6 | 7 | #define EN_PIN 38 // Nano v3: 16 Mega: 38 //enable (CFG6) 8 | #define DIR_PIN 55 // 19 55 //direction 9 | #define STEP_PIN 54 // 18 54 //step 10 | #define CS_PIN 40 // 17 64 //chip select 11 | #define STEP_PORT PORTF // Register to match with STEP_PIN 12 | #define STEP_BIT 0 // Bit in register to match STEP_PIN 13 | 14 | TMC2130Stepper driver = TMC2130Stepper(CS_PIN); 15 | 16 | // You can define starting values here: 17 | struct { 18 | uint8_t blank_time = 24; // [16, 24, 36, 54] 19 | uint8_t off_time = 3; // [1..15] 20 | uint8_t hysteresis_start = 1; // [1..8] 21 | int8_t hysteresis_end = 12; // [-3..12] 22 | } config; 23 | 24 | void initPins(); 25 | 26 | ISR(TIMER1_COMPA_vect){ 27 | STEP_PORT |= 1 << STEP_BIT; 28 | STEP_PORT &= ~(1 << STEP_BIT); 29 | } 30 | 31 | void reportCurrentSettings() { 32 | Serial.print("Off time = "); 33 | Serial.print(config.off_time); 34 | Serial.print(" Hysteresis end = "); 35 | Serial.print(config.hysteresis_end); 36 | Serial.print(" Hysteresis start = "); 37 | Serial.println(config.hysteresis_start); 38 | } 39 | 40 | void setup() { 41 | initPins(); 42 | Serial.begin(250000); 43 | Serial.println(F("Starting calibration of TMC spreadCycle parameters.")); 44 | Serial.println(F("This example by default uses X axis driver on a RAMPS1.4.")); 45 | Serial.println(F("First make sure your serial terminal sends newline ending only!")); 46 | for (uint8_t i = 0; i < 60; i++) { Serial.print('.'); delay(100); } 47 | Serial.println(F("\nThen make sure the belt is disconnected")); 48 | Serial.println(F("as we will not respect endstops or physical limits")); 49 | while(1) { 50 | Serial.println(F("Is the belt disconnected? Send 'yes' to confirm.")); 51 | while(!Serial.available()); 52 | String yn = Serial.readStringUntil('\n'); 53 | Serial.println(yn); 54 | if (yn == "yes") { 55 | break; 56 | } else { 57 | Serial.println(F("Belt still connected.")); 58 | Serial.println(F("Please disconnect belt.")); 59 | }; 60 | } 61 | 62 | Serial.println(F("\nNow make sure the driver has 12V (or greater) power turned on.")); 63 | while(1) { 64 | Serial.println(F("Is VMOT power on? Send 'yes' to confirm")); 65 | while(!Serial.available()); 66 | String yn = Serial.readStringUntil('\n'); 67 | Serial.println(yn); 68 | if (yn == "yes") { 69 | break; 70 | } else { 71 | Serial.println(F("Please turn on power to the driver.")); 72 | }; 73 | } 74 | 75 | Serial.print(F("\nTesting connection...")); 76 | uint8_t result = driver.test_connection(); 77 | if (result) { 78 | Serial.println(F("failed!")); 79 | Serial.print(F("Likely cause: ")); 80 | switch(result) { 81 | case 1: Serial.println(F("loose connection")); break; 82 | case 2: Serial.println(F("Likely cause: no power")); break; 83 | } 84 | Serial.println(F("Fix the problem and reset board.")); 85 | abort(); 86 | } 87 | Serial.println(F("OK")); 88 | 89 | driver.push(); 90 | driver.microsteps(256); 91 | driver.irun(10); 92 | driver.ihold(10); 93 | 94 | Serial.print(F("Setting driver blank time to ")); 95 | Serial.print(config.blank_time); 96 | Serial.println(F(" cycles.")); 97 | driver.blank_time(config.blank_time); 98 | 99 | Serial.print(F("Setting driver off time to ")); 100 | Serial.println(config.off_time); 101 | driver.off_time(config.off_time); 102 | 103 | Serial.print(F("Setting hysteresis end value to ")); 104 | Serial.println(config.hysteresis_end); 105 | driver.hysteresis_end(config.hysteresis_end); 106 | 107 | Serial.print(F("Setting hysteresis start value to ")); 108 | Serial.println(config.hysteresis_start); 109 | driver.hysteresis_start(config.hysteresis_start); 110 | 111 | Serial.print(F("Effective hysteresis = ")); 112 | Serial.print(config.hysteresis_end); 113 | Serial.print(F(" + ")); 114 | Serial.print(config.hysteresis_start); 115 | Serial.print(F(" = ")); 116 | Serial.println(config.hysteresis_end + config.hysteresis_start); 117 | 118 | Serial.println(F("\nNow we start decreasing the hysteresis end setting.")); 119 | Serial.println(F("You should first hear your motor making clearly audible noise.")); 120 | Serial.println(F("As we tune the timings the noise will get higher pitched.")); 121 | Serial.println(F("When the noise is no longer audible we have reached a good setting.")); 122 | Serial.println(F("You can tune the setting by sending - (minus) character")); 123 | Serial.println(F("or you can go back to previous parameter by sending + (plus) character.")); 124 | Serial.println(F("Sending = (equal) character move to the next phase.")); 125 | 126 | digitalWrite(EN_PIN, LOW); 127 | while (driver.cur_a() < 240) { // Use cur_b if measuring from B coil 128 | digitalWrite(STEP_PIN, HIGH); 129 | digitalWrite(STEP_PIN, LOW); 130 | delay(3); 131 | } 132 | 133 | while(1) { 134 | if (Serial.available() > 0) { 135 | uint8_t c = Serial.read(); 136 | if (c == '+') { 137 | if (config.hysteresis_end == 12) Serial.println(F("Reached MAX setting already!")); 138 | else { 139 | config.hysteresis_end++; 140 | reportCurrentSettings(); 141 | driver.hysterisis_end(config.hysteresis_end); 142 | } 143 | } else if (c == '-') { 144 | if (config.hysteresis_end == -3) Serial.println(F("Reached MIN setting already!")); 145 | else { 146 | config.hysteresis_end--; 147 | reportCurrentSettings(); 148 | driver.hysterisis_end(config.hysteresis_end); 149 | } 150 | } 151 | else if (c == '=') break; 152 | } 153 | } 154 | 155 | Serial.print(F("Final effective hysteresis = ")); 156 | Serial.print(config.hysteresis_end); 157 | Serial.print(F(" + ")); 158 | Serial.print(config.hysteresis_start); 159 | Serial.print(F(" = ")); 160 | Serial.println(config.hysteresis_end + config.hysteresis_start); 161 | Serial.println(F("Your configuration parameters in Marlin are:")); 162 | Serial.print(F("#define CHOPPER_TIMING ")); 163 | Serial.print(config.off_time); 164 | Serial.print(F(" ")); 165 | Serial.print(config.hysteresis_end); 166 | Serial.print(F(" ")); 167 | Serial.print(config.hysteresis_start); 168 | } 169 | 170 | void initPins() { 171 | pinMode(EN_PIN, OUTPUT); 172 | pinMode(DIR_PIN, OUTPUT); 173 | pinMode(STEP_PIN, OUTPUT); 174 | pinMode(CS_PIN, OUTPUT); 175 | digitalWrite(EN_PIN, HIGH); //deactivate driver (LOW active) 176 | digitalWrite(DIR_PIN, LOW); //LOW or HIGH 177 | digitalWrite(STEP_PIN, LOW); 178 | digitalWrite(CS_PIN, HIGH); 179 | SPI.begin(); 180 | pinMode(MISO, INPUT_PULLUP); 181 | } 182 | 183 | void loop() {} -------------------------------------------------------------------------------- /examples/Live_tune/Live_tune.ino: -------------------------------------------------------------------------------- 1 | #define EN_PIN 38 // Nano v3: 16 Mega: 38 //enable (CFG6) 2 | #define DIR_PIN 55 // 19 55 //direction 3 | #define STEP_PIN 54 // 18 54 //step 4 | #define CS_PIN 40 // 17 40 //chip select 5 | #define STEP_PORT PORTF 6 | #define STEP_BIT 0 7 | 8 | int speed = 10; 9 | bool running = false; 10 | float Rsense = 0.11; 11 | float hold_x = 0.5; 12 | boolean toggle1 = 0; 13 | uint8_t stall_value = 9; 14 | volatile uint32_t step_counter = 0; 15 | const uint32_t steps_per_mm = 80 * 16; // @ 256 microsteps 16 | const uint16_t fsteps_per_rotation = 200; 17 | const uint32_t MHz = 16000000>>8; // Scaled by 256 18 | const uint16_t acceleration = 2000; 19 | 20 | #include 21 | TMC2130Stepper myStepper = TMC2130Stepper(CS_PIN); 22 | 23 | ISR(TIMER1_COMPA_vect){ 24 | STEP_PORT |= 1 << STEP_BIT; 25 | STEP_PORT &= ~(1 << STEP_BIT); 26 | step_counter++; 27 | } 28 | 29 | void initTimer() { 30 | cli();//stop interrupts 31 | //set timer1 interrupt at 10kHz => 10000 steps/s => ~ 20 fullsteps/s 32 | TCCR1A = 0; // set entire TCCR1A register to 0 33 | TCCR1B = 0; // same for TCCR1B 34 | TCNT1 = 0; //initialize counter value to 0 35 | // set compare match register for 2kHz increments 36 | OCR1A = 61;// = (16*10^6) / (8*2000) - 1 (must be <65536) 37 | // turn on CTC mode 38 | TCCR1B |= (1 << WGM12); 39 | // Set CS01 bit for no prescaler 40 | TCCR1B |= (1 << CS10); 41 | // enable/disable timer compare interrupt on start 42 | //TIMSK1 |= (1 << OCIE1A); 43 | TIMSK1 &= ~(1 << OCIE1A); 44 | sei();//allow interrupts 45 | } 46 | 47 | uint16_t calculateMMSTimer(uint8_t mms) { 48 | uint32_t steps_per_second = mms * steps_per_mm; 49 | steps_per_second >>= 8; 50 | uint32_t tmr = MHz / steps_per_second - 1; 51 | return tmr; 52 | } 53 | uint16_t calculateFSPSTimer(uint16_t fsps) { 54 | return MHz / fsps - 1; 55 | } 56 | uint16_t calculateRPSTimer(uint8_t rps) { 57 | return MHz / (rps * fsteps_per_rotation) - 1; 58 | } 59 | 60 | void accelerationRamp(uint16_t maxMMS = 100) { 61 | TIMSK1 &= ~(1 << OCIE1A); 62 | while (myStepper.cur_a() != 0) { // Use cur_b if measuring from B coil 63 | digitalWrite(STEP_PIN, HIGH); 64 | digitalWrite(STEP_PIN, LOW); 65 | delay(1); 66 | } 67 | delay(100); 68 | digitalWrite(EN_PIN, HIGH); 69 | uint16_t mms = 2; 70 | uint16_t maxOCR1A = calculateMMSTimer(maxMMS); 71 | uint16_t _OCR1A = calculateMMSTimer(mms); 72 | digitalWrite(EN_PIN, LOW); 73 | OCR1A = _OCR1A; 74 | TIMSK1 |= 1 << OCIE1A; 75 | for (; mms <= maxMMS; mms += acceleration) { 76 | delay(1); 77 | OCR1A = calculateMMSTimer(mms); 78 | } 79 | cli(); 80 | step_counter = 0; 81 | sei(); 82 | while (step_counter <= 100*steps_per_mm); 83 | for (; mms >= 2; mms -= acceleration) { 84 | delay(1); 85 | OCR1A = calculateMMSTimer(mms); 86 | } 87 | } 88 | 89 | void serialTuple(String cmd, int arg) { 90 | Serial.print("Received command: "); 91 | Serial.print(cmd); 92 | Serial.print("("); 93 | Serial.print(arg); 94 | Serial.println(")"); 95 | } 96 | 97 | void setup() { 98 | initTimer(); 99 | Serial.begin(500000); 100 | 101 | pinMode(EN_PIN, OUTPUT); 102 | pinMode(DIR_PIN, OUTPUT); 103 | pinMode(STEP_PIN, OUTPUT); 104 | pinMode(CS_PIN, OUTPUT); 105 | digitalWrite(EN_PIN, HIGH); //deactivate driver (LOW active) 106 | digitalWrite(DIR_PIN, LOW); //LOW or HIGH 107 | digitalWrite(STEP_PIN, LOW); 108 | digitalWrite(CS_PIN, HIGH); 109 | SPI.begin(); 110 | pinMode(MISO, INPUT_PULLUP); 111 | 112 | myStepper.push(); 113 | myStepper.tbl(1); //blank_time(24); 114 | myStepper.power_down_delay(255); 115 | myStepper.toff(4); 116 | 117 | // Effective hysteresis = 0 118 | myStepper.hstrt(0); 119 | myStepper.hend(2); 120 | 121 | myStepper.en_pwm_mode(true); 122 | myStepper.pwm_freq(1); 123 | myStepper.pwm_autoscale(true); 124 | myStepper.pwm_ampl(180); 125 | myStepper.pwm_grad(1); 126 | 127 | myStepper.rms_current(600); // mA 128 | myStepper.microsteps(256); 129 | myStepper.diag1_stall(1); 130 | myStepper.diag1_active_high(1); 131 | digitalWrite(EN_PIN, LOW); 132 | 133 | while (myStepper.cur_a() < 240) { // Use cur_b if measuring from B coil 134 | digitalWrite(STEP_PIN, HIGH); 135 | digitalWrite(STEP_PIN, LOW); 136 | delay(3); 137 | } 138 | Serial.print("cur_a = "); 139 | Serial.println(myStepper.cur_a(), DEC); 140 | Serial.print("cur_b = "); 141 | Serial.println(myStepper.cur_b(), DEC); 142 | } 143 | 144 | void loop() { 145 | if (Serial.available() > 0) { 146 | String cmd = Serial.readStringUntil(' '); 147 | String strArg = Serial.readStringUntil('\n'); 148 | 149 | int arg = strArg.toInt(); 150 | 151 | if (cmd == "run") { 152 | serialTuple("run", arg); 153 | running = arg; 154 | arg ? TIMSK1 |= 1 << OCIE1A : TIMSK1 &= ~(1 << OCIE1A); 155 | //arg ? digitalWrite(EN_PIN, LOW) : digitalWrite(EN_PIN, HIGH); 156 | } 157 | 158 | else if (cmd == "mms") { 159 | serialTuple("mms", arg); 160 | cli(); 161 | TCNT1 = 0; 162 | OCR1A = calculateMMSTimer(arg); 163 | Serial.print("Set OCR1A to "); 164 | Serial.println(OCR1A); 165 | sei(); 166 | } 167 | else if (cmd == "fsps") { 168 | serialTuple("fsps", arg); 169 | cli(); 170 | OCR1A = calculateFSPSTimer(arg); 171 | Serial.print("Set OCR1A to "); 172 | Serial.println(OCR1A); 173 | sei(); 174 | } 175 | else if (cmd == "rps") { 176 | serialTuple("rps", arg); 177 | cli(); 178 | OCR1A = calculateRPSTimer(arg); 179 | Serial.print("Set OCR1A to "); 180 | Serial.println(OCR1A); 181 | sei(); 182 | } 183 | else if (cmd == "setCurrent") { 184 | serialTuple("setCurrent", arg); 185 | myStepper.setCurrent(arg, Rsense, hold_x); 186 | } 187 | else if (cmd == "find_pos") { 188 | serialTuple("find_pos", arg); 189 | TIMSK1 &= ~(1 << OCIE1A); 190 | while (myStepper.cur_a() != arg) { // Use cur_b if measuring from B coil 191 | digitalWrite(STEP_PIN, HIGH); 192 | digitalWrite(STEP_PIN, LOW); 193 | delay(1); 194 | } 195 | } 196 | else if (cmd == "rampTo") { 197 | serialTuple("rampTo", arg); 198 | accelerationRamp(arg); 199 | } 200 | else if (cmd == "Rsense") { 201 | Serial.print("Setting R sense value to: "); 202 | Serial.println(arg); 203 | Rsense = arg; 204 | } 205 | else if (cmd == "hold_multiplier") { 206 | Serial.print("Setting hold multiplier to: "); 207 | Serial.println(arg); 208 | hold_x = arg; 209 | } 210 | else if (cmd == "GCONF") { 211 | Serial.print("GCONF: 0b"); 212 | Serial.println(myStepper.GCONF(), BIN); 213 | } 214 | else if (cmd == "I_scale_analog") { 215 | serialTuple("I_scale_analog", arg); 216 | myStepper.I_scale_analog(arg); 217 | } 218 | else if (cmd == "internal_Rsense") { 219 | serialTuple("internal_Rsense", arg); 220 | myStepper.internal_Rsense(arg); 221 | } 222 | else if (cmd == "en_pwm_mode") { 223 | serialTuple("en_pwm_mode", arg); 224 | myStepper.en_pwm_mode(arg); 225 | } 226 | else if (cmd == "enc_commutation") { 227 | serialTuple("enc_commutation", arg); 228 | myStepper.enc_commutation(arg); 229 | } 230 | else if (cmd == "shaft") { 231 | serialTuple("shaft", arg); 232 | myStepper.shaft(arg); 233 | } 234 | else if (cmd == "diag0_errors") { 235 | serialTuple("diag0_errors", arg); 236 | myStepper.diag0_errors(arg); 237 | } 238 | else if (cmd == "diag0_temp_prewarn") { 239 | serialTuple("diag0_temp_prewarn", arg); 240 | myStepper.diag0_temp_prewarn(arg); 241 | } 242 | else if (cmd == "diag0_stall") { 243 | serialTuple("diag0_stall", arg); 244 | myStepper.diag0_stall(arg); 245 | } 246 | else if (cmd == "diag1_stall") { 247 | serialTuple("diag1_stall", arg); 248 | myStepper.diag1_stall(arg); 249 | } 250 | else if (cmd == "diag1_index") { 251 | serialTuple("diag1_index", arg); 252 | myStepper.diag1_index(arg); 253 | } 254 | else if (cmd == "diag1_chopper_on") { 255 | serialTuple("diag1_chopper_on", arg); 256 | myStepper.diag1_chopper_on(arg); 257 | } 258 | else if (cmd == "diag0_active_high") { 259 | serialTuple("diag0_active_high", arg); 260 | myStepper.diag0_active_high(arg); 261 | } 262 | else if (cmd == "diag1_active_high") { 263 | serialTuple("diag1_active_high", arg); 264 | myStepper.diag1_active_high(arg); 265 | } 266 | else if (cmd == "small_hysteresis") { 267 | serialTuple("small_hysteresis", arg); 268 | myStepper.small_hysteresis(arg); 269 | } 270 | else if (cmd == "stop_enable") { 271 | serialTuple("stop_enable", arg); 272 | myStepper.stop_enable(arg); 273 | } 274 | else if (cmd == "direct_mode") { 275 | serialTuple("direct_mode", arg); 276 | myStepper.direct_mode(arg); 277 | } 278 | // IHOLD_IRUN 279 | else if (cmd == "ihold") { 280 | serialTuple("ihold", arg); 281 | myStepper.ihold(arg); 282 | } 283 | else if (cmd == "irun") { 284 | serialTuple("irun", arg); 285 | myStepper.irun(arg); 286 | } 287 | else if (cmd == "iholddelay") { 288 | serialTuple("iholddelay", arg); 289 | myStepper.iholddelay(arg); 290 | } 291 | 292 | else if (cmd == "microstep_time") { 293 | Serial.print("microstep_time: "); 294 | Serial.println(myStepper.microstep_time()); 295 | } 296 | 297 | else if (cmd == "TPWMTHRS") { 298 | serialTuple("TPWMTHRS", arg); 299 | myStepper.TPWMTHRS(arg); 300 | } 301 | else if (cmd == "TCOOLTHRS") { 302 | serialTuple("TCOOLTHRS", arg); 303 | myStepper.TCOOLTHRS(arg); 304 | } 305 | else if (cmd == "THIGH") { 306 | serialTuple("THIGH", arg); 307 | myStepper.THIGH(arg); 308 | } 309 | // XDIRECT 310 | else if (cmd == "coil_A") { 311 | serialTuple("coil_A", arg); 312 | myStepper.coil_A(arg); 313 | } 314 | else if (cmd == "coil_B") { 315 | serialTuple("coil_B", arg); 316 | myStepper.coil_B(arg); 317 | } 318 | 319 | else if (cmd == "VDCMIN") { 320 | serialTuple("VDCMIN", arg); 321 | myStepper.VDCMIN(arg); 322 | } 323 | 324 | else if (cmd == "CHOPCONF") { 325 | Serial.print("CHOPCONF: 0b"); 326 | Serial.println(myStepper.CHOPCONF(), BIN); 327 | } 328 | else if (cmd == "toff") { 329 | serialTuple("toff", arg); 330 | myStepper.toff(arg); 331 | } 332 | else if (cmd == "hstrt") { 333 | serialTuple("hstrt", arg); 334 | myStepper.hstrt(arg); 335 | } 336 | else if (cmd == "hend") { 337 | serialTuple("hend", arg); 338 | myStepper.hend(arg); 339 | } 340 | else if (cmd == "fd") { 341 | serialTuple("fd", arg); 342 | myStepper.fd(arg); 343 | } 344 | else if (cmd == "disfdcc") { 345 | serialTuple("disfdcc", arg); 346 | myStepper.disfdcc(arg); 347 | } 348 | else if (cmd == "rndtf") { 349 | serialTuple("rndtf", arg); 350 | myStepper.rndtf(arg); 351 | } 352 | else if (cmd == "chm") { 353 | serialTuple("chm", arg); 354 | myStepper.chm(arg); 355 | } 356 | else if (cmd == "tbl") { 357 | serialTuple("tbl", arg); 358 | myStepper.tbl(arg); 359 | } 360 | else if (cmd == "vsense") { 361 | serialTuple("vsense", arg); 362 | myStepper.vsense(arg); 363 | } 364 | else if (cmd == "vhighfs") { 365 | serialTuple("vhighfs", arg); 366 | myStepper.vhighfs(arg); 367 | } 368 | else if (cmd == "vhighchm") { 369 | serialTuple("vhighchm", arg); 370 | myStepper.vhighchm(arg); 371 | } 372 | else if (cmd == "sync") { 373 | serialTuple("sync", arg); 374 | myStepper.sync(arg); 375 | } 376 | else if (cmd == "mres") { 377 | serialTuple("mres", arg); 378 | myStepper.mres(arg); 379 | } 380 | else if (cmd == "intpol") { 381 | serialTuple("intpol", arg); 382 | myStepper.intpol(arg); 383 | } 384 | else if (cmd == "dedge") { 385 | serialTuple("dedge", arg); 386 | myStepper.dedge(arg); 387 | } 388 | else if (cmd == "diss2g") { 389 | serialTuple("diss2g", arg); 390 | myStepper.diss2g(arg); 391 | } 392 | // COOLCONF 393 | else if (cmd == "semin") { 394 | serialTuple("semin", arg); 395 | myStepper.semin(arg); 396 | } 397 | else if (cmd == "seup") { 398 | serialTuple("seup", arg); 399 | myStepper.seup(arg); 400 | } 401 | else if (cmd == "semax") { 402 | serialTuple("semax", arg); 403 | myStepper.semax(arg); 404 | } 405 | else if (cmd == "sedn") { 406 | serialTuple("sedn", arg); 407 | myStepper.sedn(arg); 408 | } 409 | else if (cmd == "seimin") { 410 | serialTuple("seimin", arg); 411 | myStepper.seimin(arg); 412 | } 413 | else if (cmd == "sgt") { 414 | serialTuple("sgt", arg); 415 | myStepper.sgt(arg); 416 | } 417 | else if (cmd == "sfilt") { 418 | serialTuple("sfilt", arg); 419 | myStepper.sfilt(arg); 420 | } 421 | // PWMCONF 422 | else if (cmd == "pwm_ampl") { 423 | serialTuple("pwm_ampl", arg); 424 | myStepper.pwm_ampl(arg); 425 | } 426 | else if (cmd == "pwm_grad") { 427 | serialTuple("pwm_grad", arg); 428 | myStepper.pwm_grad(arg); 429 | } 430 | else if (cmd == "pwm_freq") { 431 | serialTuple("pwm_freq", arg); 432 | myStepper.pwm_freq(arg); 433 | } 434 | else if (cmd == "pwm_autoscale") { 435 | serialTuple("pwm_autoscale", arg); 436 | myStepper.pwm_autoscale(arg); 437 | } 438 | else if (cmd == "pwm_symmetric") { 439 | serialTuple("pwm_symmetric", arg); 440 | myStepper.pwm_symmetric(arg); 441 | } 442 | else if (cmd == "freewheel") { 443 | serialTuple("freewheel", arg); 444 | myStepper.freewheel(arg); 445 | } 446 | // ENCM_CTRL 447 | else if (cmd == "inv") { 448 | serialTuple("inv", arg); 449 | myStepper.inv(arg); 450 | } 451 | else if (cmd == "maxspeed") { 452 | serialTuple("maxspeed", arg); 453 | myStepper.maxspeed(arg); 454 | } 455 | 456 | else if (cmd == "DRVSTATUS") { 457 | Serial.print("DRVSTATUS: 0b"); 458 | Serial.println(myStepper.DRV_STATUS(), BIN); 459 | } 460 | else if (cmd == "PWM_SCALE") { 461 | Serial.print("PWM_SCALE: 0b"); 462 | Serial.println(myStepper.PWM_SCALE(), DEC); 463 | } 464 | else if (cmd == "LOST_STEPS") { 465 | Serial.print("LOST_STEPS: 0b"); 466 | Serial.println(myStepper.LOST_STEPS(), DEC); 467 | } 468 | else { 469 | Serial.println("Invalid command!"); 470 | } 471 | } 472 | } 473 | -------------------------------------------------------------------------------- /examples/Simple/Simple.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Author Teemu Mäntykallio 3 | * Initializes the library and turns the motor in alternating directions. 4 | */ 5 | 6 | #define EN_PIN 38 // Nano v3: 16 Mega: 38 //enable (CFG6) 7 | #define DIR_PIN 55 // 19 55 //direction 8 | #define STEP_PIN 54 // 18 54 //step 9 | #define CS_PIN 40 // 17 64 //chip select 10 | 11 | bool dir = true; 12 | 13 | #include 14 | TMC2130Stepper driver = TMC2130Stepper(EN_PIN, DIR_PIN, STEP_PIN, CS_PIN); 15 | 16 | void setup() { 17 | Serial.begin(9600); 18 | while(!Serial); 19 | Serial.println("Start..."); 20 | SPI.begin(); 21 | pinMode(MISO, INPUT_PULLUP); 22 | driver.begin(); // Initiate pins and registeries 23 | driver.rms_current(600); // Set stepper current to 600mA. The command is the same as command TMC2130.setCurrent(600, 0.11, 0.5); 24 | driver.stealthChop(1); // Enable extremely quiet stepping 25 | 26 | digitalWrite(EN_PIN, LOW); 27 | } 28 | 29 | void loop() { 30 | digitalWrite(STEP_PIN, HIGH); 31 | delayMicroseconds(10); 32 | digitalWrite(STEP_PIN, LOW); 33 | delayMicroseconds(10); 34 | uint32_t ms = millis(); 35 | static uint32_t last_time = 0; 36 | if ((ms - last_time) > 2000) { 37 | if (dir) { 38 | Serial.println("Dir -> 0"); 39 | driver.shaft_dir(0); 40 | } else { 41 | Serial.println("Dir -> 1"); 42 | driver.shaft_dir(1); 43 | } 44 | dir = !dir; 45 | last_time = ms; 46 | } 47 | } 48 | -------------------------------------------------------------------------------- /examples/Software_SPI/Software_SPI.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Author Teemu Mäntykallio 3 | * Initializes the library and turns the motor in alternating directions. 4 | */ 5 | 6 | #define EN_PIN 7 // Nano v3: 16 Mega: 38 //enable (CFG6) 7 | #define DIR_PIN 6 // 19 55 //direction 8 | #define STEP_PIN 5 // 18 54 //step 9 | #define CS_PIN 8 // 17 64 //chip select 10 | #define MOSI_PIN 9 11 | #define MISO_PIN 10 12 | #define SCK_PIN 11 13 | 14 | bool dir = true; 15 | 16 | #include 17 | TMC2130Stepper driver = TMC2130Stepper(EN_PIN, DIR_PIN, STEP_PIN, CS_PIN, MOSI_PIN, MISO_PIN, SCK_PIN); 18 | 19 | void setup() { 20 | Serial.begin(9600); 21 | while(!Serial); 22 | Serial.println("Start..."); 23 | driver.begin(); // Initiate pins and registeries 24 | driver.rms_current(600); // Set stepper current to 600mA. The command is the same as command TMC2130.setCurrent(600, 0.11, 0.5); 25 | driver.stealthChop(1); // Enable extremely quiet stepping 26 | 27 | digitalWrite(EN_PIN, LOW); 28 | 29 | Serial.print("DRV_STATUS=0b"); 30 | Serial.println(driver.DRV_STATUS(), BIN); 31 | } 32 | 33 | void loop() { 34 | digitalWrite(STEP_PIN, HIGH); 35 | delayMicroseconds(10); 36 | digitalWrite(STEP_PIN, LOW); 37 | delayMicroseconds(10); 38 | uint32_t ms = millis(); 39 | static uint32_t last_time = 0; 40 | if ((ms - last_time) > 2000) { 41 | if (dir) { 42 | Serial.println("Dir -> 0"); 43 | driver.shaft_dir(0); 44 | } else { 45 | Serial.println("Dir -> 1"); 46 | driver.shaft_dir(1); 47 | } 48 | dir = !dir; 49 | last_time = ms; 50 | } 51 | } 52 | -------------------------------------------------------------------------------- /examples/StallGuard/StallGuard.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Author Teemu Mäntykallio 3 | * 4 | * Plot TMC2130 motor load using the stallGuard value. 5 | * You can finetune the reading by changing the STALL_VALUE. 6 | * This will let you control at which load the value will read 0 7 | * and the stall flag will be triggered. This will also set pin DIAG1 high. 8 | * A higher STALL_VALUE will make the reading less sensitive and 9 | * a lower STALL_VALUE will make it more sensitive. 10 | * 11 | * You can control the rotation speed with 12 | * 0 Stop 13 | * 1 Resume 14 | * + Speed up 15 | * - Slow down 16 | */ 17 | #define MAX_SPEED 40 // In timer value 18 | #define MIN_SPEED 1000 19 | 20 | #define STALL_VALUE 0 // [-64..63] 21 | 22 | // Note: You also have to connect GND, 5V and VM. 23 | // A connection diagram can be found in the schematics. 24 | #define EN_PIN 38 // Nano v3: 16 Mega: 38 //enable (CFG6) 25 | #define DIR_PIN 55 // 19 55 //direction 26 | #define STEP_PIN 54 // 18 54 //step 27 | #define CS_PIN 40 // 17 64 //chip select 28 | 29 | #include 30 | #include 31 | TMC2130Stepper driver = TMC2130Stepper(CS_PIN); 32 | 33 | bool vsense; 34 | 35 | uint16_t rms_current(uint8_t CS, float Rsense = 0.11) { 36 | return (float)(CS+1)/32.0 * (vsense?0.180:0.325)/(Rsense+0.02) / 1.41421 * 1000; 37 | } 38 | 39 | void setup() { 40 | //init serial port 41 | { 42 | Serial.begin(250000); //init serial port and set baudrate 43 | while(!Serial); //wait for serial port to connect (needed for Leonardo only) 44 | Serial.println("\nStart..."); 45 | pinMode(EN_PIN, OUTPUT); 46 | pinMode(DIR_PIN, OUTPUT); 47 | pinMode(STEP_PIN, OUTPUT); 48 | pinMode(CS_PIN, OUTPUT); 49 | digitalWrite(EN_PIN, HIGH); //deactivate driver (LOW active) 50 | digitalWrite(DIR_PIN, LOW); //LOW or HIGH 51 | digitalWrite(STEP_PIN, LOW); 52 | digitalWrite(CS_PIN, HIGH); 53 | SPI.begin(); 54 | pinMode(MISO, INPUT_PULLUP); 55 | } 56 | 57 | //set TMC2130 config 58 | { 59 | driver.push(); 60 | driver.toff(3); 61 | driver.tbl(1); 62 | driver.hysteresis_start(4); 63 | driver.hysteresis_end(-2); 64 | driver.rms_current(600); // mA 65 | driver.microsteps(16); 66 | driver.diag1_stall(1); 67 | driver.diag1_active_high(1); 68 | driver.coolstep_min_speed(0xFFFFF); // 20bit max 69 | driver.THIGH(0); 70 | driver.semin(5); 71 | driver.semax(2); 72 | driver.sedn(0b01); 73 | driver.sg_stall_value(STALL_VALUE); 74 | } 75 | 76 | // Set stepper interrupt 77 | { 78 | cli();//stop interrupts 79 | TCCR1A = 0;// set entire TCCR1A register to 0 80 | TCCR1B = 0;// same for TCCR1B 81 | TCNT1 = 0;//initialize counter value to 0 82 | OCR1A = 256;// = (16*10^6) / (1*1024) - 1 (must be <65536) 83 | // turn on CTC mode 84 | TCCR1B |= (1 << WGM12); 85 | // Set CS11 bits for 8 prescaler 86 | TCCR1B |= (1 << CS11);// | (1 << CS10); 87 | // enable timer compare interrupt 88 | TIMSK1 |= (1 << OCIE1A); 89 | sei();//allow interrupts 90 | } 91 | 92 | //TMC2130 outputs on (LOW active) 93 | digitalWrite(EN_PIN, LOW); 94 | 95 | vsense = driver.vsense(); 96 | } 97 | 98 | ISR(TIMER1_COMPA_vect){ 99 | PORTF |= 1 << 0; 100 | PORTF &= ~(1 << 0); 101 | } 102 | 103 | void loop() 104 | { 105 | static uint32_t last_time=0; 106 | uint32_t ms = millis(); 107 | 108 | while(Serial.available() > 0) { 109 | int8_t read_byte = Serial.read(); 110 | if (read_byte == '0') { TIMSK1 &= ~(1 << OCIE1A); digitalWrite( EN_PIN, HIGH ); } 111 | else if (read_byte == '1') { TIMSK1 |= (1 << OCIE1A); digitalWrite( EN_PIN, LOW ); } 112 | else if (read_byte == '+') if (OCR1A > MAX_SPEED) OCR1A -= 20; 113 | else if (read_byte == '-') if (OCR1A < MIN_SPEED) OCR1A += 20; 114 | } 115 | 116 | if((ms-last_time) > 100) //run every 0.1s 117 | { 118 | last_time = ms; 119 | uint32_t drv_status = driver.DRV_STATUS(); 120 | Serial.print("0 "); 121 | Serial.print((drv_status & SG_RESULT_bm)>>SG_RESULT_bp , DEC); 122 | Serial.print(" "); 123 | Serial.println(rms_current((drv_status & CS_ACTUAL_bm)>>CS_ACTUAL_bp), DEC); 124 | } 125 | } 126 | 127 | -------------------------------------------------------------------------------- /examples/TMC2130_AccelStepper/TMC2130_AccelStepper.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Author Teemu Mäntykallio 3 | * Initializes the library and turns the motor in alternating directions. 4 | */ 5 | 6 | #define EN_PIN 38 // Nano v3: 16 Mega: 38 //enable (CFG6) 7 | #define DIR_PIN 55 // 19 55 //direction 8 | #define STEP_PIN 54 // 18 54 //step 9 | #define CS_PIN 40 // 17 40 //chip select 10 | 11 | constexpr uint32_t steps_per_mm = 80; 12 | 13 | #include 14 | TMC2130Stepper driver = TMC2130Stepper(EN_PIN, DIR_PIN, STEP_PIN, CS_PIN); 15 | 16 | #include 17 | AccelStepper stepper = AccelStepper(stepper.DRIVER, STEP_PIN, DIR_PIN); 18 | 19 | void setup() { 20 | SPI.begin(); 21 | Serial.begin(9600); 22 | while(!Serial); 23 | Serial.println("Start..."); 24 | pinMode(CS_PIN, OUTPUT); 25 | digitalWrite(CS_PIN, HIGH); 26 | driver.begin(); // Initiate pins and registeries 27 | driver.rms_current(600); // Set stepper current to 600mA. The command is the same as command TMC2130.setCurrent(600, 0.11, 0.5); 28 | driver.stealthChop(1); // Enable extremely quiet stepping 29 | driver.stealth_autoscale(1); 30 | driver.microsteps(16); 31 | 32 | stepper.setMaxSpeed(50*steps_per_mm); // 100mm/s @ 80 steps/mm 33 | stepper.setAcceleration(1000*steps_per_mm); // 2000mm/s^2 34 | stepper.setEnablePin(EN_PIN); 35 | stepper.setPinsInverted(false, false, true); 36 | stepper.enableOutputs(); 37 | } 38 | 39 | void loop() { 40 | if (stepper.distanceToGo() == 0) { 41 | stepper.disableOutputs(); 42 | delay(100); 43 | stepper.move(100*steps_per_mm); // Move 100mm 44 | stepper.enableOutputs(); 45 | } 46 | stepper.run(); 47 | } 48 | -------------------------------------------------------------------------------- /extras/Fritzing/SilentStepStick-TMC2130-part.fzpz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/teemuatlut/TMC2130Stepper/6af7aef0f3f43c007711a8fcf6cf41062ef58970/extras/Fritzing/SilentStepStick-TMC2130-part.fzpz -------------------------------------------------------------------------------- /extras/Fritzing/TMC2130-breadboard.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | image/svg+xml -------------------------------------------------------------------------------- /extras/Fritzing/TMC2130-sample-circuit .fzz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/teemuatlut/TMC2130Stepper/6af7aef0f3f43c007711a8fcf6cf41062ef58970/extras/Fritzing/TMC2130-sample-circuit .fzz -------------------------------------------------------------------------------- /extras/Fritzing/TMC2130-sample-circuit .png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/teemuatlut/TMC2130Stepper/6af7aef0f3f43c007711a8fcf6cf41062ef58970/extras/Fritzing/TMC2130-sample-circuit .png -------------------------------------------------------------------------------- /extras/Fritzing/TMC2130-schematic.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | image/svg+xmlTMC2130 341 | DIR 354 | STEP 367 | NC 380 | SDO 393 | CS 406 | SCK 419 | SDI 432 | EN 445 | GND 458 | VIO 471 | M1B 484 | M1A 497 | M2A 510 | M2B 523 | GND 536 | VM 549 | -------------------------------------------------------------------------------- /extras/TMC5130_TMC2130_TMC2100_Calculations.xlsx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/teemuatlut/TMC2130Stepper/6af7aef0f3f43c007711a8fcf6cf41062ef58970/extras/TMC5130_TMC2130_TMC2100_Calculations.xlsx -------------------------------------------------------------------------------- /keywords.txt: -------------------------------------------------------------------------------- 1 | ####################################### 2 | # Syntax Coloring Map For Test 3 | ####################################### 4 | 5 | ####################################### 6 | # Datatypes (KEYWORD1) 7 | ####################################### 8 | 9 | TMC2130Stepper KEYWORD1 10 | 11 | ####################################### 12 | # Methods and Functions (KEYWORD2) 13 | ####################################### 14 | 15 | begin KEYWORD2 16 | checkStatus KEYWORD2 17 | SilentStepStick2130 KEYWORD2 18 | setCurrent KEYWORD2 19 | checkOT KEYWORD2 20 | getOTPW KEYWORD2 21 | clear_otpw KEYWORD2 22 | isEnabled KEYWORD2 23 | push KEYWORD2 24 | GCONF KEYWORD2 25 | external_ref KEYWORD2 26 | internal_sense_R KEYWORD2 27 | stealthChop KEYWORD2 28 | commutation KEYWORD2 29 | shaft_dir KEYWORD2 30 | diag0_errors KEYWORD2 31 | diag0_temp_prewarn KEYWORD2 32 | diag0_stall KEYWORD2 33 | diag1_stall KEYWORD2 34 | diag1_index KEYWORD2 35 | diag1_chopper_on KEYWORD2 36 | diag1_steps_skipped KEYWORD2 37 | diag0_active_high KEYWORD2 38 | diag1_active_high KEYWORD2 39 | small_hysteresis KEYWORD2 40 | stop_enable KEYWORD2 41 | direct_mode KEYWORD2 42 | hold_current KEYWORD2 43 | run_current KEYWORD2 44 | hold_delay KEYWORD2 45 | power_down_delay KEYWORD2 46 | status_flags KEYWORD2 47 | input KEYWORD2 48 | microstep_time KEYWORD2 49 | stealth_max_speed KEYWORD2 50 | coolstep_min_speed KEYWORD2 51 | mode_sw_speed KEYWORD2 52 | coil_A_current KEYWORD2 53 | coil_B_current KEYWORD2 54 | DCstep_min_speed KEYWORD2 55 | CHOPCONF KEYWORD2 56 | off_time KEYWORD2 57 | hysteresis_start KEYWORD2 58 | fast_decay_time KEYWORD2 59 | hysteresis_end KEYWORD2 60 | sine_offset KEYWORD2 61 | disable_I_comparator KEYWORD2 62 | random_off_time KEYWORD2 63 | chopper_mode KEYWORD2 64 | blank_time KEYWORD2 65 | high_sense_R KEYWORD2 66 | fullstep_threshold KEYWORD2 67 | high_speed_mode KEYWORD2 68 | sync_phases KEYWORD2 69 | microsteps KEYWORD2 70 | interpolate KEYWORD2 71 | double_edge_step KEYWORD2 72 | disable_short_protection KEYWORD2 73 | sg_min KEYWORD2 74 | sg_step_width KEYWORD2 75 | sg_max KEYWORD2 76 | sg_current_decrease KEYWORD2 77 | smart_min_current KEYWORD2 78 | sg_stall_value KEYWORD2 79 | sg_filter KEYWORD2 80 | stealth_amplitude KEYWORD2 81 | stealth_gradient KEYWORD2 82 | stealth_freq KEYWORD2 83 | stealth_autoscale KEYWORD2 84 | stealth_symmetric KEYWORD2 85 | standstill_mode KEYWORD2 86 | DRVSTATUS KEYWORD2 87 | PWM_SCALE KEYWORD2 88 | invert_encoder KEYWORD2 89 | maxspeed KEYWORD2 90 | LOST_STEPS KEYWORD2 91 | _started KEYWORD2 92 | 93 | I_scale_analog KEYWORD2 94 | internal_Rsense KEYWORD2 95 | en_pwm_mode KEYWORD2 96 | enc_commutation KEYWORD2 97 | shaft KEYWORD2 98 | diag0_error KEYWORD2 99 | diag0_otpw KEYWORD2 100 | diag1_onstate KEYWORD2 101 | diag0_int_pushpull KEYWORD2 102 | diag1_int_pushpull KEYWORD2 103 | GSTAT KEYWORD2 104 | IOIN KEYWORD2 105 | IHOLD KEYWORD2 106 | IRUN KEYWORD2 107 | IHOLDDELAY KEYWORD2 108 | TPOWERDOWN KEYWORD2 109 | TSTEP KEYWORD2 110 | TPWMTHRS KEYWORD2 111 | TCOOLTHRS KEYWORD2 112 | THIGH KEYWORD2 113 | XDIRECT_A KEYWORD2 114 | XDIRECT_B KEYWORD2 115 | VDCMIN KEYWORD2 116 | CHOPCONF KEYWORD2 117 | toff KEYWORD2 118 | hstrt KEYWORD2 119 | hend KEYWORD2 120 | fd KEYWORD2 121 | disfdcc KEYWORD2 122 | rndtf KEYWORD2 123 | chm KEYWORD2 124 | tbl KEYWORD2 125 | vsense KEYWORD2 126 | vhighfs KEYWORD2 127 | vhighchm KEYWORD2 128 | sync KEYWORD2 129 | mres KEYWORD2 130 | intpol KEYWORD2 131 | dedge KEYWORD2 132 | diss2g KEYWORD2 133 | semin KEYWORD2 134 | seup KEYWORD2 135 | semax KEYWORD2 136 | sedn KEYWORD2 137 | seimin KEYWORD2 138 | sgt KEYWORD2 139 | sfilt KEYWORD2 140 | PWM_AMPL KEYWORD2 141 | PWM_GRAD KEYWORD2 142 | pwm_freq KEYWORD2 143 | pwm_autoscale KEYWORD2 144 | pwm_symmetric KEYWORD2 145 | freewheel KEYWORD2 146 | ENCM_CTRL0 KEYWORD2 147 | ENCM_CTRL1 KEYWORD2 148 | -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=TMC2130Stepper 2 | version=2.5.1 3 | author=teemuatlut 4 | maintainer=teemuatlut 5 | sentence=Arduino library for Trinamic TMC2130 stepper drivers 6 | paragraph=Easily configure your TMC2130 stepper motor drivers 7 | category=Device Control 8 | url=https://github.com/teemuatlut/TMC2130Stepper 9 | architectures=avr,sam 10 | -------------------------------------------------------------------------------- /src/TMC2130Stepper.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | //#define TMC2130DEBUG 4 | #include 5 | #include 6 | #include 7 | 8 | #define TMC2130STEPPER_VERSION 0x020501 // v2.5.1 9 | 10 | class TMC2130Stepper { 11 | public: 12 | TMC2130Stepper(uint16_t pinCS); 13 | TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS); 14 | TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK); 15 | void begin(); 16 | void checkStatus(); 17 | void rms_current(uint16_t mA, float multiplier=0.5, float RS=0.11); 18 | uint16_t rms_current(); 19 | void SilentStepStick2130(uint16_t mA); 20 | void setCurrent(uint16_t mA, float Rsense, float multiplier); 21 | uint16_t getCurrent(); 22 | bool checkOT(); 23 | bool getOTPW(); 24 | void clear_otpw(); 25 | bool isEnabled(); 26 | void push(); 27 | uint8_t test_connection(); 28 | // GCONF 29 | uint32_t GCONF(); 30 | void GCONF( uint32_t value); 31 | void I_scale_analog( bool B); 32 | void internal_Rsense( bool B); 33 | void en_pwm_mode( bool B); 34 | void enc_commutation( bool B); 35 | void shaft( bool B); 36 | void diag0_error( bool B); 37 | void diag0_otpw( bool B); 38 | void diag0_stall( bool B); 39 | void diag1_stall( bool B); 40 | void diag1_index( bool B); 41 | void diag1_onstate( bool B); 42 | void diag1_steps_skipped( bool B); 43 | void diag0_int_pushpull( bool B); 44 | void diag1_pushpull( bool B); 45 | void small_hysteresis( bool B); 46 | void stop_enable( bool B); 47 | void direct_mode( bool B); 48 | bool I_scale_analog(); 49 | bool internal_Rsense(); 50 | bool en_pwm_mode(); 51 | bool enc_commutation(); 52 | bool shaft(); 53 | bool diag0_error(); 54 | bool diag0_otpw(); 55 | bool diag0_stall(); 56 | bool diag1_stall(); 57 | bool diag1_index(); 58 | bool diag1_onstate(); 59 | bool diag1_steps_skipped(); 60 | bool diag0_int_pushpull(); 61 | bool diag1_pushpull(); 62 | bool small_hysteresis(); 63 | bool stop_enable(); 64 | bool direct_mode(); 65 | // IHOLD_IRUN 66 | void IHOLD_IRUN( uint32_t input); 67 | uint32_t IHOLD_IRUN(); 68 | void ihold( uint8_t B); 69 | void irun( uint8_t B); 70 | void iholddelay( uint8_t B); 71 | uint8_t ihold(); 72 | uint8_t irun(); 73 | uint8_t iholddelay(); 74 | // GSTAT 75 | void GSTAT( uint8_t input); 76 | uint8_t GSTAT(); 77 | bool reset(); 78 | bool drv_err(); 79 | bool uv_cp(); 80 | // IOIN 81 | uint32_t IOIN(); 82 | bool step(); 83 | bool dir(); 84 | bool dcen_cfg4(); 85 | bool dcin_cfg5(); 86 | bool drv_enn_cfg6(); 87 | bool dco(); 88 | uint8_t version(); 89 | // TPOWERDOWN 90 | uint8_t TPOWERDOWN(); 91 | void TPOWERDOWN( uint8_t input); 92 | // TSTEP 93 | uint32_t TSTEP(); 94 | // TPWMTHRS 95 | uint32_t TPWMTHRS(); 96 | void TPWMTHRS( uint32_t input); 97 | // TCOOLTHRS 98 | uint32_t TCOOLTHRS(); 99 | void TCOOLTHRS( uint32_t input); 100 | // THIGH 101 | uint32_t THIGH(); 102 | void THIGH( uint32_t input); 103 | // XDRIRECT 104 | uint32_t XDIRECT(); 105 | void XDIRECT( uint32_t input); 106 | void coil_A( int16_t B); 107 | void coil_B( int16_t B); 108 | int16_t coil_A(); 109 | int16_t coil_B(); 110 | // VDCMIN 111 | uint32_t VDCMIN(); 112 | void VDCMIN( uint32_t input); 113 | // MSLUT0..MSLUT7 114 | uint32_t MSLUT0(); 115 | void MSLUT0( uint32_t input); 116 | uint32_t MSLUT1(); 117 | void MSLUT1( uint32_t input); 118 | uint32_t MSLUT2(); 119 | void MSLUT2( uint32_t input); 120 | uint32_t MSLUT3(); 121 | void MSLUT3( uint32_t input); 122 | uint32_t MSLUT4(); 123 | void MSLUT4( uint32_t input); 124 | uint32_t MSLUT5(); 125 | void MSLUT5( uint32_t input); 126 | uint32_t MSLUT6(); 127 | void MSLUT6( uint32_t input); 128 | uint32_t MSLUT7(); 129 | void MSLUT7( uint32_t input); 130 | // MSLUTSEL 131 | uint32_t MSLUTSEL(); 132 | void MSLUTSEL( uint32_t input); 133 | // MSLUTSTART 134 | uint32_t MSLUTSTART(); 135 | void MSLUTSTART( uint32_t input); 136 | // MSCNT 137 | uint16_t MSCNT(); 138 | // MSCURACT 139 | uint32_t MSCURACT(); 140 | int16_t cur_a(); 141 | int16_t cur_b(); 142 | // CHOPCONF 143 | uint32_t CHOPCONF(); 144 | void CHOPCONF( uint32_t value); 145 | void toff( uint8_t B); 146 | void hstrt( uint8_t B); 147 | void hend( uint8_t B); 148 | void fd( uint8_t B); 149 | void disfdcc( bool B); 150 | void rndtf( bool B); 151 | void chm( bool B); 152 | void tbl( uint8_t B); 153 | void vsense( bool B); 154 | void vhighfs( bool B); 155 | void vhighchm( bool B); 156 | void sync( uint8_t B); 157 | void mres( uint8_t B); 158 | void intpol( bool B); 159 | void dedge( bool B); 160 | void diss2g( bool B); 161 | uint8_t toff(); 162 | uint8_t hstrt(); 163 | uint8_t hend(); 164 | uint8_t fd(); 165 | bool disfdcc(); 166 | bool rndtf(); 167 | bool chm(); 168 | uint8_t tbl(); 169 | bool vsense(); 170 | bool vhighfs(); 171 | bool vhighchm(); 172 | uint8_t sync(); 173 | uint8_t mres(); 174 | bool intpol(); 175 | bool dedge(); 176 | bool diss2g(); 177 | // COOLCONF 178 | void COOLCONF(uint32_t value); 179 | uint32_t COOLCONF(); 180 | void semin( uint8_t B); 181 | void seup( uint8_t B); 182 | void semax( uint8_t B); 183 | void sedn( uint8_t B); 184 | void seimin( bool B); 185 | void sgt( int8_t B); 186 | void sfilt( bool B); 187 | uint8_t semin(); 188 | uint8_t seup(); 189 | uint8_t semax(); 190 | uint8_t sedn(); 191 | bool seimin(); 192 | int8_t sgt(); 193 | bool sfilt(); 194 | // PWMCONF 195 | void PWMCONF( uint32_t value); 196 | uint32_t PWMCONF(); 197 | void pwm_ampl( uint8_t B); 198 | void pwm_grad( uint8_t B); 199 | void pwm_freq( uint8_t B); 200 | void pwm_autoscale( bool B); 201 | void pwm_symmetric( bool B); 202 | void freewheel( uint8_t B); 203 | uint8_t pwm_ampl(); 204 | uint8_t pwm_grad(); 205 | uint8_t pwm_freq(); 206 | bool pwm_autoscale(); 207 | bool pwm_symmetric(); 208 | uint8_t freewheel(); 209 | // DRVSTATUS 210 | uint32_t DRV_STATUS(); 211 | uint16_t sg_result(); 212 | bool fsactive(); 213 | uint8_t cs_actual(); 214 | bool stallguard(); 215 | bool ot(); 216 | bool otpw(); 217 | bool s2ga(); 218 | bool s2gb(); 219 | bool ola(); 220 | bool olb(); 221 | bool stst(); 222 | // PWM_SCALE 223 | uint8_t PWM_SCALE(); 224 | // ENCM_CTRL 225 | uint8_t ENCM_CTRL(); 226 | void ENCM_CTRL( uint8_t input); 227 | void inv( bool B); 228 | void maxspeed( bool B); 229 | bool inv(); 230 | bool maxspeed(); 231 | // LOST_STEPS 232 | uint32_t LOST_STEPS(); 233 | 234 | // Helper functions 235 | void microsteps(uint16_t ms); 236 | uint16_t microsteps(); 237 | void blank_time(uint8_t value); 238 | uint8_t blank_time(); 239 | void hysteresis_end(int8_t value); 240 | int8_t hysteresis_end(); 241 | void hysteresis_start(uint8_t value); 242 | uint8_t hysteresis_start(); 243 | void sg_current_decrease(uint8_t value); 244 | uint8_t sg_current_decrease(); 245 | 246 | // Aliases 247 | 248 | // RW: GCONF 249 | inline bool external_ref() __attribute__((always_inline)) { return I_scale_analog(); } 250 | inline bool internal_sense_R() __attribute__((always_inline)) { return internal_Rsense(); } 251 | inline bool stealthChop() __attribute__((always_inline)) { return en_pwm_mode(); } 252 | inline bool commutation() __attribute__((always_inline)) { return enc_commutation(); } 253 | inline bool shaft_dir() __attribute__((always_inline)) { return shaft(); } 254 | inline bool diag0_errors() __attribute__((always_inline)) { return diag0_error(); } 255 | inline bool diag0_temp_prewarn() __attribute__((always_inline)) { return diag0_otpw(); } 256 | inline bool diag1_chopper_on() __attribute__((always_inline)) { return diag1_onstate(); } 257 | inline bool diag0_active_high() __attribute__((always_inline)) { return diag0_int_pushpull(); } 258 | inline bool diag1_active_high() __attribute__((always_inline)) { return diag1_pushpull(); } 259 | inline void external_ref( bool value) __attribute__((always_inline)) { I_scale_analog(value); } 260 | inline void internal_sense_R( bool value) __attribute__((always_inline)) { internal_Rsense(value); } 261 | inline void stealthChop( bool value) __attribute__((always_inline)) { en_pwm_mode(value); } 262 | inline void commutation( bool value) __attribute__((always_inline)) { enc_commutation(value); } 263 | inline void shaft_dir( bool value) __attribute__((always_inline)) { shaft(value); } 264 | inline void diag0_errors( bool value) __attribute__((always_inline)) { diag0_error(value); } 265 | inline void diag0_temp_prewarn( bool value) __attribute__((always_inline)) { diag0_otpw(value); } 266 | inline void diag1_chopper_on( bool value) __attribute__((always_inline)) { diag1_onstate(value); } 267 | inline void diag0_active_high( bool value) __attribute__((always_inline)) { diag0_int_pushpull(value); } 268 | inline void diag1_active_high( bool value) __attribute__((always_inline)) { diag1_pushpull(value); } 269 | // RC 270 | inline uint8_t status_flags() __attribute__((always_inline)) { return GSTAT(); } 271 | // R 272 | inline uint32_t input() __attribute__((always_inline)) { return IOIN(); } 273 | // W: IHOLD_IRUN 274 | inline uint8_t hold_current() __attribute__((always_inline)) { return ihold(); } 275 | inline uint8_t run_current() __attribute__((always_inline)) { return irun(); } 276 | inline uint8_t hold_delay() __attribute__((always_inline)) { return iholddelay(); } 277 | inline void hold_current( uint8_t value) __attribute__((always_inline)) { ihold(value); } 278 | inline void run_current( uint8_t value) __attribute__((always_inline)) { irun(value); } 279 | inline void hold_delay( uint8_t value) __attribute__((always_inline)) { iholddelay(value); } 280 | // W 281 | inline uint8_t power_down_delay() __attribute__((always_inline)) { return TPOWERDOWN(); } 282 | inline void power_down_delay( uint8_t value) __attribute__((always_inline)) { TPOWERDOWN(value); } 283 | // R 284 | inline uint32_t microstep_time() __attribute__((always_inline)) { return TSTEP(); } 285 | // W 286 | inline uint32_t stealth_max_speed() __attribute__((always_inline)) { return TPWMTHRS(); } 287 | inline void stealth_max_speed(uint32_t value) __attribute__((always_inline)) { TPWMTHRS(value); } 288 | // W 289 | inline uint32_t coolstep_min_speed() __attribute__((always_inline)) { return TCOOLTHRS(); } 290 | inline void coolstep_min_speed(uint32_t value) __attribute__((always_inline)) { TCOOLTHRS(value); } 291 | // W 292 | inline uint32_t mode_sw_speed() __attribute__((always_inline)) { return THIGH(); } 293 | inline void mode_sw_speed( uint32_t value) __attribute__((always_inline)) { THIGH(value); } 294 | // RW: XDIRECT 295 | inline int16_t coil_A_current() __attribute__((always_inline)) { return coil_A(); } 296 | inline void coil_A_current( int16_t value) __attribute__((always_inline)) { coil_A(value); } 297 | inline int16_t coil_B_current() __attribute__((always_inline)) { return coil_B(); } 298 | inline void coil_B_current( int16_t value) __attribute__((always_inline)) { coil_B(value); } 299 | // W 300 | inline uint32_t DCstep_min_speed() __attribute__((always_inline)) { return VDCMIN(); } 301 | inline void DCstep_min_speed( uint32_t value) __attribute__((always_inline)) { VDCMIN(value); } 302 | // W 303 | inline uint32_t lut_mslutstart() __attribute__((always_inline)) { return MSLUTSTART(); } 304 | inline void lut_mslutstart( uint32_t value) __attribute__((always_inline)) { MSLUTSTART(value); } 305 | inline uint32_t lut_msutsel() __attribute__((always_inline)) { return MSLUTSEL(); } 306 | inline void lut_msutsel( uint32_t value) __attribute__((always_inline)) { MSLUTSEL(value); } 307 | inline uint32_t ms_lookup_0() __attribute__((always_inline)) { return MSLUT0(); } 308 | inline void ms_lookup_0( uint32_t value) __attribute__((always_inline)) { MSLUT0(value); } 309 | inline uint32_t ms_lookup_1() __attribute__((always_inline)) { return MSLUT1(); } 310 | inline void ms_lookup_1( uint32_t value) __attribute__((always_inline)) { MSLUT1(value); } 311 | inline uint32_t ms_lookup_2() __attribute__((always_inline)) { return MSLUT2(); } 312 | inline void ms_lookup_2( uint32_t value) __attribute__((always_inline)) { MSLUT2(value); } 313 | inline uint32_t ms_lookup_3() __attribute__((always_inline)) { return MSLUT3(); } 314 | inline void ms_lookup_3( uint32_t value) __attribute__((always_inline)) { MSLUT3(value); } 315 | inline uint32_t ms_lookup_4() __attribute__((always_inline)) { return MSLUT4(); } 316 | inline void ms_lookup_4( uint32_t value) __attribute__((always_inline)) { MSLUT4(value); } 317 | inline uint32_t ms_lookup_5() __attribute__((always_inline)) { return MSLUT5(); } 318 | inline void ms_lookup_5( uint32_t value) __attribute__((always_inline)) { MSLUT5(value); } 319 | inline uint32_t ms_lookup_6() __attribute__((always_inline)) { return MSLUT6(); } 320 | inline void ms_lookup_6( uint32_t value) __attribute__((always_inline)) { MSLUT6(value); } 321 | inline uint32_t ms_lookup_7() __attribute__((always_inline)) { return MSLUT7(); } 322 | inline void ms_lookup_7( uint32_t value) __attribute__((always_inline)) { MSLUT7(value); } 323 | // RW: CHOPCONF 324 | inline uint8_t off_time() __attribute__((always_inline)) { return toff(); } 325 | // inline uint8_t hysteresis_start() __attribute__((always_inline)) { return hstrt(); } 326 | // inline int8_t hysteresis_low() __attribute__((always_inline)) { return hend(); } 327 | inline int8_t hysteresis_low() __attribute__((always_inline)) { return hysteresis_end(); } 328 | inline uint8_t fast_decay_time() __attribute__((always_inline)) { return fd(); } 329 | inline bool disable_I_comparator() __attribute__((always_inline)) { return disfdcc(); } 330 | inline bool random_off_time() __attribute__((always_inline)) { return rndtf(); } 331 | inline bool chopper_mode() __attribute__((always_inline)) { return chm(); } 332 | // inline uint8_t blank_time() __attribute__((always_inline)) { return tbl(); } 333 | inline bool high_sense_R() __attribute__((always_inline)) { return vsense(); } 334 | inline bool fullstep_threshold() __attribute__((always_inline)) { return vhighfs(); } 335 | inline bool high_speed_mode() __attribute__((always_inline)) { return vhighchm(); } 336 | inline uint8_t sync_phases() __attribute__((always_inline)) { return sync(); } 337 | // inline uint16_t microsteps() __attribute__((always_inline)) { return mres(); } 338 | inline bool interpolate() __attribute__((always_inline)) { return intpol(); } 339 | inline bool double_edge_step() __attribute__((always_inline)) { return dedge(); } 340 | inline bool disable_short_protection() __attribute__((always_inline)) { return diss2g(); } 341 | inline void off_time( uint8_t value) __attribute__((always_inline)) { toff(value); } 342 | // inline void hysteresis_start( uint8_t value) __attribute__((always_inline)) { hstrt(value); } 343 | // inline void hysteresis_low( int8_t value) __attribute__((always_inline)) { hend(value); } 344 | inline void hysteresis_low( int8_t value) __attribute__((always_inline)) { hysteresis_end(value); } 345 | inline void fast_decay_time( uint8_t value) __attribute__((always_inline)) { fd(value); } 346 | inline void disable_I_comparator( bool value) __attribute__((always_inline)) { disfdcc(value); } 347 | inline void random_off_time( bool value) __attribute__((always_inline)) { rndtf(value); } 348 | inline void chopper_mode( bool value) __attribute__((always_inline)) { chm(value); } 349 | // inline void blank_time( uint8_t value) __attribute__((always_inline)) { tbl(value); } 350 | inline void high_sense_R( bool value) __attribute__((always_inline)) { vsense(value); } 351 | inline void fullstep_threshold( bool value) __attribute__((always_inline)) { vhighfs(value); } 352 | inline void high_speed_mode( bool value) __attribute__((always_inline)) { vhighchm(value); } 353 | inline void sync_phases( uint8_t value) __attribute__((always_inline)) { sync(value); } 354 | // inline void microsteps( uint16_t value) __attribute__((always_inline)) { mres(value); } 355 | inline void interpolate( bool value) __attribute__((always_inline)) { intpol(value); } 356 | inline void double_edge_step( bool value) __attribute__((always_inline)) { dedge(value); } 357 | inline void disable_short_protection(bool value)__attribute__((always_inline)) { diss2g(value); } 358 | // W: COOLCONF 359 | inline uint8_t sg_min() __attribute__((always_inline)) { return semin(); } 360 | inline uint8_t sg_step_width() __attribute__((always_inline)) { return seup(); } 361 | inline uint8_t sg_max() __attribute__((always_inline)) { return semax(); } 362 | // inline uint8_t sg_current_decrease() __attribute__((always_inline)) { return sedn(); } 363 | inline uint8_t smart_min_current() __attribute__((always_inline)) { return seimin(); } 364 | inline int8_t sg_stall_value() __attribute__((always_inline)) { return sgt(); } 365 | inline bool sg_filter() __attribute__((always_inline)) { return sfilt(); } 366 | inline void sg_min( uint8_t value) __attribute__((always_inline)) { semin(value); } 367 | inline void sg_step_width( uint8_t value) __attribute__((always_inline)) { seup(value); } 368 | inline void sg_max( uint8_t value) __attribute__((always_inline)) { semax(value); } 369 | // inline void sg_current_decrease(uint8_t value)__attribute__((always_inline)) { sedn(value); } 370 | inline void smart_min_current( uint8_t value) __attribute__((always_inline)) { seimin(value); } 371 | inline void sg_stall_value( int8_t value) __attribute__((always_inline)) { sgt(value); } 372 | inline void sg_filter( bool value) __attribute__((always_inline)) { sfilt(value); } 373 | // W: PWMCONF 374 | inline uint8_t stealth_amplitude() __attribute__((always_inline)) { return pwm_ampl(); } 375 | inline uint8_t stealth_gradient() __attribute__((always_inline)) { return pwm_grad(); } 376 | inline uint8_t stealth_freq() __attribute__((always_inline)) { return pwm_freq(); } 377 | inline bool stealth_autoscale() __attribute__((always_inline)) { return pwm_autoscale(); } 378 | inline bool stealth_symmetric() __attribute__((always_inline)) { return pwm_symmetric(); } 379 | inline uint8_t standstill_mode() __attribute__((always_inline)) { return freewheel(); } 380 | inline void stealth_amplitude( uint8_t value) __attribute__((always_inline)) { pwm_ampl(value); } 381 | inline void stealth_gradient( uint8_t value) __attribute__((always_inline)) { pwm_grad(value); } 382 | inline void stealth_freq( uint8_t value) __attribute__((always_inline)) { pwm_freq(value); } 383 | inline void stealth_autoscale( bool value) __attribute__((always_inline)) { pwm_autoscale(value); } 384 | inline void stealth_symmetric( bool value) __attribute__((always_inline)) { pwm_symmetric(value); } 385 | inline void standstill_mode( uint8_t value) __attribute__((always_inline)) { freewheel(value); } 386 | // W: ENCM_CTRL 387 | inline bool invert_encoder() __attribute__((always_inline)) { return inv(); } 388 | inline void invert_encoder( bool value) __attribute__((always_inline)) { inv(value); } 389 | // R: DRV_STATUS 390 | inline uint32_t DRVSTATUS() __attribute__((always_inline)) { return DRV_STATUS(); } 391 | 392 | // Backwards compatibility 393 | inline void hysterisis_end(int8_t value) __attribute__((always_inline)) { hysteresis_end(value); } 394 | inline int8_t hysterisis_end() __attribute__((always_inline)) { return hysteresis_end(); } 395 | inline void hysterisis_start(uint8_t value) __attribute__((always_inline)) { hysteresis_start(value); } 396 | inline uint8_t hysterisis_start() __attribute__((always_inline)) { return hysteresis_start(); } 397 | 398 | 399 | float Rsense = 0.11; 400 | uint8_t status_response; 401 | bool flag_otpw = false; 402 | 403 | private: 404 | //const uint8_t WRITE = 0b10000000; 405 | //const uint8_t READ = 0b00000000; 406 | const uint16_t _pinEN = 0xFFFF; 407 | const uint16_t _pinSTEP = 0xFFFF; 408 | const uint16_t _pinCS = 0xFFFF; 409 | //const int MOSI_PIN = 12; 410 | //const int MISO_PIN = 11; 411 | //const int SCK_PIN = 13; 412 | const uint16_t _pinDIR = 0xFFFF; 413 | 414 | // Shadow registers 415 | uint32_t GCONF_sr = 0x00000000UL, 416 | IHOLD_IRUN_sr = 0x00000000UL, 417 | TSTEP_sr = 0x00000000UL, 418 | TPWMTHRS_sr = 0x00000000UL, 419 | TCOOLTHRS_sr = 0x00000000UL, 420 | THIGH_sr = 0x00000000UL, 421 | XDIRECT_sr = 0x00000000UL, 422 | VDCMIN_sr = 0x00000000UL, 423 | MSLUT0_sr = 0xAAAAB554UL, 424 | MSLUT1_sr = 0x4A9554AAUL, 425 | MSLUT2_sr = 0x24492929UL, 426 | MSLUT3_sr = 0x10104222UL, 427 | MSLUT4_sr = 0xFBFFFFFFUL, 428 | MSLUT5_sr = 0xB5BB777DUL, 429 | MSLUT6_sr = 0x49295556UL, 430 | MSLUT7_sr = 0x00404222UL, 431 | MSLUTSEL_sr = 0xFFFF8056UL, 432 | CHOPCONF_sr = 0x00000000UL, 433 | COOLCONF_sr = 0x00000000UL, 434 | DCCTRL_sr = 0x00000000UL, 435 | PWMCONF_sr = 0x00050480UL, 436 | tmp_sr = 0x00000000UL, 437 | TPOWERDOWN_sr = 0x00000000UL, 438 | ENCM_CTRL_sr = 0x00000000UL, 439 | GSTAT_sr = 0x00000000UL, 440 | MSLUTSTART_sr = 0x00F70000UL; 441 | 442 | void send2130(uint8_t addressByte, uint32_t *config); 443 | 444 | uint16_t val_mA = 0; 445 | const bool uses_sw_spi; 446 | }; 447 | -------------------------------------------------------------------------------- /src/TMC2130Stepper_REGDEFS.h: -------------------------------------------------------------------------------- 1 | #ifndef TMC2130Stepper_REGDEFS_h 2 | #define TMC2130Stepper_REGDEFS_h 3 | 4 | constexpr uint8_t TMC2130_READ = 0x00; 5 | constexpr uint8_t TMC2130_WRITE = 0x80; 6 | 7 | // Register memory positions 8 | constexpr uint8_t REG_GCONF = 0x00; 9 | constexpr uint8_t REG_GSTAT = 0x01; 10 | constexpr uint8_t REG_IOIN = 0x04; 11 | constexpr uint8_t REG_IHOLD_IRUN = 0x10; 12 | constexpr uint8_t REG_TPOWERDOWN = 0x11; 13 | constexpr uint8_t REG_TSTEP = 0x12; 14 | constexpr uint8_t REG_TPWMTHRS = 0x13; 15 | constexpr uint8_t REG_TCOOLTHRS = 0x14; 16 | constexpr uint8_t REG_THIGH = 0x15; 17 | constexpr uint8_t REG_XDIRECT = 0x2D; 18 | constexpr uint8_t REG_VDCMIN = 0x33; 19 | constexpr uint8_t REG_MSLUT0 = 0x60; 20 | constexpr uint8_t REG_MSLUT1 = 0x61; 21 | constexpr uint8_t REG_MSLUT2 = 0x62; 22 | constexpr uint8_t REG_MSLUT3 = 0x63; 23 | constexpr uint8_t REG_MSLUT4 = 0x64; 24 | constexpr uint8_t REG_MSLUT5 = 0x65; 25 | constexpr uint8_t REG_MSLUT6 = 0x66; 26 | constexpr uint8_t REG_MSLUT7 = 0x67; 27 | constexpr uint8_t REG_MSLUTSEL = 0x68; 28 | constexpr uint8_t REG_MSLUTSTART = 0x69; 29 | constexpr uint8_t REG_MSCNT = 0x6A; 30 | constexpr uint8_t REG_MSCURACT = 0x6B; 31 | constexpr uint8_t REG_CHOPCONF = 0x6C; 32 | constexpr uint8_t REG_COOLCONF = 0x6D; 33 | constexpr uint8_t REG_DCCTRL = 0x6E; 34 | constexpr uint8_t REG_DRV_STATUS = 0x6F; 35 | constexpr uint8_t REG_PWMCONF = 0x70; 36 | constexpr uint8_t REG_PWM_SCALE = 0x71; 37 | constexpr uint8_t REG_ENCM_CTRL = 0x72; 38 | constexpr uint8_t REG_LOST_STEPS = 0x73; 39 | 40 | // SPI_STATUS 41 | constexpr uint8_t RESET_FLAG_bp = 0; 42 | constexpr uint8_t DRIVER_ERROR_bp = 1; 43 | constexpr uint8_t SG2_bp = 2; 44 | constexpr uint8_t STANDSTILL_bp = 3; 45 | constexpr uint32_t RESET_FLAG_bm = 0x1UL; 46 | constexpr uint32_t DRIVER_ERROR_bm = 0x2UL; 47 | constexpr uint32_t SG2_bm = 0x4UL; 48 | constexpr uint32_t STANDSTILL_bm = 0x8UL; 49 | 50 | // GCONF 51 | constexpr uint8_t I_SCALE_ANALOG_bp = 0; 52 | constexpr uint8_t INTERNAL_RSENSE_bp = 1; 53 | constexpr uint8_t EN_PWM_MODE_bp = 2; 54 | constexpr uint8_t ENC_COMMUTATION_bp = 3; 55 | constexpr uint8_t SHAFT_bp = 4; 56 | constexpr uint8_t DIAG0_ERROR_bp = 5; 57 | constexpr uint8_t DIAG0_OTPW_bp = 6; 58 | constexpr uint8_t DIAG0_STALL_bp = 7; 59 | constexpr uint8_t DIAG1_STALL_bp = 8; 60 | constexpr uint8_t DIAG1_INDEX_bp = 9; 61 | constexpr uint8_t DIAG1_ONSTATE_bp = 10; 62 | constexpr uint8_t DIAG1_STEPS_SKIPPED_bp = 11; 63 | constexpr uint8_t DIAG0_INT_PUSHPULL_bp = 12; 64 | constexpr uint8_t DIAG1_PUSHPULL_bp = 13; 65 | constexpr uint8_t SMALL_HYSTERESIS_bp = 14; 66 | constexpr uint8_t STOP_ENABLE_bp = 15; 67 | constexpr uint8_t DIRECT_MODE_bp = 16; 68 | constexpr uint32_t GCONF_bm = 0x3FFFFUL; 69 | constexpr uint32_t I_SCALE_ANALOG_bm = 0x1UL; 70 | constexpr uint32_t INTERNAL_RSENSE_bm = 0x2UL; 71 | constexpr uint32_t EN_PWM_MODE_bm = 0x4UL; 72 | constexpr uint32_t ENC_COMMUTATION_bm = 0x8UL; 73 | constexpr uint32_t SHAFT_bm = 0x10UL; 74 | constexpr uint32_t DIAG0_ERROR_bm = 0x20UL; 75 | constexpr uint32_t DIAG0_OTPW_bm = 0x40UL; 76 | constexpr uint32_t DIAG0_STALL_bm = 0x80UL; 77 | constexpr uint32_t DIAG1_STALL_bm = 0x100UL; 78 | constexpr uint32_t DIAG1_INDEX_bm = 0x200UL; 79 | constexpr uint32_t DIAG1_ONSTATE_bm = 0x400UL; 80 | constexpr uint32_t DIAG1_STEPS_SKIPPED_bm = 0x800UL; 81 | constexpr uint32_t DIAG0_INT_PUSHPULL_bm = 0x1000UL; 82 | constexpr uint32_t DIAG1_PUSHPULL_bm = 0x2000UL; 83 | constexpr uint32_t SMALL_HYSTERESIS_bm = 0x4000UL; 84 | constexpr uint32_t STOP_ENABLE_bm = 0x8000UL; 85 | constexpr uint32_t DIRECT_MODE_bm = 0x10000UL; 86 | // GSTAT 87 | constexpr uint8_t RESET_bp = 0; 88 | constexpr uint8_t DRV_ERR_bp = 1; 89 | constexpr uint8_t UV_CP_bp = 2; 90 | constexpr uint32_t GSTAT_bm = 0x7UL; 91 | constexpr uint32_t RESET_bm = 0b1UL; 92 | constexpr uint32_t DRV_ERR_bm = 0b10UL; 93 | constexpr uint32_t UV_CP_bm = 0b100UL; 94 | // IOIN 95 | constexpr uint8_t STEP_bp = 0; 96 | constexpr uint8_t DIR_bp = 1; 97 | constexpr uint8_t DCEN_CFG4_bp = 2; 98 | constexpr uint8_t DCIN_CFG5_bp = 3; 99 | constexpr uint8_t DRV_ENN_CFG6_bp = 4; 100 | constexpr uint8_t DCO_bp = 5; 101 | constexpr uint8_t VERSION_bp = 24; 102 | constexpr uint32_t IOIN_bm = 0xFF00003FUL; 103 | constexpr uint32_t STEP_bm = 0x1UL; 104 | constexpr uint32_t DIR_bm = 0x2UL; 105 | constexpr uint32_t DCEN_CFG4_bm = 0x4UL; 106 | constexpr uint32_t DCIN_CFG5_bm = 0x8UL; 107 | constexpr uint32_t DRV_ENN_CFG6_bm = 0x10UL; 108 | constexpr uint32_t DCO_bm = 0x20UL; 109 | constexpr uint32_t VERSION_bm = 0xFF000000UL; 110 | // IHOLD_IRUN 111 | constexpr uint8_t IHOLD_bp = 0; 112 | constexpr uint8_t IRUN_bp = 8; 113 | constexpr uint8_t IHOLDDELAY_bp = 16; 114 | constexpr uint32_t IHOLD_IRUN_bm = 0xF1F1FUL; 115 | constexpr uint32_t IHOLD_bm = 0x1FUL; 116 | constexpr uint32_t IRUN_bm = 0x1F00UL; 117 | constexpr uint32_t IHOLDDELAY_bm = 0xF0000UL; 118 | // TPOWERDOWN 119 | constexpr uint8_t TPOWERDOWN_bp = 0; 120 | constexpr uint32_t TPOWERDOWN_bm = 0xFFUL; 121 | // TSTEP 122 | constexpr uint8_t TSTEP_bp = 0; 123 | constexpr uint32_t TSTEP_bm = 0xFFFFFUL; 124 | // TPWMTHRS 125 | constexpr uint8_t TPWMTHRS_bp = 0; 126 | constexpr uint32_t TPWMTHRS_bm = 0xFFFFFUL; 127 | // TCOOLTHRS 128 | constexpr uint8_t TCOOLTHRS_bp = 0; 129 | constexpr uint32_t TCOOLTHRS_bm = 0xFFFFFUL; 130 | // THIGH 131 | constexpr uint8_t THIGH_bp = 0; 132 | constexpr uint32_t THIGH_bm = 0xFFFFFUL; 133 | // XDIRECT 134 | constexpr uint8_t XDIRECT_bp = 0; 135 | constexpr uint32_t XDIRECT_bm = 0xFFFFFFFFUL; 136 | constexpr uint8_t COIL_A_bp = 0; 137 | constexpr uint8_t COIL_B_bp = 16; 138 | constexpr uint32_t COIL_A_bm = 0x1FFUL; 139 | constexpr uint32_t COIL_B_bm = 0x1FF0000UL; 140 | // VDCMIN 141 | constexpr uint8_t VDCMIN_bp = 0; 142 | constexpr uint32_t VDCMIN_bm = 0x7FFFFFUL; 143 | // MSLUT0 144 | constexpr uint8_t MSLUT0_bp = 0; 145 | constexpr uint32_t MSLUT0_bm = 0xFFFFFFFFUL; 146 | // MSLUT1 147 | constexpr uint8_t MSLUT1_bp = 0; 148 | constexpr uint32_t MSLUT1_bm = 0xFFFFFFFFUL; 149 | // MSLUT2 150 | constexpr uint8_t MSLUT2_bp = 0; 151 | constexpr uint32_t MSLUT2_bm = 0xFFFFFFFFUL; 152 | // MSLUT3 153 | constexpr uint8_t MSLUT3_bp = 0; 154 | constexpr uint32_t MSLUT3_bm = 0xFFFFFFFFUL; 155 | // MSLUT4 156 | constexpr uint8_t MSLUT4_bp = 0; 157 | constexpr uint32_t MSLUT4_bm = 0xFFFFFFFFUL; 158 | // MSLUT5 159 | constexpr uint8_t MSLUT5_bp = 0; 160 | constexpr uint32_t MSLUT5_bm = 0xFFFFFFFFUL; 161 | // MSLUT6 162 | constexpr uint8_t MSLUT6_bp = 0; 163 | constexpr uint32_t MSLUT6_bm = 0xFFFFFFFFUL; 164 | // MSLUT7 165 | constexpr uint8_t MSLUT7_bp = 0; 166 | constexpr uint32_t MSLUT7_bm = 0xFFFFFFFFUL; 167 | // MSLUTSEL 168 | constexpr uint8_t MSLUTSEL_bp = 0; 169 | constexpr uint32_t MSLUTSEL_bm = 0xFFFFFFFFUL; 170 | // MSLUTSTART 171 | constexpr uint8_t START_SIN_bp = 0; 172 | constexpr uint8_t START_SIN90_bp = 16; 173 | constexpr uint32_t START_SIN_bm = 0xFFUL; 174 | constexpr uint32_t START_SIN90_bm = 0xFF0000UL; 175 | // MSCNT 176 | constexpr uint8_t MSCNT_bp = 0; 177 | constexpr uint32_t MSCNT_bm = 0x3FFUL; 178 | // MSCURACT 179 | constexpr uint8_t CUR_A_bp = 0; 180 | constexpr uint8_t CUR_B_bp = 16; 181 | constexpr uint32_t CUR_A_bm = 0x1FFUL; 182 | constexpr uint32_t CUR_B_bm = 0x1FF0000UL; 183 | // CHOPCONF 184 | constexpr uint8_t TOFF_bp = 0; 185 | constexpr uint8_t HSTRT_bp = 4; 186 | constexpr uint8_t FD_bp = 4; 187 | constexpr uint8_t HEND_bp = 7; 188 | constexpr uint8_t DISFDCC_bp = 12; 189 | constexpr uint8_t RNDTF_bp = 13; 190 | constexpr uint8_t CHM_bp = 14; 191 | constexpr uint8_t TBL_bp = 15; 192 | constexpr uint8_t VSENSE_bp = 17; 193 | constexpr uint8_t VHIGHFS_bp = 18; 194 | constexpr uint8_t VHIGHCHM_bp = 19; 195 | constexpr uint8_t SYNC_bp = 20; 196 | constexpr uint8_t MRES_bp = 24; 197 | constexpr uint8_t INTPOL_bp = 28; 198 | constexpr uint8_t DEDGE_bp = 29; 199 | constexpr uint8_t DISS2G_bp = 30; 200 | constexpr uint32_t CHOPCONF_bm = 0xFFFFFFFFUL; 201 | constexpr uint32_t TOFF_bm = 0xFUL; 202 | constexpr uint32_t HSTRT_bm = 0x70UL; 203 | constexpr uint32_t FD_bm = 0x830UL; 204 | constexpr uint32_t HEND_bm = 0x780UL; 205 | constexpr uint32_t DISFDCC_bm = 0x1000UL; 206 | constexpr uint32_t RNDTF_bm = 0x2000UL; 207 | constexpr uint32_t CHM_bm = 0x4000UL; 208 | constexpr uint32_t TBL_bm = 0x18000UL; 209 | constexpr uint32_t VSENSE_bm = 0x20000UL; 210 | constexpr uint32_t VHIGHFS_bm = 0x40000UL; 211 | constexpr uint32_t VHIGHCHM_bm = 0x80000UL; 212 | constexpr uint32_t SYNC_bm = 0xF00000UL; 213 | constexpr uint32_t MRES_bm = 0xF000000UL; 214 | constexpr uint32_t INTPOL_bm = 0x10000000UL; 215 | constexpr uint32_t DEDGE_bm = 0x20000000UL; 216 | constexpr uint32_t DISS2G_bm = 0x40000000UL; 217 | // COOLCONF 218 | constexpr uint8_t SEMIN_bp = 0; 219 | constexpr uint8_t SEUP_bp = 5; 220 | constexpr uint8_t SEMAX_bp = 8; 221 | constexpr uint8_t SEDN_bp = 13; 222 | constexpr uint8_t SEIMIN_bp = 15; 223 | constexpr uint8_t SGT_bp = 16; 224 | constexpr uint8_t SFILT_bp = 24; 225 | constexpr uint32_t COOLCONF_bm = 0x3FFFFFFUL; 226 | constexpr uint32_t SEMIN_bm = 0xFUL; 227 | constexpr uint32_t SEUP_bm = 0x60UL; 228 | constexpr uint32_t SEMAX_bm = 0xF00UL; 229 | constexpr uint32_t SEDN_bm = 0x6000UL; 230 | constexpr uint32_t SEIMIN_bm = 0x8000UL; 231 | constexpr uint32_t SGT_bm = 0x7F0000UL; 232 | constexpr uint32_t SFILT_bm = 0x1000000UL; 233 | // DCCTRL 234 | constexpr uint8_t DC_TIME_bp = 0; 235 | constexpr uint8_t DC_SG_bp = 16; 236 | constexpr uint32_t DC_TIME_bm = 0x3FFUL; 237 | constexpr uint32_t DC_SG_bm = 0xFF0000UL; 238 | // DRV_STATUS 239 | constexpr uint8_t SG_RESULT_bp = 0; 240 | constexpr uint8_t FSACTIVE_bp = 15; 241 | constexpr uint8_t CS_ACTUAL_bp = 16; 242 | constexpr uint8_t STALLGUARD_bp = 24; 243 | constexpr uint8_t OT_bp = 25; 244 | constexpr uint8_t OTPW_bp = 26; 245 | constexpr uint8_t S2GA_bp = 27; 246 | constexpr uint8_t S2GB_bp = 28; 247 | constexpr uint8_t OLA_bp = 29; 248 | constexpr uint8_t OLB_bp = 30; 249 | constexpr uint8_t STST_bp = 31; 250 | constexpr uint32_t DRV_STATUS_bm = 0xFFFFFFFFUL; 251 | constexpr uint32_t SG_RESULT_bm = 0x3FFUL; 252 | constexpr uint32_t FSACTIVE_bm = 0x8000UL; 253 | constexpr uint32_t CS_ACTUAL_bm = 0x1F0000UL; 254 | constexpr uint32_t STALLGUARD_bm = 0x1000000UL; 255 | constexpr uint32_t OT_bm = 0x2000000UL; 256 | constexpr uint32_t OTPW_bm = 0x4000000UL; 257 | constexpr uint32_t S2GA_bm = 0x8000000UL; 258 | constexpr uint32_t S2GB_bm = 0x10000000UL; 259 | constexpr uint32_t OLA_bm = 0x20000000UL; 260 | constexpr uint32_t OLB_bm = 0x40000000UL; 261 | constexpr uint32_t STST_bm = 0x80000000UL; 262 | // PWMCONF 263 | constexpr uint8_t PWM_AMPL_bp = 0; 264 | constexpr uint8_t PWM_GRAD_bp = 8; 265 | constexpr uint8_t PWM_FREQ_bp = 16; 266 | constexpr uint8_t PWM_AUTOSCALE_bp = 18; 267 | constexpr uint8_t PWM_SYMMETRIC_bp = 19; 268 | constexpr uint8_t FREEWHEEL_bp = 20; 269 | constexpr uint32_t PWMCONF_bm = 0x7FFFFFUL; 270 | constexpr uint32_t PWM_AMPL_bm = 0xFFUL; 271 | constexpr uint32_t PWM_GRAD_bm = 0xFF00UL; 272 | constexpr uint32_t PWM_FREQ_bm = 0x30000UL; 273 | constexpr uint32_t PWM_AUTOSCALE_bm = 0x40000UL; 274 | constexpr uint32_t PWM_SYMMETRIC_bm = 0x80000UL; 275 | constexpr uint32_t FREEWHEEL_bm = 0x300000UL; 276 | // PWM_SCALE 277 | constexpr uint8_t PWM_SCALE_bp = 0; 278 | constexpr uint32_t PWM_SCALE_bm = 0xFFUL; 279 | // ENCM_CTRL 280 | constexpr uint8_t INV_bp = 0; 281 | constexpr uint8_t MAXSPEED_bp = 1; 282 | constexpr uint32_t INV_bm = 0x1UL; 283 | constexpr uint32_t MAXSPEED_bm = 0x2UL; 284 | // LOST_STEPS 285 | constexpr uint8_t LOST_STEPS_bp = 0; 286 | constexpr uint32_t LOST_STEPS_bm = 0xFFFFFUL; 287 | 288 | #endif 289 | -------------------------------------------------------------------------------- /src/TMC2130Stepper_UTILITY.h: -------------------------------------------------------------------------------- 1 | #ifndef TMC2130Stepper_UTILITY_h 2 | #define TMC2130Stepper_UTILITY_h 3 | 4 | void print_HEX(uint32_t data) { 5 | for(uint8_t B=24; B>=4; B-=8){ 6 | Serial.print((data>>(B+4))&0xF, HEX); 7 | Serial.print((data>>B)&0xF, HEX); 8 | Serial.print(":"); 9 | } 10 | Serial.print((data>>4)&0xF, HEX); 11 | Serial.print(data&0xF, HEX); 12 | } 13 | 14 | void print_BIN(uint32_t data) { 15 | int b = 31; 16 | for(; b>=24; b--){ 17 | Serial.print((data>>b)&0b1); 18 | } 19 | Serial.print("."); 20 | for(; b>=16; b--){ 21 | Serial.print((data>>b)&0b1); 22 | } 23 | Serial.print("."); 24 | for(; b>=8; b--){ 25 | Serial.print((data>>b)&0b1); 26 | } 27 | Serial.print("."); 28 | for(; b>=0; b--){ 29 | Serial.print((data>>b)&0b1); 30 | } 31 | } 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /src/source/SW_SPI.cpp: -------------------------------------------------------------------------------- 1 | #include "SW_SPI.h" 2 | 3 | SW_SPIClass TMC_SW_SPI; 4 | 5 | #if defined(ARDUINO_ARCH_AVR) 6 | #define getPort(P) digitalPinToPort(P) 7 | #define writeMOSI_H *mosi_register |= mosi_bm 8 | #define writeMOSI_L *mosi_register &= ~mosi_bm 9 | #define writeSCK_H *sck_register |= sck_bm 10 | #define writeSCK_L *sck_register &= ~sck_bm 11 | #define readMISO *miso_register & miso_bm 12 | #elif defined(ARDUINO_ARCH_SAM) // DUE:1.2MHz 13 | // by stimmer https://forum.arduino.cc/index.php?topic=129868.msg980466#msg980466 14 | #define writeMOSI_H g_APinDescription[mosi_pin].pPort -> PIO_SODR = g_APinDescription[mosi_pin].ulPin 15 | #define writeMOSI_L g_APinDescription[mosi_pin].pPort -> PIO_CODR = g_APinDescription[mosi_pin].ulPin 16 | #define writeSCK_H g_APinDescription[sck_pin].pPort -> PIO_SODR = g_APinDescription[sck_pin].ulPin 17 | #define writeSCK_L g_APinDescription[sck_pin].pPort -> PIO_CODR = g_APinDescription[sck_pin].ulPin 18 | #define readMISO !!(g_APinDescription[miso_pin].pPort -> PIO_PDSR & g_APinDescription[miso_pin].ulPin) 19 | #else // DUE:116kHz 20 | #define writeMOSI_H digitalWrite(mosi_pin, HIGH) 21 | #define writeMOSI_L digitalWrite(mosi_pin, LOW) 22 | #define writeSCK_H digitalWrite(sck_pin, HIGH) 23 | #define writeSCK_L digitalWrite(sck_pin, LOW) 24 | #define readMISO digitalRead(miso_pin) 25 | #endif 26 | 27 | void SW_SPIClass::setPins(uint16_t sw_mosi_pin, uint16_t sw_miso_pin, uint16_t sw_sck_pin) { 28 | mosi_pin = sw_mosi_pin; 29 | miso_pin = sw_miso_pin; 30 | sck_pin = sw_sck_pin; 31 | } 32 | 33 | void SW_SPIClass::init() { 34 | pinMode(mosi_pin, OUTPUT); 35 | pinMode(sck_pin, OUTPUT); 36 | pinMode(miso_pin, INPUT_PULLUP); 37 | #ifndef TARGET_LPC1768 38 | mosi_bm = digitalPinToBitMask(mosi_pin); 39 | miso_bm = digitalPinToBitMask(miso_pin); 40 | sck_bm = digitalPinToBitMask(sck_pin); 41 | #ifdef ARDUINO_ARCH_AVR 42 | mosi_register = portOutputRegister(getPort(mosi_pin)); 43 | miso_register = portInputRegister(getPort(miso_pin)); 44 | sck_register = portOutputRegister(getPort(sck_pin)); 45 | #endif 46 | #endif 47 | } 48 | 49 | //Combined shiftOut and shiftIn from Arduino wiring_shift.c 50 | byte SW_SPIClass::transfer(uint8_t ulVal, uint8_t ulBitOrder) { 51 | uint8_t value = 0; 52 | 53 | for (uint8_t i=0 ; i<8 ; ++i) { 54 | // Write bit 55 | if ( ulBitOrder == LSBFIRST ) { 56 | !!(ulVal & (1 << i)) ? writeMOSI_H : writeMOSI_L; 57 | } else { 58 | !!(ulVal & (1 << (7 - i))) ? writeMOSI_H : writeMOSI_L; 59 | } 60 | 61 | // Start clock pulse 62 | writeSCK_H; 63 | 64 | // Read bit 65 | if ( ulBitOrder == LSBFIRST ) { 66 | value |= ( readMISO ? 1 : 0) << i ; 67 | } else { 68 | value |= ( readMISO ? 1 : 0) << (7 - i) ; 69 | } 70 | 71 | // Stop clock pulse 72 | writeSCK_L; 73 | } 74 | 75 | return value; 76 | } 77 | 78 | uint16_t SW_SPIClass::transfer16(uint16_t data) { 79 | uint16_t returnVal = 0x0000; 80 | returnVal |= transfer((data>>8)&0xFF) << 8; 81 | returnVal |= transfer(data&0xFF) & 0xFF; 82 | return returnVal; 83 | } 84 | -------------------------------------------------------------------------------- /src/source/SW_SPI.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | class SW_SPIClass { 6 | public: 7 | void setPins(uint16_t sw_mosi_pin, uint16_t sw_miso_pin, uint16_t sw_sck_pin); 8 | void init(); 9 | void begin() {}; 10 | byte transfer(uint8_t ulVal, uint8_t ulBitOrder=MSBFIRST); 11 | uint16_t transfer16(uint16_t data); 12 | void endTransaction() {}; 13 | private: 14 | uint16_t mosi_pin, 15 | miso_pin, 16 | sck_pin; 17 | uint8_t mosi_bm, 18 | miso_bm, 19 | sck_bm; 20 | volatile uint8_t *mosi_register, 21 | *miso_register, 22 | *sck_register; 23 | }; 24 | 25 | extern SW_SPIClass TMC_SW_SPI; 26 | -------------------------------------------------------------------------------- /src/source/TMC2130Stepper.cpp: -------------------------------------------------------------------------------- 1 | #include "TMC2130Stepper.h" 2 | #include "TMC2130Stepper_MACROS.h" 3 | #include 4 | #include "SW_SPI.h" 5 | 6 | TMC2130Stepper::TMC2130Stepper(uint16_t pinCS) : _pinCS(pinCS), uses_sw_spi(false) {} 7 | 8 | TMC2130Stepper::TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS) : 9 | _pinEN(pinEN), 10 | _pinSTEP(pinStep), 11 | _pinCS(pinCS), 12 | _pinDIR(pinDIR), 13 | uses_sw_spi(false) 14 | {} 15 | 16 | TMC2130Stepper::TMC2130Stepper(uint16_t pinEN, uint16_t pinDIR, uint16_t pinStep, uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK) : 17 | _pinEN(pinEN), 18 | _pinSTEP(pinStep), 19 | _pinCS(pinCS), 20 | _pinDIR(pinDIR), 21 | uses_sw_spi(true) 22 | { TMC_SW_SPI.setPins(pinMOSI, pinMISO, pinSCK); } 23 | 24 | void TMC2130Stepper::begin() { 25 | #ifdef TMC2130DEBUG 26 | Serial.println("TMC2130 Stepper driver library"); 27 | Serial.print("Enable pin: "); 28 | Serial.println(_pinEN); 29 | Serial.print("Direction pin: "); 30 | Serial.println(_pinDIR); 31 | Serial.print("Step pin: "); 32 | Serial.println(_pinSTEP); 33 | Serial.print("Chip select pin: "); 34 | Serial.println(_pinCS); 35 | #endif 36 | delay(200); 37 | 38 | //set pins 39 | if (_pinEN != 0xFFFF) { 40 | pinMode(_pinEN, OUTPUT); 41 | digitalWrite(_pinEN, HIGH); //deactivate driver (LOW active) 42 | } 43 | if (_pinDIR != 0xFFFF) { 44 | pinMode(_pinDIR, OUTPUT); 45 | } 46 | if (_pinSTEP != 0xFFFF) { 47 | pinMode(_pinSTEP, OUTPUT); 48 | digitalWrite(_pinSTEP, LOW); 49 | } 50 | 51 | pinMode(_pinCS, OUTPUT); 52 | digitalWrite(_pinCS, HIGH); 53 | 54 | if (uses_sw_spi) TMC_SW_SPI.init(); 55 | 56 | // Reset registers 57 | push(); 58 | 59 | toff(8); //off_time(8); 60 | tbl(1); //blank_time(24); 61 | } 62 | 63 | void TMC2130Stepper::send2130(uint8_t addressByte, uint32_t *config) { 64 | if (uses_sw_spi) { 65 | digitalWrite(_pinCS, LOW); 66 | 67 | status_response = TMC_SW_SPI.transfer(addressByte & 0xFF); // s = 68 | 69 | if (addressByte >> 7) { // Check if WRITE command 70 | //*config &= ~mask; // Clear bits being set 71 | //*config |= (value & mask); // Set new values 72 | TMC_SW_SPI.transfer((*config >> 24) & 0xFF); 73 | TMC_SW_SPI.transfer((*config >> 16) & 0xFF); 74 | TMC_SW_SPI.transfer((*config >> 8) & 0xFF); 75 | TMC_SW_SPI.transfer(*config & 0xFF); 76 | } else { // READ command 77 | TMC_SW_SPI.transfer16(0x0000); // Clear SPI 78 | TMC_SW_SPI.transfer16(0x0000); 79 | digitalWrite(_pinCS, HIGH); 80 | digitalWrite(_pinCS, LOW); 81 | 82 | TMC_SW_SPI.transfer(addressByte & 0xFF); // Send the address byte again 83 | *config = TMC_SW_SPI.transfer(0x00); 84 | *config <<= 8; 85 | *config|= TMC_SW_SPI.transfer(0x00); 86 | *config <<= 8; 87 | *config|= TMC_SW_SPI.transfer(0x00); 88 | *config <<= 8; 89 | *config|= TMC_SW_SPI.transfer(0x00); 90 | } 91 | 92 | digitalWrite(_pinCS, HIGH); 93 | } else { 94 | SPI.begin(); 95 | SPI.beginTransaction(SPISettings(16000000/8, MSBFIRST, SPI_MODE3)); 96 | digitalWrite(_pinCS, LOW); 97 | 98 | status_response = SPI.transfer(addressByte & 0xFF); // s = 99 | 100 | if (addressByte >> 7) { // Check if WRITE command 101 | //*config &= ~mask; // Clear bits being set 102 | //*config |= (value & mask); // Set new values 103 | SPI.transfer((*config >> 24) & 0xFF); 104 | SPI.transfer((*config >> 16) & 0xFF); 105 | SPI.transfer((*config >> 8) & 0xFF); 106 | SPI.transfer(*config & 0xFF); 107 | } else { // READ command 108 | SPI.transfer16(0x0000); // Clear SPI 109 | SPI.transfer16(0x0000); 110 | digitalWrite(_pinCS, HIGH); 111 | digitalWrite(_pinCS, LOW); 112 | 113 | SPI.transfer(addressByte & 0xFF); // Send the address byte again 114 | *config = SPI.transfer(0x00); 115 | *config <<= 8; 116 | *config|= SPI.transfer(0x00); 117 | *config <<= 8; 118 | *config|= SPI.transfer(0x00); 119 | *config <<= 8; 120 | *config|= SPI.transfer(0x00); 121 | } 122 | 123 | digitalWrite(_pinCS, HIGH); 124 | SPI.endTransaction(); 125 | } 126 | } 127 | 128 | bool TMC2130Stepper::checkOT() { 129 | uint32_t response = DRV_STATUS(); 130 | if (response & OTPW_bm) { 131 | flag_otpw = 1; 132 | return true; // bit 26 for overtemperature warning flag 133 | } 134 | return false; 135 | } 136 | 137 | bool TMC2130Stepper::getOTPW() { return flag_otpw; } 138 | 139 | void TMC2130Stepper::clear_otpw() { flag_otpw = 0; } 140 | 141 | bool TMC2130Stepper::isEnabled() { return !digitalRead(_pinEN) && toff(); } 142 | 143 | void TMC2130Stepper::push() { 144 | GCONF(GCONF_sr); 145 | IHOLD_IRUN(IHOLD_IRUN_sr); 146 | TPOWERDOWN(TPOWERDOWN_sr); 147 | TPWMTHRS(TPWMTHRS_sr); 148 | TCOOLTHRS(TCOOLTHRS_sr); 149 | THIGH(THIGH_sr); 150 | XDIRECT(XDIRECT_sr); 151 | VDCMIN(VDCMIN_sr); 152 | CHOPCONF(CHOPCONF_sr); 153 | //MSLUT0(MSLUT0_sr); 154 | //MSLUT1(MSLUT1_sr); 155 | //MSLUT2(MSLUT2_sr); 156 | //MSLUT3(MSLUT3_sr); 157 | //MSLUT4(MSLUT4_sr); 158 | //MSLUT5(MSLUT5_sr); 159 | //MSLUT6(MSLUT6_sr); 160 | //MSLUT7(MSLUT7_sr); 161 | //MSLUT0(MSLUT0_sr); 162 | //MSLUT0(MSLUT0_sr); 163 | //MSLUTSTART(MSLUTSTART_sr); 164 | COOLCONF(COOLCONF_sr); 165 | PWMCONF(PWMCONF_sr); 166 | ENCM_CTRL(ENCM_CTRL_sr); 167 | } 168 | 169 | uint8_t TMC2130Stepper::test_connection() { 170 | uint32_t drv_status = DRV_STATUS(); 171 | switch (drv_status) { 172 | case 0xFFFFFFFF: return 1; 173 | case 0: return 2; 174 | default: return 0; 175 | } 176 | } 177 | 178 | /////////////////////////////////////////////////////////////////////////////////////// 179 | // R+C: GSTAT 180 | void TMC2130Stepper::GSTAT(uint8_t input){ 181 | GSTAT_sr = input; 182 | TMC_WRITE_REG(GSTAT); 183 | } 184 | uint8_t TMC2130Stepper::GSTAT() { TMC_READ_REG_R(GSTAT); } 185 | bool TMC2130Stepper::reset() { TMC_GET_BYTE(GSTAT, RESET); } 186 | bool TMC2130Stepper::drv_err() { TMC_GET_BYTE(GSTAT, DRV_ERR); } 187 | bool TMC2130Stepper::uv_cp() { TMC_GET_BYTE(GSTAT, UV_CP); } 188 | /////////////////////////////////////////////////////////////////////////////////////// 189 | // R: IOIN 190 | uint32_t TMC2130Stepper::IOIN() { TMC_READ_REG_R(IOIN); } 191 | bool TMC2130Stepper::step() { TMC_GET_BYTE_R(IOIN, STEP); } 192 | bool TMC2130Stepper::dir() { TMC_GET_BYTE_R(IOIN, DIR); } 193 | bool TMC2130Stepper::dcen_cfg4() { TMC_GET_BYTE_R(IOIN, DCEN_CFG4); } 194 | bool TMC2130Stepper::dcin_cfg5() { TMC_GET_BYTE_R(IOIN, DCIN_CFG5); } 195 | bool TMC2130Stepper::drv_enn_cfg6() { TMC_GET_BYTE_R(IOIN, DRV_ENN_CFG6); } 196 | bool TMC2130Stepper::dco() { TMC_GET_BYTE_R(IOIN, DCO); } 197 | uint8_t TMC2130Stepper::version() { TMC_GET_BYTE_R(IOIN, VERSION); } 198 | /////////////////////////////////////////////////////////////////////////////////////// 199 | // W: TPOWERDOWN 200 | uint8_t TMC2130Stepper::TPOWERDOWN() { return TPOWERDOWN_sr; } 201 | void TMC2130Stepper::TPOWERDOWN(uint8_t input) { 202 | TPOWERDOWN_sr = input; 203 | TMC_WRITE_REG(TPOWERDOWN); 204 | } 205 | /////////////////////////////////////////////////////////////////////////////////////// 206 | // R: TSTEP 207 | uint32_t TMC2130Stepper::TSTEP() { TMC_READ_REG_R(TSTEP); } 208 | /////////////////////////////////////////////////////////////////////////////////////// 209 | // W: TPWMTHRS 210 | uint32_t TMC2130Stepper::TPWMTHRS() { return TPWMTHRS_sr; } 211 | void TMC2130Stepper::TPWMTHRS(uint32_t input) { 212 | TPWMTHRS_sr = input; 213 | TMC_WRITE_REG(TPWMTHRS); 214 | } 215 | /////////////////////////////////////////////////////////////////////////////////////// 216 | // W: TCOOLTHRS 217 | uint32_t TMC2130Stepper::TCOOLTHRS() { return TCOOLTHRS_sr; } 218 | void TMC2130Stepper::TCOOLTHRS(uint32_t input) { 219 | TCOOLTHRS_sr = input; 220 | TMC_WRITE_REG(TCOOLTHRS); 221 | } 222 | /////////////////////////////////////////////////////////////////////////////////////// 223 | // W: THIGH 224 | uint32_t TMC2130Stepper::THIGH() { return THIGH_sr; } 225 | void TMC2130Stepper::THIGH(uint32_t input) { 226 | THIGH_sr = input; 227 | TMC_WRITE_REG(THIGH); 228 | } 229 | /////////////////////////////////////////////////////////////////////////////////////// 230 | // RW: XDIRECT 231 | uint32_t TMC2130Stepper::XDIRECT() { TMC_READ_REG(XDIRECT); } 232 | void TMC2130Stepper::XDIRECT(uint32_t input) { 233 | XDIRECT_sr = input; 234 | TMC_WRITE_REG(XDIRECT); 235 | } 236 | void TMC2130Stepper::coil_A(int16_t B) { TMC_MOD_REG(XDIRECT, COIL_A); } 237 | void TMC2130Stepper::coil_B(int16_t B) { TMC_MOD_REG(XDIRECT, COIL_B); } 238 | int16_t TMC2130Stepper::coil_A() { TMC_GET_BYTE_R(XDIRECT, COIL_A); } 239 | int16_t TMC2130Stepper::coil_B() { TMC_GET_BYTE_R(XDIRECT, COIL_B); } 240 | /////////////////////////////////////////////////////////////////////////////////////// 241 | // W: VDCMIN 242 | uint32_t TMC2130Stepper::VDCMIN() { return VDCMIN_sr; } 243 | void TMC2130Stepper::VDCMIN(uint32_t input) { 244 | VDCMIN_sr = input; 245 | TMC_WRITE_REG(VDCMIN); 246 | } 247 | /////////////////////////////////////////////////////////////////////////////////////// 248 | // W: MSLUT 249 | uint32_t TMC2130Stepper::MSLUT0() { return MSLUT0_sr; } 250 | void TMC2130Stepper::MSLUT0(uint32_t input) { 251 | MSLUT0_sr = input; 252 | TMC_WRITE_REG(MSLUT0); 253 | } 254 | uint32_t TMC2130Stepper::MSLUT1() { return MSLUT1_sr; } 255 | void TMC2130Stepper::MSLUT1(uint32_t input) { 256 | MSLUT1_sr = input; 257 | TMC_WRITE_REG(MSLUT1); 258 | } 259 | uint32_t TMC2130Stepper::MSLUT2() { return MSLUT2_sr; } 260 | void TMC2130Stepper::MSLUT2(uint32_t input) { 261 | MSLUT2_sr = input; 262 | TMC_WRITE_REG(MSLUT2); 263 | } 264 | uint32_t TMC2130Stepper::MSLUT3() { return MSLUT3_sr; } 265 | void TMC2130Stepper::MSLUT3(uint32_t input) { 266 | MSLUT3_sr = input; 267 | TMC_WRITE_REG(MSLUT3); 268 | } 269 | uint32_t TMC2130Stepper::MSLUT4() { return MSLUT4_sr; } 270 | void TMC2130Stepper::MSLUT4(uint32_t input) { 271 | MSLUT4_sr = input; 272 | TMC_WRITE_REG(MSLUT4); 273 | } 274 | uint32_t TMC2130Stepper::MSLUT5() { return MSLUT5_sr; } 275 | void TMC2130Stepper::MSLUT5(uint32_t input) { 276 | MSLUT0_sr = input; 277 | TMC_WRITE_REG(MSLUT5); 278 | } 279 | uint32_t TMC2130Stepper::MSLUT6() { return MSLUT6_sr; } 280 | void TMC2130Stepper::MSLUT6(uint32_t input) { 281 | MSLUT0_sr = input; 282 | TMC_WRITE_REG(MSLUT6); 283 | } 284 | uint32_t TMC2130Stepper::MSLUT7() { return MSLUT7_sr; } 285 | void TMC2130Stepper::MSLUT7(uint32_t input) { 286 | MSLUT0_sr = input; 287 | TMC_WRITE_REG(MSLUT7); 288 | } 289 | /////////////////////////////////////////////////////////////////////////////////////// 290 | // W: MSLUTSEL 291 | uint32_t TMC2130Stepper::MSLUTSEL() { return MSLUTSEL_sr; } 292 | void TMC2130Stepper::MSLUTSEL(uint32_t input) { 293 | MSLUTSEL_sr = input; 294 | TMC_WRITE_REG(MSLUTSEL); 295 | } 296 | /////////////////////////////////////////////////////////////////////////////////////// 297 | // W: MSLUTSTART 298 | uint32_t TMC2130Stepper::MSLUTSTART() { return MSLUTSTART_sr; } 299 | void TMC2130Stepper::MSLUTSTART(uint32_t input) { 300 | MSLUTSTART_sr = input; 301 | TMC_WRITE_REG(MSLUTSTART); 302 | } 303 | /////////////////////////////////////////////////////////////////////////////////////// 304 | // R: MSCNT 305 | uint16_t TMC2130Stepper::MSCNT() { TMC_READ_REG_R(MSCNT); } 306 | /////////////////////////////////////////////////////////////////////////////////////// 307 | // R: MSCURACT 308 | uint32_t TMC2130Stepper::MSCURACT() { TMC_READ_REG_R(MSCURACT); } 309 | int16_t TMC2130Stepper::cur_a() { 310 | int16_t value = (MSCURACT()&CUR_A_bm) >> CUR_A_bp; 311 | if (value > 255) value -= 512; 312 | return value; 313 | } 314 | int16_t TMC2130Stepper::cur_b() { 315 | int16_t value = (MSCURACT()&CUR_B_bm) >> CUR_B_bp; 316 | if (value > 255) value -= 512; 317 | return value; 318 | } 319 | /////////////////////////////////////////////////////////////////////////////////////// 320 | // R: PWM_SCALE 321 | uint8_t TMC2130Stepper::PWM_SCALE() { TMC_READ_REG_R(PWM_SCALE); } 322 | /////////////////////////////////////////////////////////////////////////////////////// 323 | // W: ENCM_CTRL 324 | uint8_t TMC2130Stepper::ENCM_CTRL() { return ENCM_CTRL_sr; } 325 | void TMC2130Stepper::ENCM_CTRL(uint8_t input) { 326 | ENCM_CTRL_sr = input; 327 | TMC_WRITE_REG(ENCM_CTRL); 328 | } 329 | void TMC2130Stepper::inv(bool B) { TMC_MOD_REG(ENCM_CTRL, INV); } 330 | void TMC2130Stepper::maxspeed(bool B) { TMC_MOD_REG(ENCM_CTRL, MAXSPEED); } 331 | bool TMC2130Stepper::inv() { TMC_GET_BYTE(ENCM_CTRL, INV); } 332 | bool TMC2130Stepper::maxspeed() { TMC_GET_BYTE(ENCM_CTRL, MAXSPEED);} 333 | /////////////////////////////////////////////////////////////////////////////////////// 334 | // R: LOST_STEPS 335 | uint32_t TMC2130Stepper::LOST_STEPS() { TMC_READ_REG_R(LOST_STEPS); } 336 | 337 | 338 | /** 339 | * Helper functions 340 | */ 341 | 342 | 343 | /* 344 | Requested current = mA = I_rms/1000 345 | Equation for current: 346 | I_rms = (CS+1)/32 * V_fs/(R_sense+0.02ohm) * 1/sqrt(2) 347 | Solve for CS -> 348 | CS = 32*sqrt(2)*I_rms*(R_sense+0.02)/V_fs - 1 349 | 350 | Example: 351 | vsense = 0b0 -> V_fs = 0.325V 352 | mA = 1640mA = I_rms/1000 = 1.64A 353 | R_sense = 0.10 Ohm 354 | -> 355 | CS = 32*sqrt(2)*1.64*(0.10+0.02)/0.325 - 1 = 26.4 356 | CS = 26 357 | */ 358 | void TMC2130Stepper::rms_current(uint16_t mA, float multiplier, float RS) { 359 | Rsense = RS; 360 | uint8_t CS = 32.0*1.41421*mA/1000.0*(Rsense+0.02)/0.325 - 1; 361 | // If Current Scale is too low, turn on high sensitivity R_sense and calculate again 362 | if (CS < 16) { 363 | vsense(true); 364 | CS = 32.0*1.41421*mA/1000.0*(Rsense+0.02)/0.180 - 1; 365 | } else if(vsense()) { // If CS >= 16, turn off high_sense_r if it's currently ON 366 | vsense(false); 367 | } 368 | irun(CS); 369 | ihold(CS*multiplier); 370 | val_mA = mA; 371 | } 372 | 373 | uint16_t TMC2130Stepper::rms_current() { 374 | return (float)(irun()+1)/32.0 * (vsense()?0.180:0.325)/(Rsense+0.02) / 1.41421 * 1000; 375 | } 376 | 377 | void TMC2130Stepper::setCurrent(uint16_t mA, float R, float multiplier) { rms_current(mA, multiplier, R); } 378 | uint16_t TMC2130Stepper::getCurrent() { return val_mA; } 379 | 380 | void TMC2130Stepper::SilentStepStick2130(uint16_t current) { rms_current(current); } 381 | 382 | void TMC2130Stepper::microsteps(uint16_t ms) { 383 | switch(ms) { 384 | case 256: mres(0); break; 385 | case 128: mres(1); break; 386 | case 64: mres(2); break; 387 | case 32: mres(3); break; 388 | case 16: mres(4); break; 389 | case 8: mres(5); break; 390 | case 4: mres(6); break; 391 | case 2: mres(7); break; 392 | case 0: mres(8); break; 393 | default: break; 394 | } 395 | } 396 | 397 | uint16_t TMC2130Stepper::microsteps() { 398 | switch(mres()) { 399 | case 0: return 256; 400 | case 1: return 128; 401 | case 2: return 64; 402 | case 3: return 32; 403 | case 4: return 16; 404 | case 5: return 8; 405 | case 6: return 4; 406 | case 7: return 2; 407 | case 8: return 0; 408 | } 409 | return 0; 410 | } 411 | 412 | void TMC2130Stepper::sg_current_decrease(uint8_t value) { 413 | switch(value) { 414 | case 32: sedn(0b00); break; 415 | case 8: sedn(0b01); break; 416 | case 2: sedn(0b10); break; 417 | case 1: sedn(0b11); break; 418 | } 419 | } 420 | uint8_t TMC2130Stepper::sg_current_decrease() { 421 | switch(sedn()) { 422 | case 0b00: return 32; 423 | case 0b01: return 8; 424 | case 0b10: return 2; 425 | case 0b11: return 1; 426 | } 427 | return 0; 428 | } 429 | -------------------------------------------------------------------------------- /src/source/TMC2130Stepper_CHOPCONF.cpp: -------------------------------------------------------------------------------- 1 | #include "TMC2130Stepper.h" 2 | #include "TMC2130Stepper_MACROS.h" 3 | 4 | // CHOPCONF 5 | uint32_t TMC2130Stepper::CHOPCONF() { TMC_READ_REG(CHOPCONF); } 6 | void TMC2130Stepper::CHOPCONF(uint32_t input) { 7 | CHOPCONF_sr = input; 8 | TMC_WRITE_REG(CHOPCONF); 9 | } 10 | 11 | void TMC2130Stepper::toff( uint8_t B ) { TMC_MOD_REG(CHOPCONF, TOFF); } 12 | void TMC2130Stepper::hstrt( uint8_t B ) { TMC_MOD_REG(CHOPCONF, HSTRT); } 13 | void TMC2130Stepper::hend( uint8_t B ) { TMC_MOD_REG(CHOPCONF, HEND); } 14 | void TMC2130Stepper::fd( uint8_t B ) { TMC_MOD_REG(CHOPCONF, FD); } 15 | void TMC2130Stepper::disfdcc( bool B ) { TMC_MOD_REG(CHOPCONF, DISFDCC); } 16 | void TMC2130Stepper::rndtf( bool B ) { TMC_MOD_REG(CHOPCONF, RNDTF); } 17 | void TMC2130Stepper::chm( bool B ) { TMC_MOD_REG(CHOPCONF, CHM); } 18 | void TMC2130Stepper::tbl( uint8_t B ) { TMC_MOD_REG(CHOPCONF, TBL); } 19 | void TMC2130Stepper::vsense( bool B ) { TMC_MOD_REG(CHOPCONF, VSENSE); } 20 | void TMC2130Stepper::vhighfs( bool B ) { TMC_MOD_REG(CHOPCONF, VHIGHFS); } 21 | void TMC2130Stepper::vhighchm( bool B ) { TMC_MOD_REG(CHOPCONF, VHIGHCHM); } 22 | void TMC2130Stepper::sync( uint8_t B ) { TMC_MOD_REG(CHOPCONF, SYNC); } 23 | void TMC2130Stepper::mres( uint8_t B ) { TMC_MOD_REG(CHOPCONF, MRES); } 24 | void TMC2130Stepper::intpol( bool B ) { TMC_MOD_REG(CHOPCONF, INTPOL); } 25 | void TMC2130Stepper::dedge( bool B ) { TMC_MOD_REG(CHOPCONF, DEDGE); } 26 | void TMC2130Stepper::diss2g( bool B ) { TMC_MOD_REG(CHOPCONF, DISS2G); } 27 | 28 | uint8_t TMC2130Stepper::toff() { TMC_GET_BYTE(CHOPCONF, TOFF); } 29 | uint8_t TMC2130Stepper::hstrt() { TMC_GET_BYTE(CHOPCONF, HSTRT); } 30 | uint8_t TMC2130Stepper::hend() { TMC_GET_BYTE(CHOPCONF, HEND); } 31 | uint8_t TMC2130Stepper::fd() { TMC_GET_BYTE(CHOPCONF, FD); } 32 | bool TMC2130Stepper::disfdcc() { TMC_GET_BYTE(CHOPCONF, DISFDCC); } 33 | bool TMC2130Stepper::rndtf() { TMC_GET_BYTE(CHOPCONF, RNDTF); } 34 | bool TMC2130Stepper::chm() { TMC_GET_BYTE(CHOPCONF, CHM); } 35 | uint8_t TMC2130Stepper::tbl() { TMC_GET_BYTE(CHOPCONF, TBL); } 36 | bool TMC2130Stepper::vsense() { TMC_GET_BIT( CHOPCONF, VSENSE); } 37 | bool TMC2130Stepper::vhighfs() { TMC_GET_BYTE(CHOPCONF, VHIGHFS); } 38 | bool TMC2130Stepper::vhighchm() { TMC_GET_BYTE(CHOPCONF, VHIGHCHM); } 39 | uint8_t TMC2130Stepper::sync() { TMC_GET_BYTE(CHOPCONF, SYNC); } 40 | uint8_t TMC2130Stepper::mres() { TMC_GET_BYTE(CHOPCONF, MRES); } 41 | bool TMC2130Stepper::intpol() { TMC_GET_BYTE(CHOPCONF, INTPOL); } 42 | bool TMC2130Stepper::dedge() { TMC_GET_BYTE(CHOPCONF, DEDGE); } 43 | bool TMC2130Stepper::diss2g() { TMC_GET_BYTE(CHOPCONF, DISS2G); } 44 | 45 | void TMC2130Stepper::hysteresis_end(int8_t value) { hend(value+3); } 46 | int8_t TMC2130Stepper::hysteresis_end() { return hend()-3; }; 47 | 48 | void TMC2130Stepper::hysteresis_start(uint8_t value) { hstrt(value-1); } 49 | uint8_t TMC2130Stepper::hysteresis_start() { return hstrt()+1; } 50 | 51 | void TMC2130Stepper::blank_time(uint8_t value) { 52 | switch (value) { 53 | case 16: tbl(0b00); break; 54 | case 24: tbl(0b01); break; 55 | case 36: tbl(0b10); break; 56 | case 54: tbl(0b11); break; 57 | } 58 | } 59 | 60 | uint8_t TMC2130Stepper::blank_time() { 61 | switch (tbl()) { 62 | case 0b00: return 16; 63 | case 0b01: return 24; 64 | case 0b10: return 36; 65 | case 0b11: return 54; 66 | } 67 | return 0; 68 | } 69 | -------------------------------------------------------------------------------- /src/source/TMC2130Stepper_COOLCONF.cpp: -------------------------------------------------------------------------------- 1 | #include "TMC2130Stepper.h" 2 | #include "TMC2130Stepper_MACROS.h" 3 | 4 | // COOLCONF 5 | uint32_t TMC2130Stepper::COOLCONF() { return COOLCONF_sr; } 6 | void TMC2130Stepper::COOLCONF(uint32_t input) { 7 | COOLCONF_sr = input; 8 | TMC_WRITE_REG(COOLCONF); 9 | } 10 | 11 | void TMC2130Stepper::semin( uint8_t B ) { TMC_MOD_REG(COOLCONF, SEMIN); } 12 | void TMC2130Stepper::seup( uint8_t B ) { TMC_MOD_REG(COOLCONF, SEUP); } 13 | void TMC2130Stepper::semax( uint8_t B ) { TMC_MOD_REG(COOLCONF, SEMAX); } 14 | void TMC2130Stepper::sedn( uint8_t B ) { TMC_MOD_REG(COOLCONF, SEDN); } 15 | void TMC2130Stepper::seimin( bool B ) { TMC_MOD_REG(COOLCONF, SEIMIN); } 16 | void TMC2130Stepper::sgt( int8_t B ) { TMC_MOD_REG(COOLCONF, SGT); } 17 | void TMC2130Stepper::sfilt( bool B ) { TMC_MOD_REG(COOLCONF, SFILT); } 18 | 19 | uint8_t TMC2130Stepper::semin() { TMC_GET_BYTE(COOLCONF, SEMIN); } 20 | uint8_t TMC2130Stepper::seup() { TMC_GET_BYTE(COOLCONF, SEUP); } 21 | uint8_t TMC2130Stepper::semax() { TMC_GET_BYTE(COOLCONF, SEMAX); } 22 | uint8_t TMC2130Stepper::sedn() { TMC_GET_BYTE(COOLCONF, SEDN); } 23 | bool TMC2130Stepper::seimin() { TMC_GET_BYTE(COOLCONF, SEIMIN); } 24 | //int8_t TMC2130Stepper::sgt() { TMC_GET_BYTE(COOLCONF, SGT); } 25 | bool TMC2130Stepper::sfilt() { TMC_GET_BYTE(COOLCONF, SFILT); } 26 | 27 | int8_t TMC2130Stepper::sgt() { 28 | // Two's complement in a 7bit value 29 | int8_t val = (COOLCONF()&SGT_bm) >> SGT_bp; 30 | return val <= 63 ? val : val - 128; 31 | } 32 | -------------------------------------------------------------------------------- /src/source/TMC2130Stepper_DRV_STATUS.cpp: -------------------------------------------------------------------------------- 1 | #include "TMC2130Stepper.h" 2 | #include "TMC2130Stepper_MACROS.h" 3 | 4 | uint32_t TMC2130Stepper::DRV_STATUS() { TMC_READ_REG_R(DRV_STATUS); } 5 | 6 | uint16_t TMC2130Stepper::sg_result(){ TMC_GET_BYTE_R(DRV_STATUS, SG_RESULT); } 7 | bool TMC2130Stepper::fsactive() { TMC_GET_BYTE_R(DRV_STATUS, FSACTIVE); } 8 | uint8_t TMC2130Stepper::cs_actual() { TMC_GET_BYTE_R(DRV_STATUS, CS_ACTUAL); } 9 | bool TMC2130Stepper::stallguard() { TMC_GET_BYTE_R(DRV_STATUS, STALLGUARD); } 10 | bool TMC2130Stepper::ot() { TMC_GET_BYTE_R(DRV_STATUS, OT); } 11 | bool TMC2130Stepper::otpw() { TMC_GET_BYTE_R(DRV_STATUS, OTPW); } 12 | bool TMC2130Stepper::s2ga() { TMC_GET_BYTE_R(DRV_STATUS, S2GA); } 13 | bool TMC2130Stepper::s2gb() { TMC_GET_BYTE_R(DRV_STATUS, S2GB); } 14 | bool TMC2130Stepper::ola() { TMC_GET_BYTE_R(DRV_STATUS, OLA); } 15 | bool TMC2130Stepper::olb() { TMC_GET_BYTE_R(DRV_STATUS, OLB); } 16 | bool TMC2130Stepper::stst() { TMC_GET_BYTE_R(DRV_STATUS, STST); } 17 | /* 18 | uint16_t TMC2130Stepper::sg_result() { 19 | uint32_t drv_status = 0x00000000UL; 20 | Serial.print("drv_status="); 21 | Serial.print(drv_status); 22 | drv_status = DRV_STATUS(); 23 | Serial.print("\tdrv_status="); 24 | Serial.print(drv_status); 25 | Serial.print("\t"); 26 | 27 | return drv_status&SG_RESULT_bm; 28 | } 29 | */ -------------------------------------------------------------------------------- /src/source/TMC2130Stepper_GCONF.cpp: -------------------------------------------------------------------------------- 1 | #include "TMC2130Stepper.h" 2 | #include "TMC2130Stepper_MACROS.h" 3 | 4 | // GCONF 5 | uint32_t TMC2130Stepper::GCONF() { TMC_READ_REG(GCONF); } 6 | void TMC2130Stepper::GCONF(uint32_t input) { 7 | GCONF_sr = input; 8 | TMC_WRITE_REG(GCONF); 9 | } 10 | 11 | void TMC2130Stepper::I_scale_analog(bool B) { TMC_MOD_REG(GCONF, I_SCALE_ANALOG); } 12 | void TMC2130Stepper::internal_Rsense(bool B) { TMC_MOD_REG(GCONF, INTERNAL_RSENSE); } 13 | void TMC2130Stepper::en_pwm_mode(bool B) { TMC_MOD_REG(GCONF, EN_PWM_MODE); } 14 | void TMC2130Stepper::enc_commutation(bool B) { TMC_MOD_REG(GCONF, ENC_COMMUTATION); } 15 | void TMC2130Stepper::shaft(bool B) { TMC_MOD_REG(GCONF, SHAFT); } 16 | void TMC2130Stepper::diag0_error(bool B) { TMC_MOD_REG(GCONF, DIAG0_ERROR); } 17 | void TMC2130Stepper::diag0_otpw(bool B) { TMC_MOD_REG(GCONF, DIAG0_OTPW); } 18 | void TMC2130Stepper::diag0_stall(bool B) { TMC_MOD_REG(GCONF, DIAG0_STALL); } 19 | void TMC2130Stepper::diag1_stall(bool B) { TMC_MOD_REG(GCONF, DIAG1_STALL); } 20 | void TMC2130Stepper::diag1_index(bool B) { TMC_MOD_REG(GCONF, DIAG1_INDEX); } 21 | void TMC2130Stepper::diag1_onstate(bool B) { TMC_MOD_REG(GCONF, DIAG1_ONSTATE); } 22 | void TMC2130Stepper::diag1_steps_skipped(bool B) { TMC_MOD_REG(GCONF, DIAG1_STEPS_SKIPPED); } 23 | void TMC2130Stepper::diag0_int_pushpull(bool B) { TMC_MOD_REG(GCONF, DIAG0_INT_PUSHPULL); } 24 | void TMC2130Stepper::diag1_pushpull(bool B) { TMC_MOD_REG(GCONF, DIAG1_PUSHPULL); } 25 | void TMC2130Stepper::small_hysteresis(bool B) { TMC_MOD_REG(GCONF, SMALL_HYSTERESIS); } 26 | void TMC2130Stepper::stop_enable(bool B) { TMC_MOD_REG(GCONF, STOP_ENABLE); } 27 | void TMC2130Stepper::direct_mode(bool B) { TMC_MOD_REG(GCONF, DIRECT_MODE); } 28 | 29 | bool TMC2130Stepper::I_scale_analog() { TMC_GET_BYTE(GCONF, I_SCALE_ANALOG); } 30 | bool TMC2130Stepper::internal_Rsense() { TMC_GET_BYTE(GCONF, INTERNAL_RSENSE); } 31 | bool TMC2130Stepper::en_pwm_mode() { TMC_GET_BYTE(GCONF, EN_PWM_MODE); } 32 | bool TMC2130Stepper::enc_commutation() { TMC_GET_BYTE(GCONF, ENC_COMMUTATION); } 33 | bool TMC2130Stepper::shaft() { TMC_GET_BYTE(GCONF, SHAFT); } 34 | bool TMC2130Stepper::diag0_error() { TMC_GET_BYTE(GCONF, DIAG0_ERROR); } 35 | bool TMC2130Stepper::diag0_otpw() { TMC_GET_BYTE(GCONF, DIAG0_OTPW); } 36 | bool TMC2130Stepper::diag0_stall() { TMC_GET_BYTE(GCONF, DIAG0_STALL); } 37 | bool TMC2130Stepper::diag1_stall() { TMC_GET_BYTE(GCONF, DIAG1_STALL); } 38 | bool TMC2130Stepper::diag1_index() { TMC_GET_BYTE(GCONF, DIAG1_INDEX); } 39 | bool TMC2130Stepper::diag1_onstate() { TMC_GET_BYTE(GCONF, DIAG1_ONSTATE); } 40 | bool TMC2130Stepper::diag1_steps_skipped() { TMC_GET_BYTE(GCONF, DIAG1_STEPS_SKIPPED); } 41 | bool TMC2130Stepper::diag0_int_pushpull() { TMC_GET_BYTE(GCONF, DIAG0_INT_PUSHPULL); } 42 | bool TMC2130Stepper::diag1_pushpull() { TMC_GET_BYTE(GCONF, DIAG1_PUSHPULL); } 43 | bool TMC2130Stepper::small_hysteresis() { TMC_GET_BYTE(GCONF, SMALL_HYSTERESIS); } 44 | bool TMC2130Stepper::stop_enable() { TMC_GET_BYTE(GCONF, STOP_ENABLE); } 45 | bool TMC2130Stepper::direct_mode() { TMC_GET_BYTE(GCONF, DIRECT_MODE); } 46 | 47 | /* 48 | bit 18 not implemented: 49 | test_mode 0: 50 | Normal operation 1: 51 | Enable analog test output on pin DCO. IHOLD[1..0] selects the function of DCO: 52 | 0…2: T120, DAC, VDDH Attention: 53 | Not for user, set to 0 for normal operation! 54 | */ 55 | -------------------------------------------------------------------------------- /src/source/TMC2130Stepper_IHOLD_IRUN.cpp: -------------------------------------------------------------------------------- 1 | #include "TMC2130Stepper.h" 2 | #include "TMC2130Stepper_MACROS.h" 3 | 4 | // IHOLD_IRUN 5 | void TMC2130Stepper::IHOLD_IRUN(uint32_t input) { 6 | IHOLD_IRUN_sr = input; 7 | TMC_WRITE_REG(IHOLD_IRUN); 8 | } 9 | uint32_t TMC2130Stepper::IHOLD_IRUN() { return IHOLD_IRUN_sr; } 10 | 11 | void TMC2130Stepper::ihold(uint8_t B) { TMC_MOD_REG(IHOLD_IRUN, IHOLD); } 12 | void TMC2130Stepper::irun(uint8_t B) { TMC_MOD_REG(IHOLD_IRUN, IRUN); } 13 | void TMC2130Stepper::iholddelay(uint8_t B) { TMC_MOD_REG(IHOLD_IRUN, IHOLDDELAY); } 14 | uint8_t TMC2130Stepper::ihold() { TMC_GET_BYTE(IHOLD_IRUN, IHOLD); } 15 | uint8_t TMC2130Stepper::irun() { TMC_GET_BYTE(IHOLD_IRUN, IRUN); } 16 | uint8_t TMC2130Stepper::iholddelay() { TMC_GET_BYTE(IHOLD_IRUN, IHOLDDELAY); } 17 | -------------------------------------------------------------------------------- /src/source/TMC2130Stepper_MACROS.h: -------------------------------------------------------------------------------- 1 | #ifndef TMC2130Stepper_MACROS_H 2 | #define TMC2130Stepper_MACROS_H 3 | #include "TMC2130Stepper.h" 4 | #include "../TMC2130Stepper_REGDEFS.h" 5 | 6 | #define TMC_WRITE_REG(R) send2130(TMC2130_WRITE|REG_##R, &R##_sr); 7 | 8 | #define TMC_READ_REG(R) send2130(TMC2130_READ|REG_##R, &R##_sr); return R##_sr 9 | 10 | #define TMC_READ_REG_R(R) tmp_sr=0; send2130(TMC2130_READ|REG_##R, &tmp_sr); return tmp_sr; 11 | 12 | #define TMC_MOD_REG(REG, SETTING) REG##_sr &= ~SETTING##_bm; \ 13 | REG##_sr |= ((uint32_t)B<> SETTING##_bp; 17 | 18 | #define TMC_GET_BYTE_R(REG, SETTING) return (REG()&SETTING##_bm) >> SETTING##_bp; 19 | 20 | #define TMC_GET_BIT(REG, SETTING) return (bool)((REG()&SETTING##_bm) >> SETTING##_bp); 21 | 22 | #endif 23 | -------------------------------------------------------------------------------- /src/source/TMC2130Stepper_PWMCONF.cpp: -------------------------------------------------------------------------------- 1 | #include "TMC2130Stepper.h" 2 | #include "TMC2130Stepper_MACROS.h" 3 | 4 | 5 | // PWMCONF 6 | uint32_t TMC2130Stepper::PWMCONF() { return PWMCONF_sr; } 7 | void TMC2130Stepper::PWMCONF(uint32_t input) { 8 | PWMCONF_sr = input; 9 | TMC_WRITE_REG(PWMCONF); 10 | } 11 | 12 | void TMC2130Stepper::pwm_ampl( uint8_t B ) { TMC_MOD_REG(PWMCONF, PWM_AMPL); } 13 | void TMC2130Stepper::pwm_grad( uint8_t B ) { TMC_MOD_REG(PWMCONF, PWM_GRAD); } 14 | void TMC2130Stepper::pwm_freq( uint8_t B ) { TMC_MOD_REG(PWMCONF, PWM_FREQ); } 15 | void TMC2130Stepper::pwm_autoscale( bool B ) { TMC_MOD_REG(PWMCONF, PWM_AUTOSCALE); } 16 | void TMC2130Stepper::pwm_symmetric( bool B ) { TMC_MOD_REG(PWMCONF, PWM_SYMMETRIC); } 17 | void TMC2130Stepper::freewheel( uint8_t B ) { TMC_MOD_REG(PWMCONF, FREEWHEEL); } 18 | 19 | uint8_t TMC2130Stepper::pwm_ampl() { TMC_GET_BYTE(PWMCONF, PWM_AMPL); } 20 | uint8_t TMC2130Stepper::pwm_grad() { TMC_GET_BYTE(PWMCONF, PWM_GRAD); } 21 | uint8_t TMC2130Stepper::pwm_freq() { TMC_GET_BYTE(PWMCONF, PWM_FREQ); } 22 | bool TMC2130Stepper::pwm_autoscale() { TMC_GET_BYTE(PWMCONF, PWM_AUTOSCALE); } 23 | bool TMC2130Stepper::pwm_symmetric() { TMC_GET_BYTE(PWMCONF, PWM_SYMMETRIC); } 24 | uint8_t TMC2130Stepper::freewheel() { TMC_GET_BYTE(PWMCONF, FREEWHEEL); } 25 | --------------------------------------------------------------------------------