├── .github └── workflows │ └── build_examples_esp_idf_project.yml ├── .gitignore ├── .metadata └── README.org ├── CMakeLists.txt ├── LICENSE ├── Makefile ├── README.md ├── datasheet ├── TMC2209_SilentStepStick_datasheet_Rev1.20.pdf └── TMC2209_datasheet_rev1.09.pdf ├── examples ├── BidirectionalCommunication │ ├── CoolStep │ │ └── CoolStep.ino │ ├── HoldCurrent │ │ └── HoldCurrent.ino │ ├── MicrostepsPerStep │ │ └── MicrostepsPerStep.ino │ ├── MoveAtVelocity │ │ └── MoveAtVelocity.ino │ ├── ReplyDelay │ │ └── ReplyDelay.ino │ ├── RunCurrent │ │ └── RunCurrent.ino │ ├── SettingsAndStatus │ │ └── SettingsAndStatus.ino │ ├── StallGuard │ │ └── StallGuard.ino │ ├── TestBaudRate │ │ └── TestBaudRate.ino │ ├── TestCommunication │ │ └── TestCommunication.ino │ ├── TestDisconnection │ │ └── TestDisconnection.ino │ ├── TestRP2040 │ │ └── TestRP2040.ino │ └── TestUnoR4 │ │ └── TestUnoR4.ino ├── ESPIDFExample │ ├── .gitignore │ ├── CMakeLists.txt │ ├── README.md │ ├── main │ │ ├── CMakeLists.txt │ │ ├── idf_component.yml │ │ └── main.cpp │ └── sdkconfig.defaults └── UnidirectionalCommunication │ ├── HardwareEnable │ └── HardwareEnable.ino │ ├── MoveAtVelocity │ └── MoveAtVelocity.ino │ ├── SoftwareSerial │ └── SoftwareSerial.ino │ ├── Standstill │ └── Standstill.ino │ ├── StepAndDirection │ └── StepAndDirection.ino │ ├── TMC429RampMode │ └── TMC429RampMode.ino │ ├── TMC429ThreeSteppers │ └── TMC429ThreeSteppers.ino │ ├── TMC429VelocityMode │ └── TMC429VelocityMode.ino │ └── TestRP2040 │ └── TestRP2040.ino ├── idf_component.yml ├── images ├── trinamic_wiring-TMC2209-bidirectional-coupled-multiple-address.svg ├── trinamic_wiring-TMC2209-bidirectional-coupled-multiple-uart.svg ├── trinamic_wiring-TMC2209-bidirectional-coupled.svg ├── trinamic_wiring-TMC2209-description.svg ├── trinamic_wiring-TMC2209-mega2560.svg ├── trinamic_wiring-TMC2209-microcontroller.svg ├── trinamic_wiring-TMC2209-stepper-controller.svg ├── trinamic_wiring-TMC2209-teensy40.svg ├── trinamic_wiring-TMC2209-unidirectional-multiple-address.svg ├── trinamic_wiring-TMC2209-unidirectional-multiple-uart.svg ├── trinamic_wiring-TMC2209-unidirectional-multiple.svg ├── trinamic_wiring-TMC2209-unidirectional.svg └── trinamic_wiring-TMC2209-uno.svg ├── library.properties ├── platformio.ini └── src ├── TMC2209.h └── TMC2209 └── TMC2209.cpp /.github/workflows/build_examples_esp_idf_project.yml: -------------------------------------------------------------------------------- 1 | name: Build ESP-IDF example project 2 | 3 | on: 4 | push: 5 | branches: [main] 6 | pull_request: 7 | branches: [main] 8 | 9 | jobs: 10 | build: 11 | runs-on: ubuntu-latest 12 | 13 | steps: 14 | - name: Checkout 15 | uses: actions/checkout@v4 16 | - name: esp-idf build 17 | uses: espressif/esp-idf-ci-action@v1 18 | with: 19 | esp_idf_version: v5.3.2 20 | target: esp32 21 | path: examples/ESPIDFExample 22 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | .DS_Store 2 | /.idea 3 | /build 4 | /bin 5 | /lib 6 | /sftp-config.json 7 | .tags 8 | .tags_sorted_by_file 9 | *~ 10 | \#*\# 11 | .\#* 12 | .pio 13 | .venv 14 | -------------------------------------------------------------------------------- /.metadata/README.org: -------------------------------------------------------------------------------- 1 | #+EXPORT_FILE_NAME: ../README.md 2 | #+OPTIONS: toc:1 |:t ^:nil tags:nil 3 | #+TITLE: TMC2209 4 | #+AUTHOR: Peter Polidoro 5 | #+EMAIL: peter@polidoro.io 6 | 7 | # Place warning at the top of the exported file 8 | #+BEGIN_EXAMPLE 9 | 10 | 11 | #+END_EXAMPLE 12 | 13 | * Library Information 14 | - Name :: TMC2209 15 | - Version :: 10.1.0 16 | - License :: BSD 17 | - URL :: https://github.com/janelia-arduino/TMC2209 18 | - Author :: Peter Polidoro 19 | - Email :: peter@polidoro.io 20 | - Contributors 21 | - thinkier 22 | - pvginkel 23 | 24 | ** Description 25 | 26 | The TMC2209 is an ultra-silent motor driver IC for two phase stepper motors with 27 | both UART serial and step and direction interfaces. 28 | 29 | #+html: 30 | 31 | * Stepper Motors 32 | 33 | From Wikipedia, the free encyclopedia: 34 | 35 | A stepper motor, also known as step motor or stepping motor, is a brushless DC 36 | electric motor that divides a full rotation into a number of equal steps. The 37 | motor's position can be commanded to move and hold at one of these steps without 38 | any position sensor for feedback (an open-loop controller), as long as the motor 39 | is correctly sized to the application in respect to torque and speed. 40 | 41 | [[https://en.wikipedia.org/wiki/Stepper_motor][Wikipedia - Stepper Motor]] 42 | 43 | * Stepper Motor Controllers and Drivers 44 | 45 | Stepper motors need both a controller and a driver. These may be combined into a 46 | single component or separated into multiple components that communicate with 47 | each other, as is the case with the TMC2209 stepper motor driver. One controller 48 | may be connected to more than one driver for coordinated multi-axis motion 49 | control. 50 | 51 | ** Stepper Motor Controller 52 | 53 | A stepper motor controller is responsible for the commanding either the motor 54 | kinetics, the torque, or the motor kinematics, the position, speed, and 55 | acceleration of one or more stepper motors. 56 | 57 | ** Stepper Motor Driver 58 | 59 | A stepper motor driver is responsible for commanding the electrical current 60 | through the motor coils as it changes with time to meet the requirements of the 61 | stepper motor controller. 62 | 63 | ** TMC2209 Stepper Motor Driver and Controller Combination 64 | 65 | The TMC2209 is a stepper motor driver and it needs a stepper motor controller 66 | communicating with it. 67 | 68 | The TMC2209 can be used as both a stepper motor driver and stepper motor 69 | controller combined, independent from a separate stepper motor controller, but 70 | it is limited to simple velocity control mode only, with no direct position or 71 | acceleration control. 72 | 73 | In velocity control mode, the velocity of the motor is set by the method 74 | moveAtVelocity(int32_t microsteps_per_period). The actual magnitude of the 75 | velocity depends on the TMC2209 clock frequency. The TMC2209 clock frequency 76 | (fclk) is normally 12 MHz if the internal clock is used, but can be between 4 77 | and 16 MHz if an external clock is used. 78 | 79 | In general: 80 | microsteps_per_second = microsteps_per_period * (fclk Hz / 2^24) 81 | 82 | Using internal 12 MHz clock (default): 83 | microsteps_per_second = microsteps_per_period * 0.715 Hz 84 | 85 | Crude position control can be performed in this simple velocity control mode by 86 | commanding the driver to move the motor at a velocity, then after a given amount 87 | of time commanding it to stop, but small delays in the system will cause 88 | position errors. Plus without acceleration control, the stepper motor may also 89 | slip when it attempts to jump to a new velocity value causing more position 90 | errors. For some applications, these position errors may not matter, making 91 | simple velocity control good enough to save the trouble and expense of adding a 92 | separate stepper controller. 93 | 94 | Many of this library's examples use the simple velocity control mode to test the 95 | driver independently from a separate stepper motor controller, however in most 96 | real world applications a separate motor controller is needed, along with the 97 | TMC2209 and this library, for position and acceleration control. 98 | 99 | *** Microcontroller Stepper Motor Controller 100 | 101 | One controller option is to use just a single microcontroller, communicating 102 | with the TMC2209 over both the UART serial interface and the step and direction 103 | interface. 104 | 105 | #+html: 106 | 107 | *** TMC429 and Microcontroller Stepper Motor Controller 108 | 109 | Another controller option is to use both a microcontroller and a separate step 110 | and direction controller, such as the TMC429. 111 | 112 | #+html: 113 | 114 | * Communication 115 | 116 | The TMC2209 driver has two interfaces to communicate with a stepper motor 117 | controller, a UART serial interface and a step and direction interface. 118 | 119 | The UART serial interface may be used for tuning and control options, for 120 | diagnostics, and for simple velocity commands. 121 | 122 | The step and direction interface may be used for real-time position, velocity, 123 | and acceleration commands. The step and direction signals may be synchronized 124 | with the step and direction signals to other stepper drivers for coordinated 125 | multi-axis motion. 126 | 127 | ** UART Serial Interface 128 | 129 | [[https://en.wikipedia.org/wiki/Universal_asynchronous_receiver-transmitter][Wikipedia - UART]] 130 | 131 | The TMC2209 communicates over a UART serial port using a single wire interface, 132 | allowing either unidirectional communication, for parameter setting only, or for 133 | bidirectional communication allowing full control and diagnostics. It can be 134 | driven by any standard microcontroller UART or even by bit banging in software. 135 | 136 | *** Unidirectional Communication 137 | 138 | TMC2209 parameters may be set using unidirectional communication from a 139 | microcontroller UART serial TX pin to the TMC2209 PDN_UART pin. Responses from 140 | the TMC2209 to the microcontroller are ignored. 141 | 142 | #+html: 143 | 144 | *** Bidirectional Communication 145 | 146 | The UART single wire interface allows control of the TMC2209 with any set of 147 | microcontroller UART serial TX and RX pins. 148 | 149 | **** Coupled 150 | 151 | The simpliest way to connect the single TMC2209 serial signal to both the 152 | microcontroller TX pin and RX pin is to use a 1k resistor between the TX pin and 153 | the RX pin to separate them. 154 | 155 | Coupling the TX and RX lines together has the disadvantage of echoing all of the 156 | TX commands from the microcontroller to the TMC2209 on the microcontroller RX 157 | line. These echos need to be removed by this library in order to properly read 158 | responses from the TMC2209. 159 | 160 | Another disadvantage to coupling the TX and RX lines together is that it limits 161 | the length of wire between the microcontroller and the TMC2209. The TMC2209 162 | performs a CRC (cyclic redundancy check) which helps increase interface 163 | distances while decreasing the risk of wrong or missed commands even in the 164 | event of electromagnetic disturbances. 165 | 166 | #+html: 167 | 168 | *** Serial Setup 169 | 170 | The microcontroller serial port must be specified during the TMC2209 setup. 171 | 172 | Microcontroller serial ports may either be implemented in hardware or software. 173 | 174 | Hardware serial ports use dedicated hardware on the microcontroller to perform 175 | serial UART communication. 176 | 177 | Software serial ports allow serial communication on other microcontroller 178 | digital pins that do not have dedicated UART hardware by replicating the 179 | functionality in software. 180 | 181 | Hardware serial ports should always be preferred over software serial ports. 182 | Software serial ports have many performance limitations, such as not allowing 183 | transmitting and receiving data at the same time, lower baud rates, and using 184 | software serial ports may affect performance of other code running on the 185 | microcontroller. 186 | 187 | Not all platforms implement SoftwareSerial, for example ESP32 and SAMD_SERIES. 188 | If any other platforms fail to compile because SoftwareSerial cannot be found, 189 | please submit an issue saying which platform fails. 190 | 191 | **** Hardware Serial Setup 192 | 193 | #+BEGIN_SRC cpp 194 | #include 195 | 196 | 197 | // Instantiate TMC2209 198 | TMC2209 stepper_driver; 199 | 200 | HardwareSerial & serial_stream = Serial1; 201 | 202 | void setup() 203 | { 204 | stepper_driver.setup(serial_stream); 205 | } 206 | #+END_SRC 207 | 208 | **** Hardware Serial Setup with Alternate RX and TX pins 209 | 210 | Some microcontrollers (e.g. ESP32) allow alternative hardware serial RX and TX 211 | pins. 212 | 213 | #+BEGIN_SRC cpp 214 | #include 215 | 216 | 217 | // Instantiate TMC2209 218 | TMC2209 stepper_driver; 219 | 220 | HardwareSerial & serial_stream = Serial1; 221 | const long SERIAL_BAUD_RATE = 115200; 222 | const int RX_PIN = 5; 223 | const int TX_PIN = 26; 224 | 225 | void setup() 226 | { 227 | stepper_driver.setup(serial_stream, SERIAL_BAUD_RATE, TMC2209::SERIAL_ADDRESS_0, RX_PIN, TX_PIN); 228 | } 229 | #+END_SRC 230 | 231 | **** Software Serial Setup 232 | 233 | #+BEGIN_SRC cpp 234 | #include 235 | 236 | 237 | // Instantiate TMC2209 238 | TMC2209 stepper_driver; 239 | 240 | // Software serial ports should only be used for unidirectional communication 241 | // The RX pin does not need to be connected, but it must be specified when 242 | // creating an instance of a SoftwareSerial object 243 | const int RX_PIN = 0; 244 | const int TX_PIN = 1; 245 | SoftwareSerial soft_serial(RX_PIN, TX_PIN); 246 | 247 | void setup() 248 | { 249 | stepper_driver.setup(soft_serial); 250 | } 251 | #+END_SRC 252 | 253 | *** Arduino Serial 254 | 255 | [[https://www.arduino.cc/reference/en/language/functions/communication/serial][Arduino Serial Web Page]] 256 | 257 | On some Arduino boards (e.g. Uno, Nano, Mini, and Mega) pins 0 and 1 are used 258 | for communication with the computer on the serial port named "Serial". Pins 0 259 | and 1 cannot be used on these boards to communicate with the TMC2209. Connecting 260 | anything to these pins can interfere with that communication, including causing 261 | failed uploads to the board. 262 | 263 | Arduino boards with additional hardware serial ports, such as "Serial1" and 264 | "Serial2", can use those ports to communicate with the TMC2209. 265 | 266 | *** Teensy Serial 267 | 268 | [[https://www.pjrc.com/teensy/td_uart.html][Teensy Serial Web Page]] 269 | 270 | The Teensy boards have 1 to 8 hardware serial ports (Serial1 - Serial8), which 271 | may be used to connect to serial devices. 272 | 273 | Unlike Arduino boards, the Teensy USB serial interface is not connected to pins 274 | 0 and 1, allowing pins 0 and 1 to be used to communicate with a TMC2209 using 275 | "Serial1". 276 | 277 | *** Serial Baud Rate 278 | 279 | The serial baud rate is the speed of communication in bits per second of the 280 | UART serial port connected to the TMC2209. 281 | 282 | In theory, baud rates from 9600 Baud to 500000 Baud or even higher (when using 283 | an external clock) may be used. No baud rate configuration on the chip is 284 | required, as the TMC2209 automatically adapts to the baud rate. In practice, it 285 | was found that the baud rate may range from 19200 to 500000 without errors when 286 | using hardware serial ports. Software serial ports use a default baud rate of 9600. 287 | 288 | The higher the baud rate the better, but microcontrollers have various UART 289 | serial abilities and limitations which affects the maximum baud allowed. The 290 | baud rate may be specified when setting up the stepper driver. 291 | 292 | **** Arduino 293 | 294 | The maximum serial baud rate on typical Arduino boards is 115200, so that is the 295 | default when using hardware serial ports, but other values as low as 19200 may 296 | be used. 297 | 298 | [[https://www.arduino.cc/reference/en/language/functions/communication/serial/]] 299 | 300 | **** Teensy 301 | 302 | Teensy UART baud rates can go higher than many typical Arduino boards, so 500k 303 | is a good setting to use, but other values as low as 19200 may be used. 304 | 305 | [[https://www.pjrc.com/teensy/td_uart.html][Teensy Serial Baud Rate Web Page]] 306 | 307 | #+BEGIN_SRC cpp 308 | #include 309 | 310 | // Instantiate TMC2209 311 | TMC2209 stepper_driver; 312 | HardwareSerial & serial_stream = Serial1; 313 | const long SERIAL_BAUD_RATE = 500000; 314 | 315 | void setup() 316 | { 317 | stepper_driver.setup(Serial1, SERIAL_BAUD_RATE); 318 | } 319 | #+END_SRC 320 | 321 | *** Connecting multiple TMC2209 chips 322 | 323 | **** Unidirectional Communication 324 | 325 | ***** All chips using identical settings 326 | 327 | If only unidirectional communication is desired and all TMC2209 chips connected 328 | to the same serial line will have identical settings, then no serial addressing 329 | is required. All chips can be programmed in parallel like a single device. 330 | 331 | #+BEGIN_SRC cpp 332 | #include 333 | 334 | // Instantiate a single TMC2209 to talk to multiple chips 335 | TMC2209 stepper_drivers; 336 | 337 | void setup() 338 | { 339 | stepper_drivers.setup(Serial1); 340 | } 341 | #+END_SRC 342 | 343 | #+html: 344 | 345 | ***** Chips needing different settings using one UART 346 | 347 | #+BEGIN_SRC cpp 348 | #include 349 | 350 | // Instantiate the two TMC2209 351 | TMC2209 stepper_driver_0; 352 | const TMC2209::SerialAddress SERIAL_ADDRESS_0 = TMC2209::SERIAL_ADDRESS_0; 353 | TMC2209 stepper_driver_1; 354 | const TMC2209::SerialAddress SERIAL_ADDRESS_1 = TMC2209::SERIAL_ADDRESS_1; 355 | const long SERIAL_BAUD_RATE = 115200; 356 | 357 | void setup() 358 | { 359 | // TMC2209::SERIAL_ADDRESS_0 is used by default if not specified 360 | stepper_driver_0.setup(Serial1, SERIAL_BAUD_RATE, SERIAL_ADDRESS_0); 361 | stepper_driver_1.setup(Serial1, SERIAL_BAUD_RATE, SERIAL_ADDRESS_1); 362 | } 363 | #+END_SRC 364 | 365 | #+html: 366 | 367 | ***** Chips needing different settings using multiple UART 368 | 369 | #+BEGIN_SRC cpp 370 | #include 371 | 372 | // Instantiate the two TMC2209 373 | TMC2209 stepper_driver_0; 374 | TMC2209 stepper_driver_1; 375 | const long SERIAL_BAUD_RATE = 115200; 376 | 377 | void setup() 378 | { 379 | stepper_driver_0.setup(Serial1, SERIAL_BAUD_RATE); 380 | stepper_driver_1.setup(Serial2, SERIAL_BAUD_RATE); 381 | } 382 | #+END_SRC 383 | 384 | #+html: 385 | 386 | **** Bidirectional Communication 387 | 388 | ***** Chips needing different settings using one UART 389 | 390 | More than one TMC2209 may be connected to a single serial port, if each TMC2209 391 | is assigned a unique serial address. The default serial address is 392 | "SERIAL_ADDRESS_0". The serial address may be changed from "SERIAL_ADDRESS_0" 393 | using the TMC2209 hardware input pins MS1 and MS2, to "SERIAL_ADDRESS_1", 394 | "SERIAL_ADDRESS_2", or "SERIAL_ADDRESS_3". 395 | 396 | The TMC2209 serial address must be specified during the TMC2209 setup, if it is 397 | not equal to the default of "SERIAL_ADDRESS_0". 398 | 399 | When multiple TMC2209 chips are connected to the same serial line with multiple 400 | addresses then the reply delay value should be increased, otherwise a 401 | non-addressed chip might detect a transmission error upon read access to a 402 | different chip. 403 | 404 | #+BEGIN_SRC cpp 405 | #include 406 | 407 | // Instantiate the two TMC2209 408 | TMC2209 stepper_driver_0; 409 | const TMC2209::SerialAddress SERIAL_ADDRESS_0 = TMC2209::SERIAL_ADDRESS_0; 410 | TMC2209 stepper_driver_1; 411 | const TMC2209::SerialAddress SERIAL_ADDRESS_1 = TMC2209::SERIAL_ADDRESS_1; 412 | const uint8_t REPLY_DELAY = 4; 413 | const long SERIAL_BAUD_RATE = 115200; 414 | 415 | void setup() 416 | { 417 | // TMC2209::SERIAL_ADDRESS_0 is used by default if not specified 418 | stepper_driver_0.setup(Serial1,SERIAL_BAUD_RATE,SERIAL_ADDRESS_0); 419 | stepper_driver_0.setReplyDelay(REPLY_DELAY); 420 | stepper_driver_1.setup(Serial1,SERIAL_BAUD_RATE,SERIAL_ADDRESS_1); 421 | stepper_driver_1.setReplyDelay(REPLY_DELAY); 422 | } 423 | #+END_SRC 424 | 425 | #+html: 426 | 427 | ***** Chips needing different settings using multiple UART 428 | 429 | #+BEGIN_SRC cpp 430 | #include 431 | 432 | // Instantiate the two TMC2209 433 | TMC2209 stepper_driver_0; 434 | TMC2209 stepper_driver_1; 435 | const long SERIAL_BAUD_RATE = 115200; 436 | 437 | void setup() 438 | { 439 | stepper_driver_0.setup(Serial1, SERIAL_BAUD_RATE); 440 | stepper_driver_1.setup(Serial2, SERIAL_BAUD_RATE); 441 | } 442 | #+END_SRC 443 | 444 | #+html: 445 | 446 | ** Step and Direction Interface 447 | 448 | *** Microcontroller Stepper Motor Controller 449 | 450 | The step and direction signals may be output from a microcontroller, using one 451 | output pin for the step signal and another output pin for the direction signal. 452 | 453 | *** TMC429 and Microcontroller Stepper Motor Controller 454 | 455 | The step and direction signals may be output from a dedicated step and direction 456 | controller, such as the TMC429. 457 | 458 | A library such as the Arduino TMC429 library may be used to control the step and 459 | direction output signals. 460 | 461 | [[https://github.com/janelia-arduino/TMC429][Arduino TMC429 Library]] 462 | 463 | * Settings 464 | 465 | The default settings for this library are not the same as the default settings 466 | for the TMC2209 chip during power up. 467 | 468 | The default settings for this library were chosen to be as conservative as 469 | possible so that motors can be attached to the chip without worry that they will 470 | accidentally overheat from too much current before library settings can be 471 | changed. 472 | 473 | These default settings may cause this library to not work properly with a 474 | particular motor until the settings are changed. 475 | 476 | The driver starts off with the outputs disabled, with the motor current 477 | minimized, with analog current scaling disabled, and both the automatic current 478 | scaling and automatic gradient adaptation disabled, and the cool step feature 479 | disabled. 480 | 481 | Change driver settings with care as they may cause the motors, wires, or driver 482 | to overheat and be damaged when the current is too high. The driver tends to 483 | protect itself and shutdown when it overheats, then reenable when the driver 484 | cools, which can result in odd jerky motor motion. 485 | 486 | ** Driver Enable 487 | 488 | The driver is disabled by default and must be enabled before use. 489 | 490 | The driver may be disabled in two ways, either in hardware or in software, and 491 | the driver must be enabled in both ways in order to drive a motor. 492 | 493 | To enable the driver in software, or optionally in both hardware and software, 494 | use the enable() method. 495 | 496 | To disable the driver in software, or optionally in both hardware and software, 497 | use the disable() method. 498 | 499 | *** Hardware Enable 500 | 501 | The TMC2209 chip has an enable input pin that switches off the power stage, 502 | all motor outputs floating, when the pin is driven to a high level, independent 503 | of software settings. 504 | 505 | The chip itself is hardware enabled by default, but many stepper driver boards 506 | pull the enable input pin high, which causes the driver to be disabled by 507 | default. 508 | 509 | To hardware enable the driver using this library, use the setHardwareEnablePin 510 | method to assign a microcontroller pin to contol the TMC2209 enable line. 511 | 512 | To hardware enable the driver without using this library, pull the enable pin 513 | low, either with a jumper or with an output pin from the microcontroller. 514 | 515 | The method hardwareDisabled() can be used to tell if the driver is disabled in 516 | hardware. 517 | 518 | *** Software Enable 519 | 520 | The TMC2209 may also be enabled and disabled in software, independent of the 521 | hardware enable pin. 522 | 523 | When the driver is disabled in software it behaves the same as being disabled by 524 | the hardware enable pin, the power stages are switched off and all motor outputs 525 | are floating. 526 | 527 | This library disables the driver in software by default. 528 | 529 | ** Analog Current Scaling 530 | 531 | Analog current scaling is disabled in this library by default, so a 532 | potentiometer connected to VREF will not set the current limit of the driver. 533 | Current settings are controlled by UART commands instead. 534 | 535 | Use enableAnalogCurrentScaling() to allow VREF, the analog input of the driver, 536 | to be used for current control. 537 | 538 | According to the datasheet, modifying VREF or the supply voltage invalidates the 539 | result of the automatic tuning process. So take care when attempting to use 540 | analog current scaling with automatic tuning at the same time. 541 | 542 | ** Automatic Tuning 543 | 544 | The TMC2209 can operate in one of two modes, the voltage control mode and the 545 | current control mode. 546 | 547 | In both modes, the driver uses PWM (pulse width modulation) to set the voltage 548 | on the motor coils, which then determines how much current flows through the 549 | coils. In voltage control mode, the driver sets the PWM based only on the driver 550 | settings and the velocity of the motor. In current control mode, the driver uses 551 | driver settings and the velocity to set the PWM as well, but in addition it also 552 | measures the current through the coils and adjusts the PWM automatically in 553 | order to maintain the proper current levels in the coils. 554 | 555 | Voltage control mode is the default of this library. 556 | 557 | The datasheet recommends using current control mode unless the motor type, the 558 | supply voltage, and the motor load, the operating conditions, are well known. This 559 | library uses voltage control mode by default, though, because there seem to be 560 | cases when the driver is unable to calibrate the motor properties properly and 561 | that can cause the motor to overheat before the settings are adjusted. 562 | 563 | The datasheet explains how to make sure the driver performs the proper automatic 564 | tuning routine in order to use current control mode. 565 | 566 | Use enableAutomaticCurrentScaling() to switch to current control mode instead. 567 | 568 | *** Voltage Control Mode 569 | 570 | Use disableAutomaticCurrentScaling() to switch to voltage control mode and 571 | disable automatic tuning. 572 | 573 | When automatic current scaling is disabled, the driver operates in a feed 574 | forward velocity-controlled mode and will not react to a change of the supply 575 | voltage or to events like a motor stall, but it provides a very stable 576 | amplitude. 577 | 578 | When automatic tuning is disabled, the run current and hold current settings are 579 | not enforced by regulation but scale the PWM amplitude only. When automatic 580 | tuning is disabled, the PWM offset and PWM gradient values may need to be set 581 | manually in order to adjust the motor current to proper levels. 582 | 583 | *** Current Control Mode 584 | 585 | Use enableAutomaticCurrentScaling() to switch to current control mode and 586 | enable automatic tuning. 587 | 588 | Use enableAutomaticGradientAdaptation() when in current control mode to allow 589 | the driver to automatically adjust the pwm gradient value. 590 | 591 | When the driver is in current control mode it measures the current and uses that 592 | feedback to automatically adjust the voltage when the velocity, voltage supply, 593 | or load on the motor changes. In order to respond properly to the current 594 | feedback, the driver must perform a calibration routine, an automatic tuning 595 | procedure, to measure the motor properties. This allows high motor dynamics and 596 | supports powering down the motor to very low currents. 597 | 598 | Refer to the datasheet to see how to make the driver perform the automatic 599 | tuning procedure properly. 600 | 601 | *** PWM Offset 602 | 603 | The PWM offset relates the motor current to the motor voltage when the motor is 604 | at standstill. 605 | 606 | Use setPwmOffset(pwm_amplitude) to change. 607 | pwm_amplitude range: 0-255 608 | 609 | In voltage control mode, increase the PWM offset to increase the motor current. 610 | 611 | In current control mode, the pwm offset value is used for initialization only. 612 | The driver will calculate the pwm offset value automatically. 613 | 614 | *** PWM Gradient 615 | 616 | The PWM gradient adjusts the relationship between the motor current to the motor 617 | voltage to compensate for the velocity-dependent motor back-EMF. 618 | 619 | Use setPwmGradient(pwm_amplitude) to change. 620 | pwm_amplitude range: 0-255 621 | 622 | In voltage control mode, increase the PWM gradient to increase the motor current 623 | if it decreases too much when the motor increases velocity. 624 | 625 | In current control mode, the pwm gradient value is used for initialization only. 626 | The driver will calculate the pwm gradient value automatically. 627 | 628 | *** Run Current 629 | 630 | The run current is used to scale the spinning motor current. 631 | 632 | Use setRunCurrent(percent) to change. 633 | percent range: 0-100 634 | 635 | In voltage control mode, the run current scales the PWM amplitude, but the 636 | current setting is not measured and adjusted when changes to the operating 637 | conditions occur. Use the PWM offset, the PWM gradient, and the run current all 638 | three to adjust the motor current. 639 | 640 | In current control mode, setting the run current is the way to adjust the 641 | spinning motor current. The driver will measure the current and automatically 642 | adjust the voltage to maintain the run current, even with the operating 643 | conditions change. The PWM offset and the PWM gradient may be changed to help 644 | the automatic tuning procedure, but changing the run current alone is enough to 645 | adjust the motor current since the driver will adjust the offset and gradient 646 | automatically. 647 | 648 | *** Standstill Mode 649 | 650 | The standstill mode determines how the motor will behave when the driver is 651 | commanded to be at zero velocity. 652 | 653 | Use setStandstillMode(mode) to change. 654 | mode values: NORMAL, FREEWHEELING, STRONG_BRAKING, BRAKING 655 | 656 | **** NORMAL 657 | 658 | In NORMAL mode, the driver actively holds the motor still using the hold current 659 | setting to scale the motor current. 660 | 661 | **** FREEWHEELING 662 | 663 | In FREEWHEELING mode, the motor is free to spin freely when the driver is set to 664 | zero velocity. 665 | 666 | **** STRONG_BRAKING and BRAKING 667 | 668 | When the mode is either BRAKING, or STRONG_BRAKING, the motor coils will be 669 | shorted inside the driver so the motor will tend to stay in one place even 670 | though current is not actively being driven into the coils. 671 | 672 | *** Hold Current 673 | 674 | The hold current is used to scale the standstill motor current, based on the 675 | standstill mode and the hold delay settings. 676 | 677 | Use setHoldCurrent(percent) to change. 678 | percent range: 0-100 679 | 680 | In voltage control mode, the hold current scales the PWM amplitude, but the 681 | current setting is not measured and adjusted when changes to the operating 682 | conditions occur. Use the PWM offset and the hold current both to adjust the 683 | motor current. 684 | 685 | In current control mode, setting the hold current is the way to adjust the 686 | stationary motor current. The driver will measure the current and automatically 687 | adjust the voltage to maintain the hold current, even with the operating 688 | conditions change. The PWM offset may be changed to help the automatic tuning 689 | procedure, but changing the hold current alone is enough to adjust the motor 690 | current since the driver will adjust the offset automatically. 691 | 692 | * Examples 693 | 694 | ** Wiring 695 | 696 | *** Teensy 4.0 697 | 698 | #+html: 699 | 700 | *** Mega 2560 701 | 702 | #+html: 703 | 704 | *** Uno 705 | 706 | #+html: 707 | 708 | *** Wiring Documentation Source 709 | 710 | [[https://github.com/janelia-kicad/trinamic_wiring]] 711 | 712 | * Hardware Documentation 713 | 714 | ** Datasheets 715 | 716 | [[./datasheet][Datasheets]] 717 | 718 | ** TMC2209 Stepper Driver Integrated Circuit 719 | 720 | [[https://www.trinamic.com/products/integrated-circuits/details/tmc2209-la][Trinamic TMC2209-LA Web Page]] 721 | 722 | ** TMC429 Stepper Controller Integrated Circuit 723 | 724 | [[https://www.trinamic.com/products/integrated-circuits/details/tmc429/][Trinamic TMC429 Web Page]] 725 | 726 | ** SilentStepStick Stepper Driver Board 727 | 728 | [[https://www.trinamic.com/support/eval-kits/details/silentstepstick][Trinamic TMC2209 SilentStepStick Web Page]] 729 | 730 | ** BIGTREETECH TMC2209 V1.2 UART Stepper Motor Driver 731 | 732 | [[https://www.biqu.equipment/products/bigtreetech-tmc2209-stepper-motor-driver-for-3d-printer-board-vs-tmc2208][BIGTREETECH TMC2209 Web Page]] 733 | 734 | ** Janelia Stepper Driver 735 | 736 | [[https://github.com/janelia-kicad/stepper_driver][Janelia Stepper Driver Web Page]] 737 | 738 | * Host Computer Setup 739 | 740 | ** Download this repository 741 | 742 | [[https://github.com/janelia-arduino/TMC2209.git]] 743 | 744 | #+BEGIN_SRC sh 745 | git clone https://github.com/janelia-arduino/TMC2209.git 746 | #+END_SRC 747 | 748 | ** PlatformIO 749 | 750 | *** Install PlatformIO Core 751 | 752 | [[https://docs.platformio.org/en/latest/core/installation/index.html]] 753 | 754 | #+BEGIN_SRC sh 755 | python3 -m venv .venv 756 | source .venv/bin/activate 757 | pip install platformio 758 | pio --version 759 | #+END_SRC 760 | 761 | *** 99-platformio-udev.rules 762 | 763 | Linux users have to install udev rules for PlatformIO supported boards/devices. 764 | 765 | **** Download udev rules file to /etc/udev/rules.d 766 | 767 | #+BEGIN_SRC sh 768 | curl -fsSL https://raw.githubusercontent.com/platformio/platformio-core/develop/platformio/assets/system/99-platformio-udev.rules | sudo tee /etc/udev/rules.d/99-platformio-udev.rules 769 | #+END_SRC 770 | 771 | **** Restart udev management tool 772 | 773 | #+BEGIN_SRC sh 774 | sudo service udev restart 775 | #+END_SRC 776 | 777 | **** Add user to groups 778 | 779 | #+BEGIN_SRC sh 780 | sudo usermod -a -G dialout $USER && sudo usermod -a -G plugdev $USER 781 | #+END_SRC 782 | 783 | **** Remove modemmanager 784 | 785 | #+BEGIN_SRC sh 786 | sudo apt-get purge --auto-remove modemmanager 787 | #+END_SRC 788 | 789 | **** After setting up rules and groups 790 | 791 | You will need to log out and log back in again (or reboot) for the user group changes to take effect. 792 | 793 | After this file is installed, physically unplug and reconnect your board. 794 | 795 | *** Compile the firmware 796 | 797 | 798 | **** Gnu/Linux 799 | 800 | #+BEGIN_SRC sh 801 | make teensy-firmware 802 | make mega-firmware 803 | make uno-firmware 804 | #+END_SRC 805 | 806 | **** Other 807 | 808 | #+BEGIN_SRC sh 809 | pio run -e teensy40 810 | pio run -e mega 811 | pio run -e uno 812 | #+END_SRC 813 | 814 | *** Upload the firmware 815 | 816 | **** Gnu/Linux 817 | 818 | #+BEGIN_SRC sh 819 | make teensy-upload 820 | make mega-upload 821 | make uno-upload 822 | #+END_SRC 823 | 824 | **** Other 825 | 826 | #+BEGIN_SRC sh 827 | pio run -e teensy40 -t upload 828 | pio run -e mega -t upload 829 | pio run -e uno -t upload 830 | #+END_SRC 831 | 832 | *** Serial Terminal Monitor 833 | 834 | **** Gnu/Linux 835 | 836 | #+BEGIN_SRC sh 837 | make monitor 838 | #+END_SRC 839 | 840 | **** Other 841 | 842 | #+BEGIN_SRC sh 843 | pio device monitor 844 | #+END_SRC 845 | 846 | 847 | 848 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | idf_component_register( 2 | SRC_DIRS "src/TMC2209" 3 | INCLUDE_DIRS "src" 4 | REQUIRES arduino-esp32 5 | ) 6 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Janelia Open-Source Software 2 | (3-clause BSD License) 3 | 4 | Copyright (c) 2025 Howard Hughes Medical Institute 5 | 6 | Redistribution and use in source and binary forms, with or without modification, 7 | are permitted provided that the following conditions are met: 8 | 9 | * Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | * Redistributions in binary form must reproduce the above copyright notice, this 13 | list of conditions and the following disclaimer in the documentation and/or 14 | other materials provided with the distribution. 15 | 16 | * Neither the name of HHMI nor the names of its contributors may be used to 17 | endorse or promote products derived from this software without specific prior 18 | written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND 21 | ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 22 | WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR 24 | ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 25 | (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 26 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON 27 | ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 28 | (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 29 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /Makefile: -------------------------------------------------------------------------------- 1 | .PHONY: clean 2 | clean: 3 | rm -rf .pio 4 | 5 | .PHONY: teensy-firmware 6 | teensy-firmware: clean 7 | pio run -e teensy40 8 | 9 | .PHONY: teensy-upload 10 | teensy-upload: clean 11 | pio run -e teensy40 --target upload --upload-port /dev/ttyACM0 12 | 13 | .PHONY: mega-firmware 14 | mega-firmware: clean 15 | pio run -e mega 16 | 17 | .PHONY: mega-upload 18 | mega-upload: clean 19 | pio run -e mega --target upload --upload-port /dev/ttyACM0 20 | 21 | .PHONY: uno-firmware 22 | uno-firmware: clean 23 | pio run -e uno 24 | 25 | .PHONY: uno-upload 26 | uno-upload: clean 27 | pio run -e uno --target upload --upload-port /dev/ttyACM0 28 | 29 | .PHONY: pico-firmware 30 | pico-firmware: clean 31 | pio run -e pico 32 | 33 | .PHONY: pico-upload 34 | pico-upload: clean 35 | pio run -e pico --target upload 36 | 37 | .PHONY: monitor 38 | monitor: 39 | pio device monitor --echo --eol=LF 40 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | - [Library Information](#org9ab8e38) 2 | - [Stepper Motors](#org7e329c1) 3 | - [Stepper Motor Controllers and Drivers](#org80e44f6) 4 | - [Communication](#org62a53dc) 5 | - [Settings](#org3adfd4f) 6 | - [Examples](#orgd87eb2f) 7 | - [Hardware Documentation](#orgf2b9409) 8 | - [Host Computer Setup](#org2ad4462) 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | # Library Information 17 | 18 | - **Name:** TMC2209 19 | - **Version:** 10.1.0 20 | - **License:** BSD 21 | - **URL:** 22 | - **Author:** Peter Polidoro 23 | - **Email:** peter@polidoro.io 24 | - Contributors 25 | - thinkier 26 | - pvginkel 27 | 28 | 29 | ## Description 30 | 31 | The TMC2209 is an ultra-silent motor driver IC for two phase stepper motors with both UART serial and step and direction interfaces. 32 | 33 | 34 | 35 | 36 | 37 | 38 | # Stepper Motors 39 | 40 | From Wikipedia, the free encyclopedia: 41 | 42 | A stepper motor, also known as step motor or stepping motor, is a brushless DC electric motor that divides a full rotation into a number of equal steps. The motor's position can be commanded to move and hold at one of these steps without any position sensor for feedback (an open-loop controller), as long as the motor is correctly sized to the application in respect to torque and speed. 43 | 44 | [Wikipedia - Stepper Motor](https://en.wikipedia.org/wiki/Stepper_motor) 45 | 46 | 47 | 48 | 49 | # Stepper Motor Controllers and Drivers 50 | 51 | Stepper motors need both a controller and a driver. These may be combined into a single component or separated into multiple components that communicate with each other, as is the case with the TMC2209 stepper motor driver. One controller may be connected to more than one driver for coordinated multi-axis motion control. 52 | 53 | 54 | ## Stepper Motor Controller 55 | 56 | A stepper motor controller is responsible for the commanding either the motor kinetics, the torque, or the motor kinematics, the position, speed, and acceleration of one or more stepper motors. 57 | 58 | 59 | ## Stepper Motor Driver 60 | 61 | A stepper motor driver is responsible for commanding the electrical current through the motor coils as it changes with time to meet the requirements of the stepper motor controller. 62 | 63 | 64 | ## TMC2209 Stepper Motor Driver and Controller Combination 65 | 66 | The TMC2209 is a stepper motor driver and it needs a stepper motor controller communicating with it. 67 | 68 | The TMC2209 can be used as both a stepper motor driver and stepper motor controller combined, independent from a separate stepper motor controller, but it is limited to simple velocity control mode only, with no direct position or acceleration control. 69 | 70 | In velocity control mode, the velocity of the motor is set by the method moveAtVelocity(int32\_t microsteps\_per\_period). The actual magnitude of the velocity depends on the TMC2209 clock frequency. The TMC2209 clock frequency (fclk) is normally 12 MHz if the internal clock is used, but can be between 4 and 16 MHz if an external clock is used. 71 | 72 | In general: microsteps\_per\_second = microsteps\_per\_period \* (fclk Hz / 2^24) 73 | 74 | Using internal 12 MHz clock (default): microsteps\_per\_second = microsteps\_per\_period \* 0.715 Hz 75 | 76 | Crude position control can be performed in this simple velocity control mode by commanding the driver to move the motor at a velocity, then after a given amount of time commanding it to stop, but small delays in the system will cause position errors. Plus without acceleration control, the stepper motor may also slip when it attempts to jump to a new velocity value causing more position errors. For some applications, these position errors may not matter, making simple velocity control good enough to save the trouble and expense of adding a separate stepper controller. 77 | 78 | Many of this library's examples use the simple velocity control mode to test the driver independently from a separate stepper motor controller, however in most real world applications a separate motor controller is needed, along with the TMC2209 and this library, for position and acceleration control. 79 | 80 | 81 | ### Microcontroller Stepper Motor Controller 82 | 83 | One controller option is to use just a single microcontroller, communicating with the TMC2209 over both the UART serial interface and the step and direction interface. 84 | 85 | 86 | 87 | 88 | ### TMC429 and Microcontroller Stepper Motor Controller 89 | 90 | Another controller option is to use both a microcontroller and a separate step and direction controller, such as the TMC429. 91 | 92 | 93 | 94 | 95 | 96 | 97 | # Communication 98 | 99 | The TMC2209 driver has two interfaces to communicate with a stepper motor controller, a UART serial interface and a step and direction interface. 100 | 101 | The UART serial interface may be used for tuning and control options, for diagnostics, and for simple velocity commands. 102 | 103 | The step and direction interface may be used for real-time position, velocity, and acceleration commands. The step and direction signals may be synchronized with the step and direction signals to other stepper drivers for coordinated multi-axis motion. 104 | 105 | 106 | ## UART Serial Interface 107 | 108 | [Wikipedia - UART](https://en.wikipedia.org/wiki/Universal_asynchronous_receiver-transmitter) 109 | 110 | The TMC2209 communicates over a UART serial port using a single wire interface, allowing either unidirectional communication, for parameter setting only, or for bidirectional communication allowing full control and diagnostics. It can be driven by any standard microcontroller UART or even by bit banging in software. 111 | 112 | 113 | ### Unidirectional Communication 114 | 115 | TMC2209 parameters may be set using unidirectional communication from a microcontroller UART serial TX pin to the TMC2209 PDN\_UART pin. Responses from the TMC2209 to the microcontroller are ignored. 116 | 117 | 118 | 119 | 120 | ### Bidirectional Communication 121 | 122 | The UART single wire interface allows control of the TMC2209 with any set of microcontroller UART serial TX and RX pins. 123 | 124 | 1. Coupled 125 | 126 | The simpliest way to connect the single TMC2209 serial signal to both the microcontroller TX pin and RX pin is to use a 1k resistor between the TX pin and the RX pin to separate them. 127 | 128 | Coupling the TX and RX lines together has the disadvantage of echoing all of the TX commands from the microcontroller to the TMC2209 on the microcontroller RX line. These echos need to be removed by this library in order to properly read responses from the TMC2209. 129 | 130 | Another disadvantage to coupling the TX and RX lines together is that it limits the length of wire between the microcontroller and the TMC2209. The TMC2209 performs a CRC (cyclic redundancy check) which helps increase interface distances while decreasing the risk of wrong or missed commands even in the event of electromagnetic disturbances. 131 | 132 | 133 | 134 | 135 | ### Serial Setup 136 | 137 | The microcontroller serial port must be specified during the TMC2209 setup. 138 | 139 | Microcontroller serial ports may either be implemented in hardware or software. 140 | 141 | Hardware serial ports use dedicated hardware on the microcontroller to perform serial UART communication. 142 | 143 | Software serial ports allow serial communication on other microcontroller digital pins that do not have dedicated UART hardware by replicating the functionality in software. 144 | 145 | Hardware serial ports should always be preferred over software serial ports. Software serial ports have many performance limitations, such as not allowing transmitting and receiving data at the same time, lower baud rates, and using software serial ports may affect performance of other code running on the microcontroller. 146 | 147 | Not all platforms implement SoftwareSerial, for example ESP32 and SAMD\_SERIES. If any other platforms fail to compile because SoftwareSerial cannot be found, please submit an issue saying which platform fails. 148 | 149 | 1. Hardware Serial Setup 150 | 151 | ```cpp 152 | #include 153 | 154 | 155 | // Instantiate TMC2209 156 | TMC2209 stepper_driver; 157 | 158 | HardwareSerial & serial_stream = Serial1; 159 | 160 | void setup() 161 | { 162 | stepper_driver.setup(serial_stream); 163 | } 164 | ``` 165 | 166 | 2. Hardware Serial Setup with Alternate RX and TX pins 167 | 168 | Some microcontrollers (e.g. ESP32) allow alternative hardware serial RX and TX pins. 169 | 170 | ```cpp 171 | #include 172 | 173 | 174 | // Instantiate TMC2209 175 | TMC2209 stepper_driver; 176 | 177 | HardwareSerial & serial_stream = Serial1; 178 | const long SERIAL_BAUD_RATE = 115200; 179 | const int RX_PIN = 5; 180 | const int TX_PIN = 26; 181 | 182 | void setup() 183 | { 184 | stepper_driver.setup(serial_stream, SERIAL_BAUD_RATE, TMC2209::SERIAL_ADDRESS_0, RX_PIN, TX_PIN); 185 | } 186 | ``` 187 | 188 | 3. Software Serial Setup 189 | 190 | ```cpp 191 | #include 192 | 193 | 194 | // Instantiate TMC2209 195 | TMC2209 stepper_driver; 196 | 197 | // Software serial ports should only be used for unidirectional communication 198 | // The RX pin does not need to be connected, but it must be specified when 199 | // creating an instance of a SoftwareSerial object 200 | const int RX_PIN = 0; 201 | const int TX_PIN = 1; 202 | SoftwareSerial soft_serial(RX_PIN, TX_PIN); 203 | 204 | void setup() 205 | { 206 | stepper_driver.setup(soft_serial); 207 | } 208 | ``` 209 | 210 | 211 | ### Arduino Serial 212 | 213 | [Arduino Serial Web Page](https://www.arduino.cc/reference/en/language/functions/communication/serial) 214 | 215 | On some Arduino boards (e.g. Uno, Nano, Mini, and Mega) pins 0 and 1 are used for communication with the computer on the serial port named "Serial". Pins 0 and 1 cannot be used on these boards to communicate with the TMC2209. Connecting anything to these pins can interfere with that communication, including causing failed uploads to the board. 216 | 217 | Arduino boards with additional hardware serial ports, such as "Serial1" and "Serial2", can use those ports to communicate with the TMC2209. 218 | 219 | 220 | ### Teensy Serial 221 | 222 | [Teensy Serial Web Page](https://www.pjrc.com/teensy/td_uart.html) 223 | 224 | The Teensy boards have 1 to 8 hardware serial ports (Serial1 - Serial8), which may be used to connect to serial devices. 225 | 226 | Unlike Arduino boards, the Teensy USB serial interface is not connected to pins 0 and 1, allowing pins 0 and 1 to be used to communicate with a TMC2209 using "Serial1". 227 | 228 | 229 | ### Serial Baud Rate 230 | 231 | The serial baud rate is the speed of communication in bits per second of the UART serial port connected to the TMC2209. 232 | 233 | In theory, baud rates from 9600 Baud to 500000 Baud or even higher (when using an external clock) may be used. No baud rate configuration on the chip is required, as the TMC2209 automatically adapts to the baud rate. In practice, it was found that the baud rate may range from 19200 to 500000 without errors when using hardware serial ports. Software serial ports use a default baud rate of 9600. 234 | 235 | The higher the baud rate the better, but microcontrollers have various UART serial abilities and limitations which affects the maximum baud allowed. The baud rate may be specified when setting up the stepper driver. 236 | 237 | 1. Arduino 238 | 239 | The maximum serial baud rate on typical Arduino boards is 115200, so that is the default when using hardware serial ports, but other values as low as 19200 may be used. 240 | 241 | 242 | 243 | 2. Teensy 244 | 245 | Teensy UART baud rates can go higher than many typical Arduino boards, so 500k is a good setting to use, but other values as low as 19200 may be used. 246 | 247 | [Teensy Serial Baud Rate Web Page](https://www.pjrc.com/teensy/td_uart.html) 248 | 249 | ```cpp 250 | #include 251 | 252 | // Instantiate TMC2209 253 | TMC2209 stepper_driver; 254 | HardwareSerial & serial_stream = Serial1; 255 | const long SERIAL_BAUD_RATE = 500000; 256 | 257 | void setup() 258 | { 259 | stepper_driver.setup(Serial1, SERIAL_BAUD_RATE); 260 | } 261 | ``` 262 | 263 | 264 | ### Connecting multiple TMC2209 chips 265 | 266 | 1. Unidirectional Communication 267 | 268 | 1. All chips using identical settings 269 | 270 | If only unidirectional communication is desired and all TMC2209 chips connected to the same serial line will have identical settings, then no serial addressing is required. All chips can be programmed in parallel like a single device. 271 | 272 | ```cpp 273 | #include 274 | 275 | // Instantiate a single TMC2209 to talk to multiple chips 276 | TMC2209 stepper_drivers; 277 | 278 | void setup() 279 | { 280 | stepper_drivers.setup(Serial1); 281 | } 282 | ``` 283 | 284 | 285 | 286 | 2. Chips needing different settings using one UART 287 | 288 | ```cpp 289 | #include 290 | 291 | // Instantiate the two TMC2209 292 | TMC2209 stepper_driver_0; 293 | const TMC2209::SerialAddress SERIAL_ADDRESS_0 = TMC2209::SERIAL_ADDRESS_0; 294 | TMC2209 stepper_driver_1; 295 | const TMC2209::SerialAddress SERIAL_ADDRESS_1 = TMC2209::SERIAL_ADDRESS_1; 296 | const long SERIAL_BAUD_RATE = 115200; 297 | 298 | void setup() 299 | { 300 | // TMC2209::SERIAL_ADDRESS_0 is used by default if not specified 301 | stepper_driver_0.setup(Serial1, SERIAL_BAUD_RATE, SERIAL_ADDRESS_0); 302 | stepper_driver_1.setup(Serial1, SERIAL_BAUD_RATE, SERIAL_ADDRESS_1); 303 | } 304 | ``` 305 | 306 | 307 | 308 | 3. Chips needing different settings using multiple UART 309 | 310 | ```cpp 311 | #include 312 | 313 | // Instantiate the two TMC2209 314 | TMC2209 stepper_driver_0; 315 | TMC2209 stepper_driver_1; 316 | const long SERIAL_BAUD_RATE = 115200; 317 | 318 | void setup() 319 | { 320 | stepper_driver_0.setup(Serial1, SERIAL_BAUD_RATE); 321 | stepper_driver_1.setup(Serial2, SERIAL_BAUD_RATE); 322 | } 323 | ``` 324 | 325 | 326 | 327 | 2. Bidirectional Communication 328 | 329 | 1. Chips needing different settings using one UART 330 | 331 | More than one TMC2209 may be connected to a single serial port, if each TMC2209 is assigned a unique serial address. The default serial address is "SERIAL\_ADDRESS\_0". The serial address may be changed from "SERIAL\_ADDRESS\_0" using the TMC2209 hardware input pins MS1 and MS2, to "SERIAL\_ADDRESS\_1", "SERIAL\_ADDRESS\_2", or "SERIAL\_ADDRESS\_3". 332 | 333 | The TMC2209 serial address must be specified during the TMC2209 setup, if it is not equal to the default of "SERIAL\_ADDRESS\_0". 334 | 335 | When multiple TMC2209 chips are connected to the same serial line with multiple addresses then the reply delay value should be increased, otherwise a non-addressed chip might detect a transmission error upon read access to a different chip. 336 | 337 | ```cpp 338 | #include 339 | 340 | // Instantiate the two TMC2209 341 | TMC2209 stepper_driver_0; 342 | const TMC2209::SerialAddress SERIAL_ADDRESS_0 = TMC2209::SERIAL_ADDRESS_0; 343 | TMC2209 stepper_driver_1; 344 | const TMC2209::SerialAddress SERIAL_ADDRESS_1 = TMC2209::SERIAL_ADDRESS_1; 345 | const uint8_t REPLY_DELAY = 4; 346 | const long SERIAL_BAUD_RATE = 115200; 347 | 348 | void setup() 349 | { 350 | // TMC2209::SERIAL_ADDRESS_0 is used by default if not specified 351 | stepper_driver_0.setup(Serial1,SERIAL_BAUD_RATE,SERIAL_ADDRESS_0); 352 | stepper_driver_0.setReplyDelay(REPLY_DELAY); 353 | stepper_driver_1.setup(Serial1,SERIAL_BAUD_RATE,SERIAL_ADDRESS_1); 354 | stepper_driver_1.setReplyDelay(REPLY_DELAY); 355 | } 356 | ``` 357 | 358 | 359 | 360 | 2. Chips needing different settings using multiple UART 361 | 362 | ```cpp 363 | #include 364 | 365 | // Instantiate the two TMC2209 366 | TMC2209 stepper_driver_0; 367 | TMC2209 stepper_driver_1; 368 | const long SERIAL_BAUD_RATE = 115200; 369 | 370 | void setup() 371 | { 372 | stepper_driver_0.setup(Serial1, SERIAL_BAUD_RATE); 373 | stepper_driver_1.setup(Serial2, SERIAL_BAUD_RATE); 374 | } 375 | ``` 376 | 377 | 378 | 379 | 380 | ## Step and Direction Interface 381 | 382 | 383 | ### Microcontroller Stepper Motor Controller 384 | 385 | The step and direction signals may be output from a microcontroller, using one output pin for the step signal and another output pin for the direction signal. 386 | 387 | 388 | ### TMC429 and Microcontroller Stepper Motor Controller 389 | 390 | The step and direction signals may be output from a dedicated step and direction controller, such as the TMC429. 391 | 392 | A library such as the Arduino TMC429 library may be used to control the step and direction output signals. 393 | 394 | [Arduino TMC429 Library](https://github.com/janelia-arduino/TMC429) 395 | 396 | 397 | 398 | 399 | # Settings 400 | 401 | The default settings for this library are not the same as the default settings for the TMC2209 chip during power up. 402 | 403 | The default settings for this library were chosen to be as conservative as possible so that motors can be attached to the chip without worry that they will accidentally overheat from too much current before library settings can be changed. 404 | 405 | These default settings may cause this library to not work properly with a particular motor until the settings are changed. 406 | 407 | The driver starts off with the outputs disabled, with the motor current minimized, with analog current scaling disabled, and both the automatic current scaling and automatic gradient adaptation disabled, and the cool step feature disabled. 408 | 409 | Change driver settings with care as they may cause the motors, wires, or driver to overheat and be damaged when the current is too high. The driver tends to protect itself and shutdown when it overheats, then reenable when the driver cools, which can result in odd jerky motor motion. 410 | 411 | 412 | ## Driver Enable 413 | 414 | The driver is disabled by default and must be enabled before use. 415 | 416 | The driver may be disabled in two ways, either in hardware or in software, and the driver must be enabled in both ways in order to drive a motor. 417 | 418 | To enable the driver in software, or optionally in both hardware and software, use the enable() method. 419 | 420 | To disable the driver in software, or optionally in both hardware and software, use the disable() method. 421 | 422 | 423 | ### Hardware Enable 424 | 425 | The TMC2209 chip has an enable input pin that switches off the power stage, all motor outputs floating, when the pin is driven to a high level, independent of software settings. 426 | 427 | The chip itself is hardware enabled by default, but many stepper driver boards pull the enable input pin high, which causes the driver to be disabled by default. 428 | 429 | To hardware enable the driver using this library, use the setHardwareEnablePin method to assign a microcontroller pin to contol the TMC2209 enable line. 430 | 431 | To hardware enable the driver without using this library, pull the enable pin low, either with a jumper or with an output pin from the microcontroller. 432 | 433 | The method hardwareDisabled() can be used to tell if the driver is disabled in hardware. 434 | 435 | 436 | ### Software Enable 437 | 438 | The TMC2209 may also be enabled and disabled in software, independent of the hardware enable pin. 439 | 440 | When the driver is disabled in software it behaves the same as being disabled by the hardware enable pin, the power stages are switched off and all motor outputs are floating. 441 | 442 | This library disables the driver in software by default. 443 | 444 | 445 | ## Analog Current Scaling 446 | 447 | Analog current scaling is disabled in this library by default, so a potentiometer connected to VREF will not set the current limit of the driver. Current settings are controlled by UART commands instead. 448 | 449 | Use enableAnalogCurrentScaling() to allow VREF, the analog input of the driver, to be used for current control. 450 | 451 | According to the datasheet, modifying VREF or the supply voltage invalidates the result of the automatic tuning process. So take care when attempting to use analog current scaling with automatic tuning at the same time. 452 | 453 | 454 | ## Automatic Tuning 455 | 456 | The TMC2209 can operate in one of two modes, the voltage control mode and the current control mode. 457 | 458 | In both modes, the driver uses PWM (pulse width modulation) to set the voltage on the motor coils, which then determines how much current flows through the coils. In voltage control mode, the driver sets the PWM based only on the driver settings and the velocity of the motor. In current control mode, the driver uses driver settings and the velocity to set the PWM as well, but in addition it also measures the current through the coils and adjusts the PWM automatically in order to maintain the proper current levels in the coils. 459 | 460 | Voltage control mode is the default of this library. 461 | 462 | The datasheet recommends using current control mode unless the motor type, the supply voltage, and the motor load, the operating conditions, are well known. This library uses voltage control mode by default, though, because there seem to be cases when the driver is unable to calibrate the motor properties properly and that can cause the motor to overheat before the settings are adjusted. 463 | 464 | The datasheet explains how to make sure the driver performs the proper automatic tuning routine in order to use current control mode. 465 | 466 | Use enableAutomaticCurrentScaling() to switch to current control mode instead. 467 | 468 | 469 | ### Voltage Control Mode 470 | 471 | Use disableAutomaticCurrentScaling() to switch to voltage control mode and disable automatic tuning. 472 | 473 | When automatic current scaling is disabled, the driver operates in a feed forward velocity-controlled mode and will not react to a change of the supply voltage or to events like a motor stall, but it provides a very stable amplitude. 474 | 475 | When automatic tuning is disabled, the run current and hold current settings are not enforced by regulation but scale the PWM amplitude only. When automatic tuning is disabled, the PWM offset and PWM gradient values may need to be set manually in order to adjust the motor current to proper levels. 476 | 477 | 478 | ### Current Control Mode 479 | 480 | Use enableAutomaticCurrentScaling() to switch to current control mode and enable automatic tuning. 481 | 482 | Use enableAutomaticGradientAdaptation() when in current control mode to allow the driver to automatically adjust the pwm gradient value. 483 | 484 | When the driver is in current control mode it measures the current and uses that feedback to automatically adjust the voltage when the velocity, voltage supply, or load on the motor changes. In order to respond properly to the current feedback, the driver must perform a calibration routine, an automatic tuning procedure, to measure the motor properties. This allows high motor dynamics and supports powering down the motor to very low currents. 485 | 486 | Refer to the datasheet to see how to make the driver perform the automatic tuning procedure properly. 487 | 488 | 489 | ### PWM Offset 490 | 491 | The PWM offset relates the motor current to the motor voltage when the motor is at standstill. 492 | 493 | Use setPwmOffset(pwm\_amplitude) to change. pwm\_amplitude range: 0-255 494 | 495 | In voltage control mode, increase the PWM offset to increase the motor current. 496 | 497 | In current control mode, the pwm offset value is used for initialization only. The driver will calculate the pwm offset value automatically. 498 | 499 | 500 | ### PWM Gradient 501 | 502 | The PWM gradient adjusts the relationship between the motor current to the motor voltage to compensate for the velocity-dependent motor back-EMF. 503 | 504 | Use setPwmGradient(pwm\_amplitude) to change. pwm\_amplitude range: 0-255 505 | 506 | In voltage control mode, increase the PWM gradient to increase the motor current if it decreases too much when the motor increases velocity. 507 | 508 | In current control mode, the pwm gradient value is used for initialization only. The driver will calculate the pwm gradient value automatically. 509 | 510 | 511 | ### Run Current 512 | 513 | The run current is used to scale the spinning motor current. 514 | 515 | Use setRunCurrent(percent) to change. percent range: 0-100 516 | 517 | In voltage control mode, the run current scales the PWM amplitude, but the current setting is not measured and adjusted when changes to the operating conditions occur. Use the PWM offset, the PWM gradient, and the run current all three to adjust the motor current. 518 | 519 | In current control mode, setting the run current is the way to adjust the spinning motor current. The driver will measure the current and automatically adjust the voltage to maintain the run current, even with the operating conditions change. The PWM offset and the PWM gradient may be changed to help the automatic tuning procedure, but changing the run current alone is enough to adjust the motor current since the driver will adjust the offset and gradient automatically. 520 | 521 | 522 | ### Standstill Mode 523 | 524 | The standstill mode determines how the motor will behave when the driver is commanded to be at zero velocity. 525 | 526 | Use setStandstillMode(mode) to change. mode values: NORMAL, FREEWHEELING, STRONG\_BRAKING, BRAKING 527 | 528 | 1. NORMAL 529 | 530 | In NORMAL mode, the driver actively holds the motor still using the hold current setting to scale the motor current. 531 | 532 | 2. FREEWHEELING 533 | 534 | In FREEWHEELING mode, the motor is free to spin freely when the driver is set to zero velocity. 535 | 536 | 3. STRONG\_BRAKING and BRAKING 537 | 538 | When the mode is either BRAKING, or STRONG\_BRAKING, the motor coils will be shorted inside the driver so the motor will tend to stay in one place even though current is not actively being driven into the coils. 539 | 540 | 541 | ### Hold Current 542 | 543 | The hold current is used to scale the standstill motor current, based on the standstill mode and the hold delay settings. 544 | 545 | Use setHoldCurrent(percent) to change. percent range: 0-100 546 | 547 | In voltage control mode, the hold current scales the PWM amplitude, but the current setting is not measured and adjusted when changes to the operating conditions occur. Use the PWM offset and the hold current both to adjust the motor current. 548 | 549 | In current control mode, setting the hold current is the way to adjust the stationary motor current. The driver will measure the current and automatically adjust the voltage to maintain the hold current, even with the operating conditions change. The PWM offset may be changed to help the automatic tuning procedure, but changing the hold current alone is enough to adjust the motor current since the driver will adjust the offset automatically. 550 | 551 | 552 | 553 | 554 | # Examples 555 | 556 | 557 | ## Wiring 558 | 559 | 560 | ### Teensy 4.0 561 | 562 | 563 | 564 | 565 | ### Mega 2560 566 | 567 | 568 | 569 | 570 | ### Uno 571 | 572 | 573 | 574 | 575 | ### Wiring Documentation Source 576 | 577 | 578 | 579 | 580 | 581 | 582 | # Hardware Documentation 583 | 584 | 585 | ## Datasheets 586 | 587 | [Datasheets](./datasheet) 588 | 589 | 590 | ## TMC2209 Stepper Driver Integrated Circuit 591 | 592 | [Trinamic TMC2209-LA Web Page](https://www.trinamic.com/products/integrated-circuits/details/tmc2209-la) 593 | 594 | 595 | ## TMC429 Stepper Controller Integrated Circuit 596 | 597 | [Trinamic TMC429 Web Page](https://www.trinamic.com/products/integrated-circuits/details/tmc429/) 598 | 599 | 600 | ## SilentStepStick Stepper Driver Board 601 | 602 | [Trinamic TMC2209 SilentStepStick Web Page](https://www.trinamic.com/support/eval-kits/details/silentstepstick) 603 | 604 | 605 | ## BIGTREETECH TMC2209 V1.2 UART Stepper Motor Driver 606 | 607 | [BIGTREETECH TMC2209 Web Page](https://www.biqu.equipment/products/bigtreetech-tmc2209-stepper-motor-driver-for-3d-printer-board-vs-tmc2208) 608 | 609 | 610 | ## Janelia Stepper Driver 611 | 612 | [Janelia Stepper Driver Web Page](https://github.com/janelia-kicad/stepper_driver) 613 | 614 | 615 | 616 | 617 | # Host Computer Setup 618 | 619 | 620 | ## Download this repository 621 | 622 | 623 | 624 | ```sh 625 | git clone https://github.com/janelia-arduino/TMC2209.git 626 | ``` 627 | 628 | 629 | ## PlatformIO 630 | 631 | 632 | ### Install PlatformIO Core 633 | 634 | 635 | 636 | ```sh 637 | python3 -m venv .venv 638 | source .venv/bin/activate 639 | pip install platformio 640 | pio --version 641 | ``` 642 | 643 | 644 | ### 99-platformio-udev.rules 645 | 646 | Linux users have to install udev rules for PlatformIO supported boards/devices. 647 | 648 | 1. Download udev rules file to /etc/udev/rules.d 649 | 650 | ```sh 651 | curl -fsSL https://raw.githubusercontent.com/platformio/platformio-core/develop/platformio/assets/system/99-platformio-udev.rules | sudo tee /etc/udev/rules.d/99-platformio-udev.rules 652 | ``` 653 | 654 | 2. Restart udev management tool 655 | 656 | ```sh 657 | sudo service udev restart 658 | ``` 659 | 660 | 3. Add user to groups 661 | 662 | ```sh 663 | sudo usermod -a -G dialout $USER && sudo usermod -a -G plugdev $USER 664 | ``` 665 | 666 | 4. Remove modemmanager 667 | 668 | ```sh 669 | sudo apt-get purge --auto-remove modemmanager 670 | ``` 671 | 672 | 5. After setting up rules and groups 673 | 674 | You will need to log out and log back in again (or reboot) for the user group changes to take effect. 675 | 676 | After this file is installed, physically unplug and reconnect your board. 677 | 678 | 679 | ### Compile the firmware 680 | 681 | 1. Gnu/Linux 682 | 683 | ```sh 684 | make teensy-firmware 685 | make mega-firmware 686 | make uno-firmware 687 | ``` 688 | 689 | 2. Other 690 | 691 | ```sh 692 | pio run -e teensy40 693 | pio run -e mega 694 | pio run -e uno 695 | ``` 696 | 697 | 698 | ### Upload the firmware 699 | 700 | 1. Gnu/Linux 701 | 702 | ```sh 703 | make teensy-upload 704 | make mega-upload 705 | make uno-upload 706 | ``` 707 | 708 | 2. Other 709 | 710 | ```sh 711 | pio run -e teensy40 -t upload 712 | pio run -e mega -t upload 713 | pio run -e uno -t upload 714 | ``` 715 | 716 | 717 | ### Serial Terminal Monitor 718 | 719 | 1. Gnu/Linux 720 | 721 | ```sh 722 | make monitor 723 | ``` 724 | 725 | 2. Other 726 | 727 | ```sh 728 | pio device monitor 729 | ``` 730 | -------------------------------------------------------------------------------- /datasheet/TMC2209_SilentStepStick_datasheet_Rev1.20.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/janelia-arduino/TMC2209/5c140f3ea0ab8425e8798c3384f2109133327d75/datasheet/TMC2209_SilentStepStick_datasheet_Rev1.20.pdf -------------------------------------------------------------------------------- /datasheet/TMC2209_datasheet_rev1.09.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/janelia-arduino/TMC2209/5c140f3ea0ab8425e8798c3384f2109133327d75/datasheet/TMC2209_datasheet_rev1.09.pdf -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/CoolStep/CoolStep.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 500; 13 | const int32_t VELOCITY = 20000; 14 | // current values may need to be reduced to prevent overheating depending on 15 | // specific motor and power supply voltage 16 | const uint8_t RUN_CURRENT_PERCENT = 100; 17 | const uint8_t LOOPS_BEFORE_TOGGLING = 3; 18 | const TMC2209::CurrentIncrement CURRENT_INCREMENT = TMC2209::CURRENT_INCREMENT_8; 19 | const TMC2209::MeasurementCount MEASUREMENT_COUNT = TMC2209::MEASUREMENT_COUNT_1; 20 | const uint32_t COOL_STEP_DURATION_THRESHOLD = 2000; 21 | const uint8_t COOL_STEP_LOWER_THRESHOLD = 1; 22 | const uint8_t COOL_STEP_UPPER_THRESHOLD = 0; 23 | 24 | uint8_t loop_count = 0; 25 | bool cool_step_enabled = false; 26 | 27 | 28 | // Instantiate TMC2209 29 | TMC2209 stepper_driver; 30 | 31 | 32 | void setup() 33 | { 34 | Serial.begin(SERIAL_BAUD_RATE); 35 | 36 | stepper_driver.setup(serial_stream); 37 | 38 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 39 | stepper_driver.setCoolStepCurrentIncrement(CURRENT_INCREMENT); 40 | stepper_driver.setCoolStepMeasurementCount(MEASUREMENT_COUNT); 41 | stepper_driver.setCoolStepDurationThreshold(COOL_STEP_DURATION_THRESHOLD); 42 | stepper_driver.enable(); 43 | stepper_driver.moveAtVelocity(VELOCITY); 44 | } 45 | 46 | void loop() 47 | { 48 | if (not stepper_driver.isSetupAndCommunicating()) 49 | { 50 | Serial.println("Stepper driver not setup and communicating!"); 51 | return; 52 | } 53 | 54 | if (cool_step_enabled) 55 | { 56 | Serial.println("cool step enabled"); 57 | } 58 | else 59 | { 60 | Serial.println("cool step disabled"); 61 | } 62 | 63 | uint32_t interstep_duration = stepper_driver.getInterstepDuration(); 64 | Serial.print("interstep_duration = "); 65 | Serial.println(interstep_duration); 66 | delay(DELAY); 67 | 68 | uint16_t stall_guard_result = stepper_driver.getStallGuardResult(); 69 | Serial.print("stall_guard_result = "); 70 | Serial.println(stall_guard_result); 71 | delay(DELAY); 72 | 73 | uint8_t pwm_scale_sum = stepper_driver.getPwmScaleSum(); 74 | Serial.print("pwm_scale_sum = "); 75 | Serial.println(pwm_scale_sum); 76 | delay(DELAY); 77 | 78 | int16_t pwm_scale_auto = stepper_driver.getPwmScaleAuto(); 79 | Serial.print("pwm_scale_auto = "); 80 | Serial.println(pwm_scale_auto); 81 | delay(DELAY); 82 | 83 | uint8_t pwm_offset_auto = stepper_driver.getPwmOffsetAuto(); 84 | Serial.print("pwm_offset_auto = "); 85 | Serial.println(pwm_offset_auto); 86 | delay(DELAY); 87 | 88 | uint8_t pwm_gradient_auto = stepper_driver.getPwmGradientAuto(); 89 | Serial.print("pwm_gradient_auto = "); 90 | Serial.println(pwm_gradient_auto); 91 | delay(DELAY); 92 | 93 | TMC2209::Status status = stepper_driver.getStatus(); 94 | Serial.print("status.current_scaling = "); 95 | Serial.println(status.current_scaling); 96 | 97 | TMC2209::Settings settings = stepper_driver.getSettings(); 98 | Serial.print("settings.irun_register_value = "); 99 | Serial.println(settings.irun_register_value); 100 | 101 | Serial.println(); 102 | 103 | if (++loop_count == LOOPS_BEFORE_TOGGLING) 104 | { 105 | loop_count = 0; 106 | cool_step_enabled = not cool_step_enabled; 107 | if (cool_step_enabled) 108 | { 109 | stepper_driver.enableCoolStep(COOL_STEP_LOWER_THRESHOLD, 110 | COOL_STEP_UPPER_THRESHOLD); 111 | } 112 | else 113 | { 114 | stepper_driver.disableCoolStep(); 115 | } 116 | } 117 | } 118 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/HoldCurrent/HoldCurrent.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 2000; 13 | const int32_t VELOCITY = 10000; 14 | const int32_t VELOCITY_STOPPED = 0; 15 | const uint8_t PERCENT_MIN = 0; 16 | const uint8_t PERCENT_MAX = 100; 17 | const uint8_t PERCENT_INC = 10; 18 | // current values may need to be reduced to prevent overheating depending on 19 | // specific motor and power supply voltage 20 | const uint8_t RUN_CURRENT_PERCENT = 100; 21 | 22 | uint8_t hold_current_percent = PERCENT_INC; 23 | 24 | // Instantiate TMC2209 25 | TMC2209 stepper_driver; 26 | 27 | 28 | void setup() 29 | { 30 | Serial.begin(SERIAL_BAUD_RATE); 31 | 32 | stepper_driver.setup(serial_stream); 33 | 34 | stepper_driver.enable(); 35 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 36 | } 37 | 38 | void loop() 39 | { 40 | if (not stepper_driver.isSetupAndCommunicating()) 41 | { 42 | Serial.println("Stepper driver not setup and communicating!"); 43 | return; 44 | } 45 | 46 | Serial.println("enable and run"); 47 | stepper_driver.enable(); 48 | stepper_driver.moveAtVelocity(VELOCITY); 49 | 50 | Serial.print("setHoldCurrent("); 51 | Serial.print(hold_current_percent); 52 | Serial.println(")"); 53 | stepper_driver.setHoldCurrent(hold_current_percent); 54 | delay(DELAY); 55 | 56 | Serial.println("stop"); 57 | stepper_driver.moveAtVelocity(VELOCITY_STOPPED); 58 | delay(DELAY); 59 | 60 | uint8_t pwm_scale_sum = stepper_driver.getPwmScaleSum(); 61 | Serial.print("pwm_scale_sum = "); 62 | Serial.println(pwm_scale_sum); 63 | delay(DELAY); 64 | 65 | stepper_driver.disable(); 66 | Serial.println("disable"); 67 | Serial.println(); 68 | delay(DELAY); 69 | 70 | if (hold_current_percent == PERCENT_MAX) 71 | { 72 | hold_current_percent = PERCENT_MIN; 73 | } 74 | hold_current_percent += PERCENT_INC; 75 | } 76 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/MicrostepsPerStep/MicrostepsPerStep.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 4000; 13 | const int32_t VELOCITY = 200; 14 | // current values may need to be reduced to prevent overheating depending on 15 | // specific motor and power supply voltage 16 | const uint8_t RUN_CURRENT_PERCENT = 100; 17 | const uint8_t MICROSTEPS_PER_STEP_EXPONENT_MIN = 0; 18 | const uint8_t MICROSTEPS_PER_STEP_EXPONENT_MAX = 8; 19 | const uint8_t MICROSTEPS_PER_STEP_EXPONENT_INC = 1; 20 | 21 | uint8_t microsteps_per_step_exponent = MICROSTEPS_PER_STEP_EXPONENT_MIN; 22 | 23 | 24 | // Instantiate TMC2209 25 | TMC2209 stepper_driver; 26 | 27 | 28 | void setup() 29 | { 30 | Serial.begin(SERIAL_BAUD_RATE); 31 | 32 | stepper_driver.setup(serial_stream); 33 | 34 | stepper_driver.setMicrostepsPerStepPowerOfTwo(microsteps_per_step_exponent); 35 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 36 | stepper_driver.enable(); 37 | stepper_driver.moveAtVelocity(VELOCITY); 38 | } 39 | 40 | void loop() 41 | { 42 | if (not stepper_driver.isSetupAndCommunicating()) 43 | { 44 | Serial.println("Stepper driver not setup and communicating!"); 45 | return; 46 | } 47 | 48 | Serial.print("setMicrostepsPerStepPowerOfTwo("); 49 | Serial.print(microsteps_per_step_exponent); 50 | Serial.println(")"); 51 | stepper_driver.setMicrostepsPerStepPowerOfTwo(microsteps_per_step_exponent); 52 | Serial.print("getMicrostepsPerStep() = "); 53 | Serial.println(stepper_driver.getMicrostepsPerStep()); 54 | delay(DELAY); 55 | 56 | uint32_t interstep_duration = stepper_driver.getInterstepDuration(); 57 | Serial.print("interstep_duration = "); 58 | Serial.println(interstep_duration); 59 | Serial.println(); 60 | 61 | microsteps_per_step_exponent += MICROSTEPS_PER_STEP_EXPONENT_INC; 62 | if (microsteps_per_step_exponent > MICROSTEPS_PER_STEP_EXPONENT_MAX) 63 | { 64 | microsteps_per_step_exponent = MICROSTEPS_PER_STEP_EXPONENT_MIN; 65 | } 66 | } 67 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/MoveAtVelocity/MoveAtVelocity.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 2000; 13 | const int32_t VELOCITY = 20000; 14 | // current values may need to be reduced to prevent overheating depending on 15 | // specific motor and power supply voltage 16 | const uint8_t RUN_CURRENT_PERCENT = 100; 17 | 18 | 19 | // Instantiate TMC2209 20 | TMC2209 stepper_driver; 21 | 22 | 23 | void setup() 24 | { 25 | Serial.begin(SERIAL_BAUD_RATE); 26 | 27 | stepper_driver.setup(serial_stream); 28 | delay(DELAY); 29 | 30 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 31 | stepper_driver.enableCoolStep(); 32 | stepper_driver.enable(); 33 | stepper_driver.moveAtVelocity(VELOCITY); 34 | } 35 | 36 | void loop() 37 | { 38 | if (not stepper_driver.isSetupAndCommunicating()) 39 | { 40 | Serial.println("Stepper driver not setup and communicating!"); 41 | return; 42 | } 43 | 44 | bool hardware_disabled = stepper_driver.hardwareDisabled(); 45 | TMC2209::Settings settings = stepper_driver.getSettings(); 46 | TMC2209::Status status = stepper_driver.getStatus(); 47 | 48 | if (hardware_disabled) 49 | { 50 | Serial.println("Stepper driver is hardware disabled!"); 51 | } 52 | else if (not settings.software_enabled) 53 | { 54 | Serial.println("Stepper driver is software disabled!"); 55 | } 56 | else if ((not status.standstill)) 57 | { 58 | Serial.print("Moving at velocity "); 59 | Serial.println(VELOCITY); 60 | 61 | uint32_t interstep_duration = stepper_driver.getInterstepDuration(); 62 | Serial.print("which is equal to an interstep_duration of "); 63 | Serial.println(interstep_duration); 64 | } 65 | else 66 | { 67 | Serial.println("Not moving, something is wrong!"); 68 | } 69 | 70 | Serial.println(); 71 | delay(DELAY); 72 | } 73 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/ReplyDelay/ReplyDelay.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 3000; 13 | const uint8_t REPEAT_COUNT_MAX = 2; 14 | 15 | // Instantiate TMC2209 16 | TMC2209 stepper_driver; 17 | 18 | uint8_t reply_delay; 19 | uint8_t repeat_count; 20 | 21 | 22 | void setup() 23 | { 24 | Serial.begin(SERIAL_BAUD_RATE); 25 | 26 | stepper_driver.setup(serial_stream); 27 | 28 | reply_delay = 0; 29 | stepper_driver.setReplyDelay(reply_delay); 30 | 31 | repeat_count = 0; 32 | } 33 | 34 | void loop() 35 | { 36 | if (stepper_driver.isSetupAndCommunicating()) 37 | { 38 | Serial.println("Stepper driver is setup and communicating!"); 39 | } 40 | else 41 | { 42 | Serial.println("Stepper driver is not communicating!"); 43 | } 44 | Serial.print("repeat count "); 45 | Serial.print(repeat_count); 46 | Serial.print(" out of "); 47 | Serial.println(REPEAT_COUNT_MAX); 48 | Serial.print("reply delay = "); 49 | Serial.println(reply_delay); 50 | Serial.println(); 51 | delay(DELAY); 52 | 53 | if (++repeat_count >= REPEAT_COUNT_MAX) 54 | { 55 | repeat_count = 0; 56 | if (++reply_delay >= stepper_driver.REPLY_DELAY_MAX) 57 | { 58 | reply_delay = 0; 59 | } 60 | stepper_driver.setReplyDelay(reply_delay); 61 | } 62 | } 63 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/RunCurrent/RunCurrent.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | // Identify which microcontroller serial port is connected to the TMC2209 10 | // e.g. Serial1, Serial2... 11 | HardwareSerial & serial_stream = Serial3; 12 | 13 | const long SERIAL_BAUD_RATE = 115200; 14 | const int DELAY = 2000; 15 | const int32_t VELOCITY = 10000; 16 | const uint8_t PERCENT_MIN = 0; 17 | // current values may need to be reduced to prevent overheating depending on 18 | // specific motor and power supply voltage 19 | const uint8_t PERCENT_MAX = 100; 20 | const uint8_t PERCENT_INC = 10; 21 | 22 | uint8_t run_current_percent = PERCENT_INC; 23 | 24 | 25 | // Instantiate TMC2209 26 | TMC2209 stepper_driver; 27 | 28 | 29 | void setup() 30 | { 31 | Serial.begin(SERIAL_BAUD_RATE); 32 | 33 | stepper_driver.setup(serial_stream); 34 | 35 | stepper_driver.enable(); 36 | stepper_driver.moveAtVelocity(VELOCITY); 37 | } 38 | 39 | void loop() 40 | { 41 | if (not stepper_driver.isSetupAndCommunicating()) 42 | { 43 | Serial.println("Stepper driver not setup and communicating!"); 44 | return; 45 | } 46 | 47 | Serial.print("setRunCurrent("); 48 | Serial.print(run_current_percent); 49 | Serial.println(")"); 50 | stepper_driver.setRunCurrent(run_current_percent); 51 | delay(DELAY); 52 | 53 | TMC2209::Status status = stepper_driver.getStatus(); 54 | Serial.print("status.current_scaling = "); 55 | Serial.println(status.current_scaling); 56 | Serial.println(); 57 | 58 | if (run_current_percent == PERCENT_MAX) 59 | { 60 | run_current_percent = PERCENT_MIN; 61 | } 62 | run_current_percent += PERCENT_INC; 63 | } 64 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/SettingsAndStatus/SettingsAndStatus.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 2000; 13 | 14 | // Instantiate TMC2209 15 | TMC2209 stepper_driver; 16 | 17 | 18 | void setup() 19 | { 20 | Serial.begin(SERIAL_BAUD_RATE); 21 | 22 | stepper_driver.setup(serial_stream); 23 | } 24 | 25 | void loop() 26 | { 27 | Serial.println("*************************"); 28 | Serial.println("getSettings()"); 29 | TMC2209::Settings settings = stepper_driver.getSettings(); 30 | Serial.print("settings.is_communicating = "); 31 | Serial.println(settings.is_communicating); 32 | Serial.print("settings.is_setup = "); 33 | Serial.println(settings.is_setup); 34 | Serial.print("settings.software_enabled = "); 35 | Serial.println(settings.software_enabled); 36 | Serial.print("settings.microsteps_per_step = "); 37 | Serial.println(settings.microsteps_per_step); 38 | Serial.print("settings.inverse_motor_direction_enabled = "); 39 | Serial.println(settings.inverse_motor_direction_enabled); 40 | Serial.print("settings.stealth_chop_enabled = "); 41 | Serial.println(settings.stealth_chop_enabled); 42 | Serial.print("settings.standstill_mode = "); 43 | switch (settings.standstill_mode) 44 | { 45 | case TMC2209::NORMAL: 46 | Serial.println("normal"); 47 | break; 48 | case TMC2209::FREEWHEELING: 49 | Serial.println("freewheeling"); 50 | break; 51 | case TMC2209::STRONG_BRAKING: 52 | Serial.println("strong_braking"); 53 | break; 54 | case TMC2209::BRAKING: 55 | Serial.println("braking"); 56 | break; 57 | } 58 | Serial.print("settings.irun_percent = "); 59 | Serial.println(settings.irun_percent); 60 | Serial.print("settings.irun_register_value = "); 61 | Serial.println(settings.irun_register_value); 62 | Serial.print("settings.ihold_percent = "); 63 | Serial.println(settings.ihold_percent); 64 | Serial.print("settings.ihold_register_value = "); 65 | Serial.println(settings.ihold_register_value); 66 | Serial.print("settings.iholddelay_percent = "); 67 | Serial.println(settings.iholddelay_percent); 68 | Serial.print("settings.iholddelay_register_value = "); 69 | Serial.println(settings.iholddelay_register_value); 70 | Serial.print("settings.automatic_current_scaling_enabled = "); 71 | Serial.println(settings.automatic_current_scaling_enabled); 72 | Serial.print("settings.automatic_gradient_adaptation_enabled = "); 73 | Serial.println(settings.automatic_gradient_adaptation_enabled); 74 | Serial.print("settings.pwm_offset = "); 75 | Serial.println(settings.pwm_offset); 76 | Serial.print("settings.pwm_gradient = "); 77 | Serial.println(settings.pwm_gradient); 78 | Serial.print("settings.cool_step_enabled = "); 79 | Serial.println(settings.cool_step_enabled); 80 | Serial.print("settings.analog_current_scaling_enabled = "); 81 | Serial.println(settings.analog_current_scaling_enabled); 82 | Serial.print("settings.internal_sense_resistors_enabled = "); 83 | Serial.println(settings.internal_sense_resistors_enabled); 84 | Serial.println("*************************"); 85 | Serial.println(); 86 | 87 | Serial.println("*************************"); 88 | Serial.println("hardwareDisabled()"); 89 | bool hardware_disabled = stepper_driver.hardwareDisabled(); 90 | Serial.print("hardware_disabled = "); 91 | Serial.println(hardware_disabled); 92 | Serial.println("*************************"); 93 | Serial.println(); 94 | 95 | Serial.println("*************************"); 96 | Serial.println("getStatus()"); 97 | TMC2209::Status status = stepper_driver.getStatus(); 98 | Serial.print("status.over_temperature_warning = "); 99 | Serial.println(status.over_temperature_warning); 100 | Serial.print("status.over_temperature_shutdown = "); 101 | Serial.println(status.over_temperature_shutdown); 102 | Serial.print("status.short_to_ground_a = "); 103 | Serial.println(status.short_to_ground_a); 104 | Serial.print("status.short_to_ground_b = "); 105 | Serial.println(status.short_to_ground_b); 106 | Serial.print("status.low_side_short_a = "); 107 | Serial.println(status.low_side_short_a); 108 | Serial.print("status.low_side_short_b = "); 109 | Serial.println(status.low_side_short_b); 110 | Serial.print("status.open_load_a = "); 111 | Serial.println(status.open_load_a); 112 | Serial.print("status.open_load_b = "); 113 | Serial.println(status.open_load_b); 114 | Serial.print("status.over_temperature_120c = "); 115 | Serial.println(status.over_temperature_120c); 116 | Serial.print("status.over_temperature_143c = "); 117 | Serial.println(status.over_temperature_143c); 118 | Serial.print("status.over_temperature_150c = "); 119 | Serial.println(status.over_temperature_150c); 120 | Serial.print("status.over_temperature_157c = "); 121 | Serial.println(status.over_temperature_157c); 122 | Serial.print("status.current_scaling = "); 123 | Serial.println(status.current_scaling); 124 | Serial.print("status.stealth_chop_mode = "); 125 | Serial.println(status.stealth_chop_mode); 126 | Serial.print("status.standstill = "); 127 | Serial.println(status.standstill); 128 | Serial.println("*************************"); 129 | Serial.println(); 130 | 131 | Serial.println(); 132 | delay(DELAY); 133 | } 134 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/StallGuard/StallGuard.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 200; 13 | // current values may need to be reduced to prevent overheating depending on 14 | // specific motor and power supply voltage 15 | const uint8_t RUN_CURRENT_PERCENT = 100; 16 | const int32_t VELOCITY = 20000; 17 | const uint8_t STALL_GUARD_THRESHOLD = 50; 18 | 19 | 20 | // Instantiate TMC2209 21 | TMC2209 stepper_driver; 22 | 23 | 24 | void setup() 25 | { 26 | Serial.begin(SERIAL_BAUD_RATE); 27 | 28 | stepper_driver.setup(serial_stream); 29 | 30 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 31 | stepper_driver.setStallGuardThreshold(STALL_GUARD_THRESHOLD); 32 | stepper_driver.enable(); 33 | stepper_driver.moveAtVelocity(VELOCITY); 34 | } 35 | 36 | void loop() 37 | { 38 | if (not stepper_driver.isSetupAndCommunicating()) 39 | { 40 | Serial.println("Stepper driver not setup and communicating!"); 41 | return; 42 | } 43 | 44 | Serial.print("run_current_percent = "); 45 | Serial.println(RUN_CURRENT_PERCENT); 46 | 47 | Serial.print("stall_guard_threshold = "); 48 | Serial.println(STALL_GUARD_THRESHOLD); 49 | 50 | uint16_t stall_guard_result = stepper_driver.getStallGuardResult(); 51 | Serial.print("stall_guard_result = "); 52 | Serial.println(stall_guard_result); 53 | 54 | Serial.println(); 55 | delay(DELAY); 56 | 57 | } 58 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/TestBaudRate/TestBaudRate.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const long SERIAL1_BAUD_RATE_COUNT = 10; 13 | const long SERIAL1_BAUD_RATES[SERIAL1_BAUD_RATE_COUNT] = 14 | { 15 | 500000, 16 | 250000, 17 | 115200, 18 | 57600, 19 | 38400, 20 | 31250, 21 | 28800, 22 | 19200, 23 | 14400, 24 | 9600 25 | }; 26 | const uint8_t SUCCESSIVE_OPERATION_COUNT = 3; 27 | const int DELAY = 2000; 28 | 29 | // Instantiate TMC2209 30 | TMC2209 stepper_driver; 31 | uint8_t serial1_baud_rate_index = 0; 32 | 33 | 34 | void setup() 35 | { 36 | Serial.begin(SERIAL_BAUD_RATE); 37 | } 38 | 39 | void loop() 40 | { 41 | long serial1_baud_rate = SERIAL1_BAUD_RATES[serial1_baud_rate_index++]; 42 | stepper_driver.setup(serial_stream,serial1_baud_rate); 43 | if (serial1_baud_rate_index == SERIAL1_BAUD_RATE_COUNT) 44 | { 45 | serial1_baud_rate_index = 0; 46 | } 47 | 48 | bool test_further = false; 49 | 50 | Serial.println("*************************"); 51 | Serial.print("serial1_baud_rate = "); 52 | Serial.println(serial1_baud_rate); 53 | 54 | if (stepper_driver.isSetupAndCommunicating()) 55 | { 56 | Serial.println("Stepper driver setup and communicating!"); 57 | test_further = true; 58 | } 59 | else 60 | { 61 | Serial.println("Stepper driver not setup and communicating!"); 62 | } 63 | 64 | if (test_further) 65 | { 66 | uint32_t microstep_sum = 0; 67 | for (uint8_t i=0; i 0) 72 | { 73 | Serial.println("Successive read test passed!"); 74 | } 75 | else 76 | { 77 | Serial.println("Successive read test failed!"); 78 | } 79 | uint8_t itc_begin = stepper_driver.getInterfaceTransmissionCounter(); 80 | for (uint8_t i=0; i 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 3000; 13 | 14 | // Instantiate TMC2209 15 | TMC2209 stepper_driver; 16 | 17 | 18 | void setup() 19 | { 20 | Serial.begin(SERIAL_BAUD_RATE); 21 | 22 | stepper_driver.setup(serial_stream); 23 | } 24 | 25 | void loop() 26 | { 27 | if (stepper_driver.isSetupAndCommunicating()) 28 | { 29 | Serial.println("Stepper driver is setup and communicating!"); 30 | Serial.println("Try turning driver power off to see what happens."); 31 | } 32 | else if (stepper_driver.isCommunicatingButNotSetup()) 33 | { 34 | Serial.println("Stepper driver is communicating but not setup!"); 35 | Serial.println("Running setup again..."); 36 | stepper_driver.setup(serial_stream); 37 | } 38 | else 39 | { 40 | Serial.println("Stepper driver is not communicating!"); 41 | Serial.println("Try turning driver power on to see what happens."); 42 | } 43 | Serial.println(); 44 | delay(DELAY); 45 | } 46 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/TestDisconnection/TestDisconnection.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial3; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 6000; 13 | 14 | const int LOOP_COUNT = 100; 15 | 16 | unsigned long time_begin; 17 | unsigned long time_end; 18 | TMC2209::Status status; 19 | 20 | typedef void (*DriverFunction)(void); 21 | 22 | // Instantiate TMC2209 23 | TMC2209 stepper_driver; 24 | 25 | void driverWriteFunction() 26 | { 27 | stepper_driver.enable(); 28 | } 29 | 30 | void driverReadFunction() 31 | { 32 | status = stepper_driver.getStatus(); 33 | } 34 | 35 | void runTestLoop(DriverFunction driver_function) 36 | { 37 | time_begin = millis(); 38 | for (uint16_t i=0; i 2 | 3 | // This example is meant to test multiple ways of using bidirectional UART on RP2040 4 | // 5 | // See this reference for more details: 6 | // https://arduino-pico.readthedocs.io/en/latest/serial.html 7 | 8 | const long SERIAL_BAUD_RATE = 115200; 9 | const int DELAY = 3000; 10 | const uint8_t SERIAL1_RX_PIN = 13; 11 | const uint8_t SERIAL1_TX_PIN = 12; 12 | const uint8_t SERIAL2_RX_PIN = 5; 13 | const uint8_t SERIAL2_TX_PIN = 4; 14 | const uint8_t SERIAL3_RX_PIN = 26; 15 | const uint8_t SERIAL3_TX_PIN = 27; 16 | 17 | SerialUART & serial_stream1 = Serial1; 18 | HardwareSerial & serial_stream2 = Serial2; 19 | SerialPIO Serial3(SERIAL3_TX_PIN, SERIAL3_RX_PIN); 20 | 21 | // Instantiate TMC2209 22 | TMC2209 stepper_driver1; 23 | TMC2209 stepper_driver2; 24 | TMC2209 stepper_driver3; 25 | 26 | 27 | void setup() 28 | { 29 | Serial.begin(SERIAL_BAUD_RATE); 30 | 31 | Serial2.setRX(SERIAL2_RX_PIN); 32 | Serial2.setTX(SERIAL2_TX_PIN); 33 | 34 | stepper_driver1.setup(serial_stream1, SERIAL_BAUD_RATE, TMC2209::SERIAL_ADDRESS_0, SERIAL1_RX_PIN, SERIAL1_TX_PIN); 35 | stepper_driver2.setup(serial_stream2, SERIAL_BAUD_RATE); 36 | stepper_driver3.setup(Serial3, SERIAL_BAUD_RATE); 37 | } 38 | 39 | void loop() 40 | { 41 | if (stepper_driver1.isSetupAndCommunicating()) 42 | { 43 | Serial.println("Stepper driver is setup and communicating!"); 44 | Serial.println("Try turning driver power off to see what happens."); 45 | } 46 | else if (stepper_driver1.isCommunicatingButNotSetup()) 47 | { 48 | Serial.println("Stepper driver is communicating but not setup!"); 49 | Serial.println("Running setup again..."); 50 | stepper_driver1.setup(serial_stream1); 51 | } 52 | else 53 | { 54 | Serial.println("Stepper driver is not communicating!"); 55 | Serial.println("Try turning driver power on to see what happens."); 56 | } 57 | Serial.println(); 58 | delay(DELAY); 59 | } 60 | -------------------------------------------------------------------------------- /examples/BidirectionalCommunication/TestUnoR4/TestUnoR4.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | UART & serial_stream = Serial1; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 3000; 13 | 14 | // Instantiate TMC2209 15 | TMC2209 stepper_driver; 16 | 17 | 18 | void setup() 19 | { 20 | Serial.begin(SERIAL_BAUD_RATE); 21 | 22 | stepper_driver.setup(serial_stream); 23 | } 24 | 25 | void loop() 26 | { 27 | if (stepper_driver.isSetupAndCommunicating()) 28 | { 29 | Serial.println("Stepper driver is setup and communicating!"); 30 | Serial.println("Try turning driver power off to see what happens."); 31 | } 32 | else if (stepper_driver.isCommunicatingButNotSetup()) 33 | { 34 | Serial.println("Stepper driver is communicating but not setup!"); 35 | Serial.println("Running setup again..."); 36 | stepper_driver.setup(serial_stream); 37 | } 38 | else 39 | { 40 | Serial.println("Stepper driver is not communicating!"); 41 | Serial.println("Try turning driver power on to see what happens."); 42 | } 43 | Serial.println(); 44 | delay(DELAY); 45 | } 46 | -------------------------------------------------------------------------------- /examples/ESPIDFExample/.gitignore: -------------------------------------------------------------------------------- 1 | /build 2 | /.vscode 3 | /managed_components 4 | /sdkconfig 5 | /dependencies.lock 6 | -------------------------------------------------------------------------------- /examples/ESPIDFExample/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | # For more information about build system see 2 | # https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html 3 | # The following five lines of boilerplate have to be in your project's 4 | # CMakeLists in this exact order for cmake to work correctly 5 | 6 | cmake_minimum_required(VERSION 3.16) 7 | 8 | include($ENV{IDF_PATH}/tools/cmake/project.cmake) 9 | 10 | project(idf_project_example) 11 | -------------------------------------------------------------------------------- /examples/ESPIDFExample/README.md: -------------------------------------------------------------------------------- 1 | This folder contains a bare bones functional ESP-IDF project. 2 | 3 | You can create one using the **ESP-IDF: New Project** command in 4 | Visual Studio code, or use this one as a basis. If you do use this one 5 | as a basis for your own project, review the `.gitignore` file as it 6 | excludes files you would not want to exclude in a normal project. 7 | Normally only the `managed_components` and `build` folders would be 8 | excluded from version control. 9 | -------------------------------------------------------------------------------- /examples/ESPIDFExample/main/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | FILE(GLOB_RECURSE SOURCES ${CMAKE_CURRENT_SOURCE_DIR}/*.c ${CMAKE_CURRENT_SOURCE_DIR}/*.cpp) 2 | 3 | idf_component_register( 4 | SRCS ${SOURCES} 5 | INCLUDE_DIRS "." 6 | ) 7 | -------------------------------------------------------------------------------- /examples/ESPIDFExample/main/idf_component.yml: -------------------------------------------------------------------------------- 1 | dependencies: 2 | TMC2209: 3 | path: ../../.. 4 | # Alternatively you can point this directly at the GitHub repository: 5 | # git: https://github.com/janelia-arduino/TMC2209.git 6 | -------------------------------------------------------------------------------- /examples/ESPIDFExample/main/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | HardwareSerial & serial_stream = Serial1; 10 | 11 | const long SERIAL_BAUD_RATE = 115200; 12 | const int DELAY = 2000; 13 | 14 | // Instantiate TMC2209 15 | TMC2209 stepper_driver; 16 | 17 | extern "C" void app_main() 18 | { 19 | Serial.begin(SERIAL_BAUD_RATE); 20 | 21 | stepper_driver.setup(serial_stream); 22 | 23 | Serial.println("*************************"); 24 | Serial.println("getSettings()"); 25 | TMC2209::Settings settings = stepper_driver.getSettings(); 26 | Serial.print("settings.is_communicating = "); 27 | Serial.println(settings.is_communicating); 28 | Serial.print("settings.is_setup = "); 29 | Serial.println(settings.is_setup); 30 | Serial.print("settings.software_enabled = "); 31 | Serial.println(settings.software_enabled); 32 | Serial.print("settings.microsteps_per_step = "); 33 | Serial.println(settings.microsteps_per_step); 34 | Serial.print("settings.inverse_motor_direction_enabled = "); 35 | Serial.println(settings.inverse_motor_direction_enabled); 36 | Serial.print("settings.stealth_chop_enabled = "); 37 | Serial.println(settings.stealth_chop_enabled); 38 | Serial.print("settings.standstill_mode = "); 39 | switch (settings.standstill_mode) 40 | { 41 | case TMC2209::NORMAL: 42 | Serial.println("normal"); 43 | break; 44 | case TMC2209::FREEWHEELING: 45 | Serial.println("freewheeling"); 46 | break; 47 | case TMC2209::STRONG_BRAKING: 48 | Serial.println("strong_braking"); 49 | break; 50 | case TMC2209::BRAKING: 51 | Serial.println("braking"); 52 | break; 53 | } 54 | Serial.print("settings.irun_percent = "); 55 | Serial.println(settings.irun_percent); 56 | Serial.print("settings.irun_register_value = "); 57 | Serial.println(settings.irun_register_value); 58 | Serial.print("settings.ihold_percent = "); 59 | Serial.println(settings.ihold_percent); 60 | Serial.print("settings.ihold_register_value = "); 61 | Serial.println(settings.ihold_register_value); 62 | Serial.print("settings.iholddelay_percent = "); 63 | Serial.println(settings.iholddelay_percent); 64 | Serial.print("settings.iholddelay_register_value = "); 65 | Serial.println(settings.iholddelay_register_value); 66 | Serial.print("settings.automatic_current_scaling_enabled = "); 67 | Serial.println(settings.automatic_current_scaling_enabled); 68 | Serial.print("settings.automatic_gradient_adaptation_enabled = "); 69 | Serial.println(settings.automatic_gradient_adaptation_enabled); 70 | Serial.print("settings.pwm_offset = "); 71 | Serial.println(settings.pwm_offset); 72 | Serial.print("settings.pwm_gradient = "); 73 | Serial.println(settings.pwm_gradient); 74 | Serial.print("settings.cool_step_enabled = "); 75 | Serial.println(settings.cool_step_enabled); 76 | Serial.print("settings.analog_current_scaling_enabled = "); 77 | Serial.println(settings.analog_current_scaling_enabled); 78 | Serial.print("settings.internal_sense_resistors_enabled = "); 79 | Serial.println(settings.internal_sense_resistors_enabled); 80 | Serial.println("*************************"); 81 | Serial.println(); 82 | 83 | Serial.println("*************************"); 84 | Serial.println("hardwareDisabled()"); 85 | bool hardware_disabled = stepper_driver.hardwareDisabled(); 86 | Serial.print("hardware_disabled = "); 87 | Serial.println(hardware_disabled); 88 | Serial.println("*************************"); 89 | Serial.println(); 90 | 91 | Serial.println("*************************"); 92 | Serial.println("getStatus()"); 93 | TMC2209::Status status = stepper_driver.getStatus(); 94 | Serial.print("status.over_temperature_warning = "); 95 | Serial.println(status.over_temperature_warning); 96 | Serial.print("status.over_temperature_shutdown = "); 97 | Serial.println(status.over_temperature_shutdown); 98 | Serial.print("status.short_to_ground_a = "); 99 | Serial.println(status.short_to_ground_a); 100 | Serial.print("status.short_to_ground_b = "); 101 | Serial.println(status.short_to_ground_b); 102 | Serial.print("status.low_side_short_a = "); 103 | Serial.println(status.low_side_short_a); 104 | Serial.print("status.low_side_short_b = "); 105 | Serial.println(status.low_side_short_b); 106 | Serial.print("status.open_load_a = "); 107 | Serial.println(status.open_load_a); 108 | Serial.print("status.open_load_b = "); 109 | Serial.println(status.open_load_b); 110 | Serial.print("status.over_temperature_120c = "); 111 | Serial.println(status.over_temperature_120c); 112 | Serial.print("status.over_temperature_143c = "); 113 | Serial.println(status.over_temperature_143c); 114 | Serial.print("status.over_temperature_150c = "); 115 | Serial.println(status.over_temperature_150c); 116 | Serial.print("status.over_temperature_157c = "); 117 | Serial.println(status.over_temperature_157c); 118 | Serial.print("status.current_scaling = "); 119 | Serial.println(status.current_scaling); 120 | Serial.print("status.stealth_chop_mode = "); 121 | Serial.println(status.stealth_chop_mode); 122 | Serial.print("status.standstill = "); 123 | Serial.println(status.standstill); 124 | Serial.println("*************************"); 125 | Serial.println(); 126 | 127 | Serial.println(); 128 | delay(DELAY); 129 | } 130 | -------------------------------------------------------------------------------- /examples/ESPIDFExample/sdkconfig.defaults: -------------------------------------------------------------------------------- 1 | # Required by the android-esp32 component. 2 | CONFIG_FREERTOS_HZ=1000 3 | -------------------------------------------------------------------------------- /examples/UnidirectionalCommunication/HardwareEnable/HardwareEnable.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | // 9 | // To make this library work with those boards, refer to this library example: 10 | // examples/UnidirectionalCommunication/SoftwareSerial 11 | 12 | HardwareSerial & serial_stream = Serial3; 13 | const uint8_t HARDWARE_ENABLE_PIN = 4; 14 | 15 | const int32_t RUN_VELOCITY = 20000; 16 | const int32_t STOP_VELOCITY = 0; 17 | const int RUN_DURATION = 2000; 18 | const int STOP_DURATION = 1000; 19 | const int RUN_COUNT = 4; 20 | // current values may need to be reduced to prevent overheating depending on 21 | // specific motor and power supply voltage 22 | const uint8_t RUN_CURRENT_PERCENT = 100; 23 | 24 | 25 | // Instantiate TMC2209 26 | TMC2209 stepper_driver; 27 | bool invert_direction = false; 28 | 29 | void setup() 30 | { 31 | stepper_driver.setup(serial_stream); 32 | 33 | stepper_driver.setHardwareEnablePin(HARDWARE_ENABLE_PIN); 34 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 35 | stepper_driver.enableCoolStep(); 36 | stepper_driver.enable(); 37 | } 38 | 39 | void loop() 40 | { 41 | stepper_driver.moveAtVelocity(STOP_VELOCITY); 42 | delay(STOP_DURATION); 43 | if (invert_direction) 44 | { 45 | stepper_driver.enableInverseMotorDirection(); 46 | } 47 | else 48 | { 49 | stepper_driver.disableInverseMotorDirection(); 50 | } 51 | invert_direction = not invert_direction; 52 | 53 | stepper_driver.moveAtVelocity(RUN_VELOCITY); 54 | 55 | for (uint8_t run=0; run 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | // 9 | // To make this library work with those boards, refer to this library example: 10 | // examples/UnidirectionalCommunication/SoftwareSerial 11 | 12 | HardwareSerial & serial_stream = Serial3; 13 | 14 | const int32_t RUN_VELOCITY = 20000; 15 | const int32_t STOP_VELOCITY = 0; 16 | const int RUN_DURATION = 2000; 17 | const int STOP_DURATION = 1000; 18 | // current values may need to be reduced to prevent overheating depending on 19 | // specific motor and power supply voltage 20 | const uint8_t RUN_CURRENT_PERCENT = 100; 21 | 22 | 23 | // Instantiate TMC2209 24 | TMC2209 stepper_driver; 25 | bool invert_direction = false; 26 | 27 | void setup() 28 | { 29 | stepper_driver.setup(serial_stream); 30 | 31 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 32 | stepper_driver.enableCoolStep(); 33 | stepper_driver.enable(); 34 | } 35 | 36 | void loop() 37 | { 38 | stepper_driver.moveAtVelocity(STOP_VELOCITY); 39 | delay(STOP_DURATION); 40 | if (invert_direction) 41 | { 42 | stepper_driver.enableInverseMotorDirection(); 43 | } 44 | else 45 | { 46 | stepper_driver.disableInverseMotorDirection(); 47 | } 48 | invert_direction = not invert_direction; 49 | 50 | stepper_driver.moveAtVelocity(RUN_VELOCITY); 51 | 52 | delay(RUN_DURATION); 53 | } 54 | -------------------------------------------------------------------------------- /examples/UnidirectionalCommunication/SoftwareSerial/SoftwareSerial.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // SoftwareSerial can be used on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | 9 | // Software serial ports should only be used for unidirectional communication 10 | // The RX pin does not need to be connected, but it must be specified when 11 | // creating an instance of a SoftwareSerial object 12 | const uint8_t RX_PIN = 15; 13 | const uint8_t TX_PIN = 14; 14 | SoftwareSerial soft_serial(RX_PIN, TX_PIN); 15 | 16 | const int32_t RUN_VELOCITY = 20000; 17 | const int32_t STOP_VELOCITY = 0; 18 | const int RUN_DURATION = 2000; 19 | const int STOP_DURATION = 1000; 20 | // current values may need to be reduced to prevent overheating depending on 21 | // specific motor and power supply voltage 22 | const uint8_t RUN_CURRENT_PERCENT = 100; 23 | 24 | 25 | // Instantiate TMC2209 26 | TMC2209 stepper_driver; 27 | bool invert_direction = false; 28 | 29 | void setup() 30 | { 31 | stepper_driver.setup(soft_serial); 32 | 33 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 34 | stepper_driver.enableCoolStep(); 35 | stepper_driver.enable(); 36 | } 37 | 38 | void loop() 39 | { 40 | stepper_driver.moveAtVelocity(STOP_VELOCITY); 41 | delay(STOP_DURATION); 42 | if (invert_direction) 43 | { 44 | stepper_driver.enableInverseMotorDirection(); 45 | } 46 | else 47 | { 48 | stepper_driver.disableInverseMotorDirection(); 49 | } 50 | invert_direction = not invert_direction; 51 | 52 | stepper_driver.moveAtVelocity(RUN_VELOCITY); 53 | 54 | delay(RUN_DURATION); 55 | } 56 | -------------------------------------------------------------------------------- /examples/UnidirectionalCommunication/Standstill/Standstill.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | // 9 | // To make this library work with those boards, refer to this library example: 10 | // examples/UnidirectionalCommunication/SoftwareSerial 11 | 12 | HardwareSerial & serial_stream = Serial3; 13 | 14 | const long SERIAL_BAUD_RATE = 115200; 15 | const int DELAY = 4000; 16 | // current values may need to be reduced to prevent overheating depending on 17 | // specific motor and power supply voltage 18 | const uint8_t RUN_CURRENT_PERCENT = 100; 19 | const uint8_t HOLD_CURRENT_STANDSTILL = 0; 20 | 21 | // Instantiate TMC2209 22 | TMC2209 stepper_driver; 23 | 24 | 25 | void setup() 26 | { 27 | Serial.begin(SERIAL_BAUD_RATE); 28 | 29 | stepper_driver.setup(serial_stream); 30 | 31 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 32 | stepper_driver.setHoldCurrent(HOLD_CURRENT_STANDSTILL); 33 | stepper_driver.enable(); 34 | } 35 | 36 | void loop() 37 | { 38 | Serial.println("standstill mode = NORMAL"); 39 | stepper_driver.setStandstillMode(stepper_driver.NORMAL); 40 | delay(DELAY); 41 | 42 | Serial.println("standstill mode = FREEWHEELING"); 43 | stepper_driver.setStandstillMode(stepper_driver.FREEWHEELING); 44 | delay(DELAY); 45 | 46 | Serial.println("standstill mode = STRONG_BRAKING"); 47 | stepper_driver.setStandstillMode(stepper_driver.STRONG_BRAKING); 48 | delay(DELAY); 49 | 50 | Serial.println("standstill mode = BRAKING"); 51 | stepper_driver.setStandstillMode(stepper_driver.BRAKING); 52 | delay(DELAY); 53 | 54 | Serial.println(); 55 | } 56 | -------------------------------------------------------------------------------- /examples/UnidirectionalCommunication/StepAndDirection/StepAndDirection.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example will not work on Arduino boards without HardwareSerial ports, 4 | // such as the Uno, Nano, and Mini. 5 | // 6 | // See this reference for more details: 7 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 8 | // 9 | // To make this library work with those boards, refer to this library example: 10 | // examples/UnidirectionalCommunication/SoftwareSerial 11 | 12 | HardwareSerial & serial_stream = Serial3; 13 | 14 | const uint8_t STEP_PIN = 2; 15 | const uint8_t DIRECTION_PIN = 3; 16 | const uint32_t STEP_COUNT = 51200; 17 | const uint16_t HALF_STEP_DURATION_MICROSECONDS = 10; 18 | const uint16_t STOP_DURATION = 1000; 19 | // current values may need to be reduced to prevent overheating depending on 20 | // specific motor and power supply voltage 21 | const uint8_t RUN_CURRENT_PERCENT = 100; 22 | 23 | 24 | // Instantiate TMC2209 25 | TMC2209 stepper_driver; 26 | 27 | void setup() 28 | { 29 | stepper_driver.setup(serial_stream); 30 | 31 | pinMode(STEP_PIN, OUTPUT); 32 | pinMode(DIRECTION_PIN, OUTPUT); 33 | 34 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 35 | stepper_driver.enableCoolStep(); 36 | stepper_driver.enable(); 37 | } 38 | 39 | void loop() 40 | { 41 | // One step takes two iterations through the for loop 42 | for (uint32_t i=0; i 2 | #include 3 | 4 | // This example will not work on Arduino boards without HardwareSerial ports, 5 | // such as the Uno, Nano, and Mini. 6 | // 7 | // See this reference for more details: 8 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 9 | // 10 | // To make this library work with those boards, refer to this library example: 11 | // examples/UnidirectionalCommunication/SoftwareSerial 12 | 13 | const long SERIAL_BAUD_RATE = 115200; 14 | const int BETWEEN_MOVE_DELAY = 2000; 15 | const int CHECK_AT_POSITION_DELAY = 500; 16 | 17 | // Stepper driver settings 18 | HardwareSerial & serial_stream = Serial3; 19 | // current values may need to be reduced to prevent overheating depending on 20 | // specific motor and power supply voltage 21 | const int RUN_CURRENT_PERCENT = 100; 22 | const int MICROSTEPS_PER_STEP = 256; 23 | 24 | // Instantiate stepper driver 25 | TMC2209 stepper_driver; 26 | 27 | // Stepper controller settings 28 | const int CHIP_SELECT_PIN = 10; 29 | const int CLOCK_FREQUENCY_MHZ = 32; 30 | const int MOTOR_INDEX = 0; 31 | const int STEPS_PER_REV = 200; 32 | const int MICROSTEPS_PER_REV = STEPS_PER_REV*MICROSTEPS_PER_STEP; 33 | const long REVS_PER_MOVE = 10; 34 | const long TARGET_POSITION = REVS_PER_MOVE * MICROSTEPS_PER_REV; 35 | const int ACCELERATION_MAX = 2 * MICROSTEPS_PER_REV; 36 | const long ZERO_POSITION = 0; 37 | const long VELOCITY_MAX = 2 * MICROSTEPS_PER_REV; 38 | const long VELOCITY_MIN = 500; 39 | 40 | // Instantiate stepper controller 41 | TMC429 stepper_controller; 42 | 43 | long target_position, actual_position; 44 | 45 | void setup() 46 | { 47 | Serial.begin(SERIAL_BAUD_RATE); 48 | 49 | stepper_driver.setup(serial_stream); 50 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 51 | stepper_driver.enableAutomaticCurrentScaling(); 52 | stepper_driver.enableAutomaticGradientAdaptation(); 53 | stepper_driver.enableCoolStep(); 54 | 55 | stepper_controller.setup(CHIP_SELECT_PIN, CLOCK_FREQUENCY_MHZ); 56 | stepper_controller.disableLeftSwitchStop(MOTOR_INDEX); 57 | stepper_controller.disableRightSwitches(); 58 | stepper_controller.disableRightSwitchStop(MOTOR_INDEX); 59 | stepper_controller.setLimitsInHz(MOTOR_INDEX, VELOCITY_MIN, VELOCITY_MAX, ACCELERATION_MAX); 60 | stepper_controller.setRampMode(MOTOR_INDEX); 61 | 62 | stepper_controller.setActualPosition(MOTOR_INDEX, ZERO_POSITION); 63 | stepper_controller.setTargetPosition(MOTOR_INDEX, ZERO_POSITION); 64 | 65 | stepper_driver.enable(); 66 | } 67 | 68 | void loop() 69 | { 70 | actual_position = stepper_controller.getActualPosition(MOTOR_INDEX); 71 | Serial.print("actual position: "); 72 | Serial.println(actual_position); 73 | Serial.println(); 74 | delay(BETWEEN_MOVE_DELAY); 75 | 76 | Serial.print("set target position: "); 77 | Serial.println(TARGET_POSITION); 78 | stepper_controller.setTargetPosition(MOTOR_INDEX, TARGET_POSITION); 79 | while (!stepper_controller.atTargetPosition(MOTOR_INDEX)) 80 | { 81 | Serial.print("target position: "); 82 | Serial.println(stepper_controller.getTargetPosition(MOTOR_INDEX)); 83 | Serial.print("actual position: "); 84 | Serial.println(stepper_controller.getActualPosition(MOTOR_INDEX)); 85 | delay(CHECK_AT_POSITION_DELAY); 86 | } 87 | Serial.println("at target position!"); 88 | Serial.println(); 89 | delay(BETWEEN_MOVE_DELAY); 90 | 91 | Serial.print("set target position: "); 92 | Serial.println(ZERO_POSITION); 93 | stepper_controller.setTargetPosition(MOTOR_INDEX, ZERO_POSITION); 94 | while (!stepper_controller.atTargetPosition(MOTOR_INDEX)) 95 | { 96 | Serial.print("target position: "); 97 | Serial.println(stepper_controller.getTargetPosition(MOTOR_INDEX)); 98 | Serial.print("actual position: "); 99 | Serial.println(stepper_controller.getActualPosition(MOTOR_INDEX)); 100 | delay(CHECK_AT_POSITION_DELAY); 101 | } 102 | Serial.println(); 103 | delay(BETWEEN_MOVE_DELAY); 104 | } 105 | -------------------------------------------------------------------------------- /examples/UnidirectionalCommunication/TMC429ThreeSteppers/TMC429ThreeSteppers.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | // This example will not work on Arduino boards without at least three 5 | // HardwareSerial ports. 6 | // 7 | // See this reference for more details: 8 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 9 | // 10 | // To make this library work with those boards, refer to this library example: 11 | // examples/UnidirectionalCommunication/SoftwareSerial 12 | 13 | const long SERIAL_BAUD_RATE = 115200; 14 | const int BETWEEN_MOVE_DELAY = 2000; 15 | const int CHECK_AT_POSITION_DELAY = 500; 16 | 17 | // Stepper drivers settings 18 | enum{MOTOR_COUNT=3}; 19 | HardwareSerial * serial_stream_ptrs[MOTOR_COUNT] = 20 | { 21 | &Serial1, 22 | &Serial2, 23 | &Serial3, 24 | }; 25 | // current values may need to be reduced to prevent overheating depending on 26 | // specific motor and power supply voltage 27 | const int RUN_CURRENT_PERCENT = 100; 28 | const int MICROSTEPS_PER_STEP = 256; 29 | 30 | // Instantiate stepper drivers 31 | TMC2209 stepper_drivers[MOTOR_COUNT]; 32 | 33 | // Stepper controller settings 34 | const int CHIP_SELECT_PIN = 10; 35 | const int CLOCK_FREQUENCY_MHZ = 32; 36 | const int MOTOR_INDEX = 0; 37 | const int STEPS_PER_REV = 200; 38 | const int MICROSTEPS_PER_REV = STEPS_PER_REV*MICROSTEPS_PER_STEP; 39 | const long REVS_PER_MOVE = 10; 40 | const long TARGET_POSITION = REVS_PER_MOVE * MICROSTEPS_PER_REV; 41 | const int ACCELERATION_MAX = 2 * MICROSTEPS_PER_REV; 42 | const long ZERO_POSITION = 0; 43 | const long VELOCITY_MAX = 2 * MICROSTEPS_PER_REV; 44 | const long VELOCITY_MIN = 500; 45 | 46 | // Instantiate stepper controller 47 | TMC429 stepper_controller; 48 | 49 | long target_position, actual_position; 50 | 51 | void setup() 52 | { 53 | Serial.begin(SERIAL_BAUD_RATE); 54 | 55 | for (size_t motor_index=0; motor_index 2 | #include 3 | 4 | // This example will not work on Arduino boards without HardwareSerial ports, 5 | // such as the Uno, Nano, and Mini. 6 | // 7 | // See this reference for more details: 8 | // https://www.arduino.cc/reference/en/language/functions/communication/serial/ 9 | // 10 | // To make this library work with those boards, refer to this library example: 11 | // examples/UnidirectionalCommunication/SoftwareSerial 12 | 13 | const long SERIAL_BAUD_RATE = 115200; 14 | const int LOOP_DELAY = 1000; 15 | 16 | // Stepper driver settings 17 | HardwareSerial & serial_stream = Serial3; 18 | // current values may need to be reduced to prevent overheating depending on 19 | // specific motor and power supply voltage 20 | const int RUN_CURRENT_PERCENT = 100; 21 | const int MICROSTEPS_PER_STEP = 256; 22 | 23 | // Instantiate stepper driver 24 | TMC2209 stepper_driver; 25 | 26 | // Stepper controller settings 27 | const int CHIP_SELECT_PIN = 10; 28 | const int CLOCK_FREQUENCY_MHZ = 32; 29 | const int MOTOR_INDEX = 0; 30 | const int STEPS_PER_REV = 200; 31 | const int REVS_PER_SEC_MAX = 2; 32 | const int MICROSTEPS_PER_REV = STEPS_PER_REV*MICROSTEPS_PER_STEP; 33 | const int ACCELERATION_MAX = MICROSTEPS_PER_REV / 2; 34 | const long VELOCITY_MAX = REVS_PER_SEC_MAX * MICROSTEPS_PER_REV; 35 | const long VELOCITY_MIN = 50; 36 | 37 | // Instantiate stepper controller 38 | TMC429 stepper_controller; 39 | 40 | long target_velocity, actual_velocity; 41 | 42 | void setup() 43 | { 44 | Serial.begin(SERIAL_BAUD_RATE); 45 | 46 | stepper_driver.setup(serial_stream); 47 | stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 48 | stepper_driver.enableAutomaticCurrentScaling(); 49 | stepper_driver.enableAutomaticGradientAdaptation(); 50 | stepper_driver.enableCoolStep(); 51 | 52 | stepper_controller.setup(CHIP_SELECT_PIN, CLOCK_FREQUENCY_MHZ); 53 | stepper_controller.disableLeftSwitchStop(MOTOR_INDEX); 54 | stepper_controller.disableRightSwitches(); 55 | stepper_controller.setVelocityMode(MOTOR_INDEX); 56 | stepper_controller.setLimitsInHz(MOTOR_INDEX, VELOCITY_MIN, VELOCITY_MAX, ACCELERATION_MAX); 57 | 58 | stepper_driver.enable(); 59 | } 60 | 61 | void loop() 62 | { 63 | delay(LOOP_DELAY); 64 | 65 | stepper_controller.setTargetVelocityInHz(MOTOR_INDEX, VELOCITY_MAX); 66 | Serial.print("set target_velocity: "); 67 | Serial.println(target_velocity); 68 | Serial.print("at target_velocity: "); 69 | Serial.println(stepper_controller.atTargetVelocity(MOTOR_INDEX)); 70 | 71 | target_velocity = stepper_controller.getTargetVelocityInHz(MOTOR_INDEX); 72 | 73 | actual_velocity = stepper_controller.getActualVelocityInHz(MOTOR_INDEX); 74 | Serial.print("actual_velocity: "); 75 | Serial.println(actual_velocity); 76 | } 77 | -------------------------------------------------------------------------------- /examples/UnidirectionalCommunication/TestRP2040/TestRP2040.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | // This example is meant to test a FYSETC-ERB board containing an RP2040 and 4 | // two TMC2209 chips 5 | // 6 | // See this reference for more details: 7 | // https://github.com/FYSETC/FYSETC-ERB 8 | 9 | 10 | const uint8_t X_TX_PIN = 20; 11 | const uint8_t Y_TX_PIN = 17; 12 | const long SERIAL_BAUD_RATE = 115200; 13 | 14 | SerialPIO x_serial(X_TX_PIN, SerialPIO::NOPIN); 15 | SerialPIO y_serial(Y_TX_PIN, SerialPIO::NOPIN); 16 | 17 | // Instantiate TMC2209 18 | TMC2209 x_stepper_driver; 19 | TMC2209 y_stepper_driver; 20 | 21 | // current values may need to be reduced to prevent overheating depending on 22 | // specific motor and power supply voltage 23 | const uint8_t RUN_CURRENT_PERCENT = 100; 24 | 25 | const int32_t RUN_VELOCITY = 20000; 26 | 27 | 28 | void setup() 29 | { 30 | x_stepper_driver.setup(x_serial, SERIAL_BAUD_RATE); 31 | x_stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 32 | x_stepper_driver.enableCoolStep(); 33 | x_stepper_driver.enable(); 34 | x_stepper_driver.moveAtVelocity(RUN_VELOCITY); 35 | 36 | y_stepper_driver.setup(y_serial, SERIAL_BAUD_RATE); 37 | y_stepper_driver.setRunCurrent(RUN_CURRENT_PERCENT); 38 | y_stepper_driver.enableCoolStep(); 39 | y_stepper_driver.enable(); 40 | y_stepper_driver.moveAtVelocity(RUN_VELOCITY); 41 | } 42 | 43 | void loop() 44 | { 45 | } 46 | -------------------------------------------------------------------------------- /idf_component.yml: -------------------------------------------------------------------------------- 1 | dependencies: 2 | idf: 3 | version: ">=5.3.0" 4 | arduino-esp32: 5 | version: "*" 6 | -------------------------------------------------------------------------------- /images/trinamic_wiring-TMC2209-unidirectional.svg: -------------------------------------------------------------------------------- 1 | 2 | 13 | 15 | 16 | 18 | image/svg+xml 19 | 21 | 22 | 23 | 24 | 26 | SVG Image created as trinamic_wiring-TMC2209-unidirectional.svg date 2023/08/02 16:28:28 28 | Image generated by Eeschema-SVG 30 | 34 | 38 | 40 | 43 | 46 | 53 | MICROCONTROLLER 62 | 65 | MICROCONTROLLER 67 | 70 | 73 | 76 | 79 | 82 | 85 | 88 | 91 | 94 | 97 | 100 | 103 | 106 | 109 | 112 | 115 | 118 | 121 | 124 | 127 | 130 | 133 | 136 | 139 | 142 | 145 | 148 | 151 | 154 | 157 | 160 | 163 | 166 | 169 | 172 | 175 | 178 | 181 | 184 | 187 | 190 | 193 | 196 | 199 | 202 | 205 | 208 | 211 | 214 | 217 | 220 | 223 | 226 | 229 | 232 | 235 | 238 | 241 | 244 | 247 | 250 | 253 | 256 | 259 | 262 | 265 | 268 | 271 | 274 | 277 | 280 | 283 | 286 | 289 | 292 | 295 | 298 | 301 | 304 | 307 | 310 | 313 | 316 | 319 | 322 | 325 | 328 | 331 | 334 | 337 | 340 | 343 | 346 | 349 | 352 | 355 | 358 | 361 | 364 | 367 | 370 | 373 | 376 | 379 | 382 | 385 | 388 | 391 | 394 | 397 | 400 | 403 | 406 | 409 | 412 | 415 | 418 | 421 | 424 | 427 | 430 | 433 | 436 | 439 | 442 | 445 | 448 | 451 | 454 | 455 | 458 | 459 | 462 | 465 | RX 474 | 477 | RX 479 | 482 | 485 | 488 | 491 | 494 | 497 | 500 | 503 | 506 | 509 | 512 | 515 | 518 | 519 | 520 | 523 | 526 | 529 | 530 | 533 | 536 | TX 545 | 548 | TX 550 | 553 | 556 | 559 | 562 | 563 | 564 | 565 | 569 | 571 | 574 | 577 | 584 | TMC2209 593 | 596 | TMC2209 598 | 601 | 604 | 607 | 610 | 613 | 616 | 619 | 622 | 625 | 628 | 631 | 634 | 637 | 640 | 643 | 646 | 649 | 652 | 655 | 658 | 661 | 664 | 667 | 670 | 673 | 676 | 679 | 682 | 685 | 688 | 691 | 694 | 697 | 700 | 703 | 706 | 709 | 712 | 715 | 718 | 721 | 724 | 727 | 730 | 733 | 736 | 739 | 742 | 745 | 748 | 751 | 754 | 757 | 760 | 763 | 766 | 769 | 772 | 775 | 778 | 781 | 784 | 787 | 790 | 793 | 796 | 799 | 802 | 805 | 808 | 811 | 814 | 817 | 820 | 823 | 826 | 829 | 832 | 835 | 838 | 841 | 844 | 845 | 848 | 849 | 852 | 855 | UART 864 | 867 | UART 869 | 872 | 875 | 878 | 881 | 884 | 887 | 890 | 893 | 896 | 899 | 902 | 905 | 908 | 911 | 914 | 917 | 920 | 923 | 926 | 929 | 932 | 935 | 938 | 941 | 944 | 945 | 946 | 947 | 951 | 955 | 959 | 962 | 963 | 967 | 971 | 974 | 977 | 978 | 979 | -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=TMC2209 2 | version=10.1.0 3 | author=Peter Polidoro 4 | maintainer=Peter Polidoro 5 | sentence=The TMC2209 is an ultra-silent motor driver IC for two phase stepper motors with both UART serial and step and direction interfaces. 6 | paragraph=Like this project? Please star it on GitHub! 7 | category=Device Control 8 | url=https://github.com/janelia-arduino/TMC2209 9 | architectures=* 10 | -------------------------------------------------------------------------------- /platformio.ini: -------------------------------------------------------------------------------- 1 | [platformio] 2 | src_dir = examples/UnidirectionalCommunication/MoveAtVelocity 3 | ;src_dir = examples/UnidirectionalCommunication/SoftwareSerial 4 | ;src_dir = examples/BidirectionalCommunication/TestRP2040 5 | ;src_dir = examples/UnidirectionalCommunication/TestRP2040 6 | ;src_dir = examples/BidirectionalCommunication/TestUnoR4 7 | 8 | lib_dir = src 9 | default_envs = teensy40 10 | 11 | [common_env_data] 12 | build_flags = 13 | -Isrc 14 | lib_deps_local = 15 | src/TMC2209 16 | 17 | [env] 18 | lib_ldf_mode = off 19 | build_flags = 20 | ${common_env_data.build_flags} 21 | monitor_echo = yes 22 | monitor_eol = LF 23 | monitor_filters = 24 | send_on_enter 25 | colorize 26 | monitor_speed = 115200 27 | lib_deps = 28 | ${common_env_data.lib_deps_local} 29 | 30 | [env:teensy40] 31 | platform = teensy 32 | framework = arduino 33 | board = teensy40 34 | upload_protocol = teensy-cli 35 | lib_deps = 36 | SoftwareSerial 37 | ${env.lib_deps} 38 | 39 | [env:mega] 40 | platform = atmelavr 41 | framework = arduino 42 | board = megaatmega2560 43 | lib_deps = 44 | SoftwareSerial 45 | ${env.lib_deps} 46 | 47 | [env:uno] 48 | platform = atmelavr 49 | framework = arduino 50 | board = uno 51 | lib_deps = 52 | SoftwareSerial 53 | ${env.lib_deps} 54 | 55 | [env:uno_r4_minima] 56 | platform = renesas-ra 57 | framework = arduino 58 | board = uno_r4_minima 59 | lib_deps = 60 | SoftwareSerial 61 | ${env.lib_deps} 62 | 63 | [env:uno_r4_wifi] 64 | platform = renesas-ra 65 | framework = arduino 66 | board = uno_r4_wifi 67 | lib_deps = 68 | SoftwareSerial 69 | ${env.lib_deps} 70 | 71 | [env:pico] 72 | platform = https://github.com/maxgerhardt/platform-raspberrypi.git 73 | board = rpipico 74 | framework = arduino 75 | board_build.core = earlephilhower 76 | upload_protocol = picotool 77 | 78 | ; pio run -e teensy40 --target upload --upload-port /dev/ttyACM0 79 | ; pio run -e teensy40 -t envdump 80 | ; pio device monitor 81 | -------------------------------------------------------------------------------- /src/TMC2209.h: -------------------------------------------------------------------------------- 1 | // ---------------------------------------------------------------------------- 2 | // TMC2209.h 3 | // 4 | // Authors: 5 | // Peter Polidoro peter@polidoro.io 6 | // ---------------------------------------------------------------------------- 7 | 8 | #ifndef TMC2209_H 9 | #define TMC2209_H 10 | #include 11 | 12 | #if !defined(ESP32) && !defined(ARDUINO_ARCH_SAMD) && !defined(ARDUINO_ARCH_RP2040) && !defined(ARDUINO_SAM_DUE) && !defined(ARDUINO_ARCH_RENESAS) 13 | # define SOFTWARE_SERIAL_INCLUDED true 14 | #else 15 | # define SOFTWARE_SERIAL_INCLUDED false 16 | #endif 17 | #if SOFTWARE_SERIAL_INCLUDED 18 | # include 19 | #endif 20 | 21 | 22 | class TMC2209 23 | { 24 | public: 25 | TMC2209(); 26 | 27 | enum SerialAddress 28 | { 29 | SERIAL_ADDRESS_0=0, 30 | SERIAL_ADDRESS_1=1, 31 | SERIAL_ADDRESS_2=2, 32 | SERIAL_ADDRESS_3=3, 33 | }; 34 | // Identify which microcontroller serial port is connected to the TMC2209 e.g. 35 | // Serial1, Serial2, etc. Optionally identify which serial address is assigned 36 | // to the TMC2209 if not the default of SERIAL_ADDRESS_0. 37 | #if !defined(ARDUINO_ARCH_RENESAS) 38 | void setup(HardwareSerial & serial, 39 | long serial_baud_rate=115200, 40 | SerialAddress serial_address=SERIAL_ADDRESS_0); 41 | #endif 42 | // Alternate rx and tx pins may be specified for certain microcontrollers e.g. 43 | // ESP32 and RP2040 44 | #if defined(ESP32) 45 | void setup(HardwareSerial & serial, 46 | long serial_baud_rate, 47 | SerialAddress serial_address, 48 | int16_t alternate_rx_pin, 49 | int16_t alternate_tx_pin); 50 | #elif defined(ARDUINO_ARCH_RP2040) 51 | void setup(SerialUART & serial, 52 | long serial_baud_rate, 53 | SerialAddress serial_address, 54 | int16_t alternate_rx_pin, 55 | int16_t alternate_tx_pin); 56 | #elif defined(ARDUINO_ARCH_RENESAS) 57 | void setup(UART & serial, 58 | long serial_baud_rate=115200, 59 | SerialAddress serial_address=SERIAL_ADDRESS_0); 60 | #endif 61 | 62 | #if SOFTWARE_SERIAL_INCLUDED 63 | // Software serial ports should only be used for unidirectional communication 64 | // The RX pin does not need to be connected, but it must be specified when 65 | // creating an instance of a SoftwareSerial object 66 | void setup(SoftwareSerial & serial, 67 | long serial_baud_rate=9600, 68 | SerialAddress serial_address=SERIAL_ADDRESS_0); 69 | #endif 70 | 71 | // unidirectional methods 72 | 73 | // driver must be enabled before use it is disabled by default 74 | void setHardwareEnablePin(uint8_t hardware_enable_pin); 75 | void enable(); 76 | void disable(); 77 | 78 | // valid values = 1,2,4,8,...128,256, other values get rounded down 79 | void setMicrostepsPerStep(uint16_t microsteps_per_step); 80 | 81 | // valid values = 0-8, microsteps = 2^exponent, 0=1,1=2,2=4,...8=256 82 | // https://en.wikipedia.org/wiki/Power_of_two 83 | void setMicrostepsPerStepPowerOfTwo(uint8_t exponent); 84 | 85 | // range 0-100 86 | void setRunCurrent(uint8_t percent); 87 | // range 0-100 88 | void setHoldCurrent(uint8_t percent); 89 | // range 0-100 90 | void setHoldDelay(uint8_t percent); 91 | // range 0-100 92 | void setAllCurrentValues(uint8_t run_current_percent, 93 | uint8_t hold_current_percent, 94 | uint8_t hold_delay_percent); 95 | void setRMSCurrent(uint16_t mA, 96 | float rSense, 97 | float holdMultiplier = 0.5f); 98 | 99 | void enableDoubleEdge(); 100 | void disableDoubleEdge(); 101 | 102 | void enableVSense(); 103 | void disableVSense(); 104 | 105 | void enableInverseMotorDirection(); 106 | void disableInverseMotorDirection(); 107 | 108 | enum StandstillMode 109 | { 110 | NORMAL=0, 111 | FREEWHEELING=1, 112 | STRONG_BRAKING=2, 113 | BRAKING=3, 114 | }; 115 | void setStandstillMode(StandstillMode mode); 116 | 117 | void enableAutomaticCurrentScaling(); 118 | void disableAutomaticCurrentScaling(); 119 | void enableAutomaticGradientAdaptation(); 120 | void disableAutomaticGradientAdaptation(); 121 | // range 0-255 122 | void setPwmOffset(uint8_t pwm_amplitude); 123 | // range 0-255 124 | void setPwmGradient(uint8_t pwm_amplitude); 125 | 126 | // default = 20 127 | // mimimum of 2 for StealthChop auto tuning 128 | void setPowerDownDelay(uint8_t power_down_delay); 129 | 130 | // mimimum of 2 when using multiple serial addresses 131 | // in bidirectional communication 132 | const static uint8_t REPLY_DELAY_MAX = 15; 133 | void setReplyDelay(uint8_t delay); 134 | 135 | void moveAtVelocity(int32_t microsteps_per_period); 136 | void moveUsingStepDirInterface(); 137 | 138 | void enableStealthChop(); 139 | void disableStealthChop(); 140 | 141 | void setStealthChopDurationThreshold(uint32_t duration_threshold); 142 | 143 | void setStallGuardThreshold(uint8_t stall_guard_threshold); 144 | 145 | // lower_threshold: min = 1, max = 15 146 | // upper_threshold: min = 0, max = 15, 0-2 recommended 147 | void enableCoolStep(uint8_t lower_threshold=1, 148 | uint8_t upper_threshold=0); 149 | void disableCoolStep(); 150 | enum CurrentIncrement 151 | { 152 | CURRENT_INCREMENT_1=0, 153 | CURRENT_INCREMENT_2=1, 154 | CURRENT_INCREMENT_4=2, 155 | CURRENT_INCREMENT_8=3, 156 | }; 157 | void setCoolStepCurrentIncrement(CurrentIncrement current_increment); 158 | enum MeasurementCount 159 | { 160 | MEASUREMENT_COUNT_32=0, 161 | MEASUREMENT_COUNT_8=1, 162 | MEASUREMENT_COUNT_2=2, 163 | MEASUREMENT_COUNT_1=3, 164 | }; 165 | void setCoolStepMeasurementCount(MeasurementCount measurement_count); 166 | void setCoolStepDurationThreshold(uint32_t duration_threshold); 167 | 168 | void enableAnalogCurrentScaling(); 169 | void disableAnalogCurrentScaling(); 170 | 171 | void useExternalSenseResistors(); 172 | void useInternalSenseResistors(); 173 | 174 | // bidirectional methods 175 | uint8_t getVersion(); 176 | 177 | // if driver is not communicating, check power and communication connections 178 | bool isCommunicating(); 179 | 180 | // check to make sure TMC2209 is properly setup and communicating 181 | bool isSetupAndCommunicating(); 182 | 183 | // driver may be communicating but not setup if driver power is lost then 184 | // restored after setup so that defaults are loaded instead of setup options 185 | bool isCommunicatingButNotSetup(); 186 | 187 | // driver may also be disabled by the hardware enable input pin 188 | // this pin must be grounded or disconnected before driver may be enabled 189 | bool hardwareDisabled(); 190 | 191 | uint16_t getMicrostepsPerStep(); 192 | 193 | struct Settings 194 | { 195 | bool is_communicating; 196 | bool is_setup; 197 | bool software_enabled; 198 | uint16_t microsteps_per_step; 199 | bool inverse_motor_direction_enabled; 200 | bool stealth_chop_enabled; 201 | uint8_t standstill_mode; 202 | uint8_t irun_percent; 203 | uint8_t irun_register_value; 204 | uint8_t ihold_percent; 205 | uint8_t ihold_register_value; 206 | uint8_t iholddelay_percent; 207 | uint8_t iholddelay_register_value; 208 | bool automatic_current_scaling_enabled; 209 | bool automatic_gradient_adaptation_enabled; 210 | uint8_t pwm_offset; 211 | uint8_t pwm_gradient; 212 | bool cool_step_enabled; 213 | bool analog_current_scaling_enabled; 214 | bool internal_sense_resistors_enabled; 215 | }; 216 | Settings getSettings(); 217 | 218 | struct Status 219 | { 220 | uint32_t over_temperature_warning : 1; 221 | uint32_t over_temperature_shutdown : 1; 222 | uint32_t short_to_ground_a : 1; 223 | uint32_t short_to_ground_b : 1; 224 | uint32_t low_side_short_a : 1; 225 | uint32_t low_side_short_b : 1; 226 | uint32_t open_load_a : 1; 227 | uint32_t open_load_b : 1; 228 | uint32_t over_temperature_120c : 1; 229 | uint32_t over_temperature_143c : 1; 230 | uint32_t over_temperature_150c : 1; 231 | uint32_t over_temperature_157c : 1; 232 | uint32_t reserved0 : 4; 233 | uint32_t current_scaling : 5; 234 | uint32_t reserved1 : 9; 235 | uint32_t stealth_chop_mode : 1; 236 | uint32_t standstill : 1; 237 | }; 238 | const static uint8_t CURRENT_SCALING_MAX = 31; 239 | Status getStatus(); 240 | 241 | struct GlobalStatus 242 | { 243 | uint32_t reset : 1; 244 | uint32_t drv_err : 1; 245 | uint32_t uv_cp : 1; 246 | uint32_t reserved : 29; 247 | }; 248 | GlobalStatus getGlobalStatus(); 249 | void clearReset(); 250 | void clearDriveError(); 251 | 252 | uint8_t getInterfaceTransmissionCounter(); 253 | 254 | uint32_t getInterstepDuration(); 255 | 256 | uint16_t getStallGuardResult(); 257 | 258 | uint8_t getPwmScaleSum(); 259 | int16_t getPwmScaleAuto(); 260 | uint8_t getPwmOffsetAuto(); 261 | uint8_t getPwmGradientAuto(); 262 | 263 | uint16_t getMicrostepCounter(); 264 | 265 | private: 266 | HardwareSerial * hardware_serial_ptr_; 267 | #if SOFTWARE_SERIAL_INCLUDED 268 | SoftwareSerial * software_serial_ptr_; 269 | #endif 270 | uint32_t serial_baud_rate_; 271 | uint8_t serial_address_; 272 | int16_t hardware_enable_pin_; 273 | 274 | void initialize(long serial_baud_rate=115200, 275 | SerialAddress serial_address=SERIAL_ADDRESS_0); 276 | int serialAvailable(); 277 | size_t serialWrite(uint8_t c); 278 | int serialRead(); 279 | void serialFlush(); 280 | 281 | // Serial Settings 282 | const static uint8_t BYTE_MAX_VALUE = 0xFF; 283 | const static uint8_t BITS_PER_BYTE = 8; 284 | 285 | const static uint32_t ECHO_DELAY_INC_MICROSECONDS = 1; 286 | const static uint32_t ECHO_DELAY_MAX_MICROSECONDS = 4000; 287 | 288 | const static uint32_t REPLY_DELAY_INC_MICROSECONDS = 1; 289 | const static uint32_t REPLY_DELAY_MAX_MICROSECONDS = 10000; 290 | 291 | const static uint8_t STEPPER_DRIVER_FEATURE_OFF = 0; 292 | const static uint8_t STEPPER_DRIVER_FEATURE_ON = 1; 293 | 294 | const static uint8_t MAX_READ_RETRIES = 5; 295 | const static uint32_t READ_RETRY_DELAY_MS = 20; 296 | 297 | // Datagrams 298 | const static uint8_t WRITE_READ_REPLY_DATAGRAM_SIZE = 8; 299 | const static uint8_t DATA_SIZE = 4; 300 | union WriteReadReplyDatagram 301 | { 302 | struct 303 | { 304 | uint64_t sync : 4; 305 | uint64_t reserved : 4; 306 | uint64_t serial_address : 8; 307 | uint64_t register_address : 7; 308 | uint64_t rw : 1; 309 | uint64_t data : 32; 310 | uint64_t crc : 8; 311 | }; 312 | uint64_t bytes; 313 | }; 314 | 315 | const static uint8_t SYNC = 0b101; 316 | const static uint8_t RW_READ = 0; 317 | const static uint8_t RW_WRITE = 1; 318 | const static uint8_t READ_REPLY_SERIAL_ADDRESS = 0b11111111; 319 | 320 | const static uint8_t READ_REQUEST_DATAGRAM_SIZE = 4; 321 | union ReadRequestDatagram 322 | { 323 | struct 324 | { 325 | uint32_t sync : 4; 326 | uint32_t reserved : 4; 327 | uint32_t serial_address : 8; 328 | uint32_t register_address : 7; 329 | uint32_t rw : 1; 330 | uint32_t crc : 8; 331 | }; 332 | uint32_t bytes; 333 | }; 334 | 335 | // General Configuration Registers 336 | const static uint8_t ADDRESS_GCONF = 0x00; 337 | union GlobalConfig 338 | { 339 | struct 340 | { 341 | uint32_t i_scale_analog : 1; 342 | uint32_t internal_rsense : 1; 343 | uint32_t enable_spread_cycle : 1; 344 | uint32_t shaft : 1; 345 | uint32_t index_otpw : 1; 346 | uint32_t index_step : 1; 347 | uint32_t pdn_disable : 1; 348 | uint32_t mstep_reg_select : 1; 349 | uint32_t multistep_filt : 1; 350 | uint32_t test_mode : 1; 351 | uint32_t reserved : 22; 352 | }; 353 | uint32_t bytes; 354 | }; 355 | GlobalConfig global_config_; 356 | 357 | const static uint8_t ADDRESS_GSTAT = 0x01; 358 | union GlobalStatusUnion 359 | { 360 | struct 361 | { 362 | GlobalStatus global_status; 363 | }; 364 | uint32_t bytes; 365 | }; 366 | 367 | const static uint8_t ADDRESS_IFCNT = 0x02; 368 | 369 | const static uint8_t ADDRESS_REPLYDELAY = 0x03; 370 | union ReplyDelay 371 | { 372 | struct 373 | { 374 | uint32_t reserved_0 : 8; 375 | uint32_t replydelay : 4; 376 | uint32_t reserved_1 : 20; 377 | }; 378 | uint32_t bytes; 379 | }; 380 | 381 | const static uint8_t ADDRESS_IOIN = 0x06; 382 | union Input 383 | { 384 | struct 385 | { 386 | uint32_t enn : 1; 387 | uint32_t reserved_0 : 1; 388 | uint32_t ms1 : 1; 389 | uint32_t ms2 : 1; 390 | uint32_t diag : 1; 391 | uint32_t reserved_1 : 1; 392 | uint32_t pdn_serial : 1; 393 | uint32_t step : 1; 394 | uint32_t spread_en : 1; 395 | uint32_t dir : 1; 396 | uint32_t reserved_2 : 14; 397 | uint32_t version : 8; 398 | }; 399 | uint32_t bytes; 400 | }; 401 | const static uint8_t VERSION = 0x21; 402 | 403 | 404 | // Velocity Dependent Driver Feature Control Register Set 405 | const static uint8_t ADDRESS_IHOLD_IRUN = 0x10; 406 | union DriverCurrent 407 | { 408 | struct 409 | { 410 | uint32_t ihold : 5; 411 | uint32_t reserved_0 : 3; 412 | uint32_t irun : 5; 413 | uint32_t reserved_1 : 3; 414 | uint32_t iholddelay : 4; 415 | uint32_t reserved_2 : 12; 416 | }; 417 | uint32_t bytes; 418 | }; 419 | DriverCurrent driver_current_; 420 | const static uint8_t PERCENT_MIN = 0; 421 | const static uint8_t PERCENT_MAX = 100; 422 | const static uint8_t CURRENT_SETTING_MIN = 0; 423 | const static uint8_t CURRENT_SETTING_MAX = 31; 424 | const static uint8_t HOLD_DELAY_MIN = 0; 425 | const static uint8_t HOLD_DELAY_MAX = 15; 426 | const static uint8_t IHOLD_DEFAULT = 16; 427 | const static uint8_t IRUN_DEFAULT = 31; 428 | const static uint8_t IHOLDDELAY_DEFAULT = 1; 429 | 430 | const static uint8_t ADDRESS_TPOWERDOWN = 0x11; 431 | const static uint8_t TPOWERDOWN_DEFAULT = 20; 432 | 433 | const static uint8_t ADDRESS_TSTEP = 0x12; 434 | 435 | const static uint8_t ADDRESS_TPWMTHRS = 0x13; 436 | const static uint32_t TPWMTHRS_DEFAULT = 0; 437 | 438 | const static uint8_t ADDRESS_VACTUAL = 0x22; 439 | const static int32_t VACTUAL_DEFAULT = 0; 440 | const static int32_t VACTUAL_STEP_DIR_INTERFACE = 0; 441 | 442 | // CoolStep and StallGuard Control Register Set 443 | const static uint8_t ADDRESS_TCOOLTHRS = 0x14; 444 | const static uint8_t TCOOLTHRS_DEFAULT = 0; 445 | const static uint8_t ADDRESS_SGTHRS = 0x40; 446 | const static uint8_t SGTHRS_DEFAULT = 0; 447 | const static uint8_t ADDRESS_SG_RESULT = 0x41; 448 | 449 | const static uint8_t ADDRESS_COOLCONF = 0x42; 450 | const static uint8_t COOLCONF_DEFAULT = 0; 451 | union CoolConfig 452 | { 453 | struct 454 | { 455 | uint32_t semin : 4; 456 | uint32_t reserved_0 : 1; 457 | uint32_t seup : 2; 458 | uint32_t reserved_1 : 1; 459 | uint32_t semax : 4; 460 | uint32_t reserved_2 : 1; 461 | uint32_t sedn : 2; 462 | uint32_t seimin : 1; 463 | uint32_t reserved_3 : 16; 464 | }; 465 | uint32_t bytes; 466 | }; 467 | CoolConfig cool_config_; 468 | bool cool_step_enabled_; 469 | const static uint8_t SEIMIN_UPPER_CURRENT_LIMIT = 20; 470 | const static uint8_t SEIMIN_LOWER_SETTING = 0; 471 | const static uint8_t SEIMIN_UPPER_SETTING = 1; 472 | const static uint8_t SEMIN_OFF = 0; 473 | const static uint8_t SEMIN_MIN = 1; 474 | const static uint8_t SEMIN_MAX = 15; 475 | const static uint8_t SEMAX_MIN = 0; 476 | const static uint8_t SEMAX_MAX = 15; 477 | 478 | // Microstepping Control Register Set 479 | const static uint8_t ADDRESS_MSCNT = 0x6A; 480 | const static uint8_t ADDRESS_MSCURACT = 0x6B; 481 | 482 | // Driver Register Set 483 | const static uint8_t ADDRESS_CHOPCONF = 0x6C; 484 | union ChopperConfig 485 | { 486 | struct 487 | { 488 | uint32_t toff : 4; 489 | uint32_t hstart : 3; 490 | uint32_t hend : 4; 491 | uint32_t reserved_0 : 4; 492 | uint32_t tbl : 2; 493 | uint32_t vsense : 1; 494 | uint32_t reserved_1 : 6; 495 | uint32_t mres : 4; 496 | uint32_t interpolation : 1; 497 | uint32_t double_edge : 1; 498 | uint32_t diss2g : 1; 499 | uint32_t diss2vs : 1; 500 | }; 501 | uint32_t bytes; 502 | }; 503 | ChopperConfig chopper_config_; 504 | const static uint32_t CHOPPER_CONFIG_DEFAULT = 0x10000053; 505 | const static uint8_t TBL_DEFAULT = 0b10; 506 | const static uint8_t HEND_DEFAULT = 0; 507 | const static uint8_t HSTART_DEFAULT = 5; 508 | const static uint8_t TOFF_DEFAULT = 3; 509 | const static uint8_t TOFF_DISABLE = 0; 510 | uint8_t toff_ = TOFF_DEFAULT; 511 | const static uint8_t MRES_256 = 0b0000; 512 | const static uint8_t MRES_128 = 0b0001; 513 | const static uint8_t MRES_064 = 0b0010; 514 | const static uint8_t MRES_032 = 0b0011; 515 | const static uint8_t MRES_016 = 0b0100; 516 | const static uint8_t MRES_008 = 0b0101; 517 | const static uint8_t MRES_004 = 0b0110; 518 | const static uint8_t MRES_002 = 0b0111; 519 | const static uint8_t MRES_001 = 0b1000; 520 | const static uint8_t DOUBLE_EDGE_DISABLE = 0; 521 | const static uint8_t DOUBLE_EDGE_ENABLE = 1; 522 | const static uint8_t VSENSE_DISABLE = 0; 523 | const static uint8_t VSENSE_ENABLE = 1; 524 | 525 | const static size_t MICROSTEPS_PER_STEP_MIN = 1; 526 | const static size_t MICROSTEPS_PER_STEP_MAX = 256; 527 | 528 | const static uint8_t ADDRESS_DRV_STATUS = 0x6F; 529 | union DriveStatus 530 | { 531 | struct 532 | { 533 | Status status; 534 | }; 535 | uint32_t bytes; 536 | }; 537 | 538 | const static uint8_t ADDRESS_PWMCONF = 0x70; 539 | union PwmConfig 540 | { 541 | struct 542 | { 543 | uint32_t pwm_offset : 8; 544 | uint32_t pwm_grad : 8; 545 | uint32_t pwm_freq : 2; 546 | uint32_t pwm_autoscale : 1; 547 | uint32_t pwm_autograd : 1; 548 | uint32_t freewheel : 2; 549 | uint32_t reserved : 2; 550 | uint32_t pwm_reg : 4; 551 | uint32_t pwm_lim : 4; 552 | }; 553 | uint32_t bytes; 554 | }; 555 | PwmConfig pwm_config_; 556 | const static uint32_t PWM_CONFIG_DEFAULT = 0xC10D0024; 557 | const static uint8_t PWM_OFFSET_MIN = 0; 558 | const static uint8_t PWM_OFFSET_MAX = 255; 559 | const static uint8_t PWM_OFFSET_DEFAULT = 0x24; 560 | const static uint8_t PWM_GRAD_MIN = 0; 561 | const static uint8_t PWM_GRAD_MAX = 255; 562 | const static uint8_t PWM_GRAD_DEFAULT = 0x14; 563 | 564 | union PwmScale 565 | { 566 | struct 567 | { 568 | uint32_t pwm_scale_sum : 8; 569 | uint32_t reserved_0 : 8; 570 | uint32_t pwm_scale_auto : 9; 571 | uint32_t reserved_1 : 7; 572 | }; 573 | uint32_t bytes; 574 | }; 575 | const static uint8_t ADDRESS_PWM_SCALE = 0x71; 576 | 577 | union PwmAuto 578 | { 579 | struct 580 | { 581 | uint32_t pwm_offset_auto : 8; 582 | uint32_t reserved_0 : 8; 583 | uint32_t pwm_gradient_auto : 8; 584 | uint32_t reserved_1 : 8; 585 | }; 586 | uint32_t bytes; 587 | }; 588 | const static uint8_t ADDRESS_PWM_AUTO = 0x72; 589 | 590 | void setOperationModeToSerial(SerialAddress serial_address); 591 | 592 | void setRegistersToDefaults(); 593 | void readAndStoreRegisters(); 594 | 595 | bool serialOperationMode(); 596 | 597 | void minimizeMotorCurrent(); 598 | 599 | uint32_t reverseData(uint32_t data); 600 | template 601 | uint8_t calculateCrc(Datagram & datagram, 602 | uint8_t datagram_size); 603 | template 604 | void sendDatagramUnidirectional(Datagram & datagram, 605 | uint8_t datagram_size); 606 | template 607 | void sendDatagramBidirectional(Datagram & datagram, 608 | uint8_t datagram_size); 609 | 610 | void write(uint8_t register_address, 611 | uint32_t data); 612 | uint32_t read(uint8_t register_address); 613 | 614 | uint8_t percentToCurrentSetting(uint8_t percent); 615 | uint8_t currentSettingToPercent(uint8_t current_setting); 616 | uint8_t percentToHoldDelaySetting(uint8_t percent); 617 | uint8_t holdDelaySettingToPercent(uint8_t hold_delay_setting); 618 | 619 | uint8_t pwmAmplitudeToPwmAmpl(uint8_t pwm_amplitude); 620 | uint8_t pwmAmplitudeToPwmGrad(uint8_t pwm_amplitude); 621 | 622 | void writeStoredGlobalConfig(); 623 | uint32_t readGlobalConfigBytes(); 624 | void writeStoredDriverCurrent(); 625 | void writeStoredChopperConfig(); 626 | uint32_t readChopperConfigBytes(); 627 | void writeStoredPwmConfig(); 628 | uint32_t readPwmConfigBytes(); 629 | 630 | uint32_t constrain_(uint32_t value, uint32_t low, uint32_t high); 631 | }; 632 | 633 | #endif 634 | -------------------------------------------------------------------------------- /src/TMC2209/TMC2209.cpp: -------------------------------------------------------------------------------- 1 | // ---------------------------------------------------------------------------- 2 | // TMC2209.cpp 3 | // 4 | // Authors: 5 | // Peter Polidoro peter@polidoro.io 6 | // ---------------------------------------------------------------------------- 7 | #include "TMC2209.h" 8 | 9 | 10 | TMC2209::TMC2209() 11 | { 12 | hardware_serial_ptr_ = nullptr; 13 | #if SOFTWARE_SERIAL_INCLUDED 14 | software_serial_ptr_ = nullptr; 15 | #endif 16 | serial_baud_rate_ = 115200; 17 | serial_address_ = SERIAL_ADDRESS_0; 18 | hardware_enable_pin_ = -1; 19 | cool_step_enabled_ = false; 20 | } 21 | 22 | #if !defined(ARDUINO_ARCH_RENESAS) 23 | void TMC2209::setup(HardwareSerial & serial, 24 | long serial_baud_rate, 25 | SerialAddress serial_address) 26 | { 27 | hardware_serial_ptr_ = &serial; 28 | hardware_serial_ptr_->end(); 29 | hardware_serial_ptr_->begin(serial_baud_rate); 30 | 31 | initialize(serial_baud_rate, serial_address); 32 | } 33 | #endif 34 | #if defined(ESP32) 35 | void TMC2209::setup(HardwareSerial & serial, 36 | long serial_baud_rate, 37 | SerialAddress serial_address, 38 | int16_t alternate_rx_pin, 39 | int16_t alternate_tx_pin) 40 | { 41 | hardware_serial_ptr_ = &serial; 42 | if ((alternate_rx_pin < 0) || (alternate_tx_pin < 0)) 43 | { 44 | // hardware_serial_ptr_->end(); // Causes issues with some versions of ESP32 45 | hardware_serial_ptr_->begin(serial_baud_rate); 46 | } 47 | else 48 | { 49 | // hardware_serial_ptr_->end(); // Causes issues with some versions of ESP32 50 | hardware_serial_ptr_->begin(serial_baud_rate, SERIAL_8N1, alternate_rx_pin, alternate_tx_pin); 51 | } 52 | 53 | initialize(serial_baud_rate, serial_address); 54 | } 55 | #elif defined(ARDUINO_ARCH_RP2040) 56 | void TMC2209::setup(SerialUART & serial, 57 | long serial_baud_rate, 58 | SerialAddress serial_address, 59 | int16_t alternate_rx_pin, 60 | int16_t alternate_tx_pin) 61 | { 62 | hardware_serial_ptr_ = &serial; 63 | if ((alternate_rx_pin < 0) || (alternate_tx_pin < 0)) 64 | { 65 | serial.end(); 66 | serial.begin(serial_baud_rate); 67 | } 68 | else 69 | { 70 | hardware_serial_ptr_->end(); 71 | serial.setRX(alternate_rx_pin); 72 | serial.setTX(alternate_tx_pin); 73 | serial.begin(serial_baud_rate); 74 | } 75 | 76 | initialize(serial_baud_rate, serial_address); 77 | } 78 | #elif defined(ARDUINO_ARCH_RENESAS) 79 | void TMC2209::setup(UART & serial, 80 | long serial_baud_rate, 81 | SerialAddress serial_address) 82 | { 83 | hardware_serial_ptr_ = &serial; 84 | serial.end(); 85 | serial.begin(serial_baud_rate); 86 | 87 | initialize(serial_baud_rate, serial_address); 88 | } 89 | #endif 90 | 91 | #if SOFTWARE_SERIAL_INCLUDED 92 | void TMC2209::setup(SoftwareSerial & serial, 93 | long serial_baud_rate, 94 | SerialAddress serial_address) 95 | { 96 | software_serial_ptr_ = &serial; 97 | // software_serial_ptr_->end(); // Does not exist in some implementations 98 | software_serial_ptr_->begin(serial_baud_rate); 99 | 100 | initialize(serial_baud_rate, serial_address); 101 | } 102 | #endif 103 | 104 | // unidirectional methods 105 | 106 | void TMC2209::setHardwareEnablePin(uint8_t hardware_enable_pin) 107 | { 108 | hardware_enable_pin_ = hardware_enable_pin; 109 | pinMode(hardware_enable_pin_, OUTPUT); 110 | digitalWrite(hardware_enable_pin_, HIGH); 111 | } 112 | 113 | void TMC2209::enable() 114 | { 115 | if (hardware_enable_pin_ >= 0) 116 | { 117 | digitalWrite(hardware_enable_pin_, LOW); 118 | } 119 | chopper_config_.toff = toff_; 120 | writeStoredChopperConfig(); 121 | } 122 | 123 | void TMC2209::disable() 124 | { 125 | if (hardware_enable_pin_ >= 0) 126 | { 127 | digitalWrite(hardware_enable_pin_, HIGH); 128 | } 129 | chopper_config_.toff = TOFF_DISABLE; 130 | writeStoredChopperConfig(); 131 | } 132 | 133 | void TMC2209::setMicrostepsPerStep(uint16_t microsteps_per_step) 134 | { 135 | uint16_t microsteps_per_step_shifted = constrain_(microsteps_per_step, 136 | MICROSTEPS_PER_STEP_MIN, 137 | MICROSTEPS_PER_STEP_MAX); 138 | microsteps_per_step_shifted = microsteps_per_step >> 1; 139 | uint16_t exponent = 0; 140 | while (microsteps_per_step_shifted > 0) 141 | { 142 | microsteps_per_step_shifted = microsteps_per_step_shifted >> 1; 143 | ++exponent; 144 | } 145 | setMicrostepsPerStepPowerOfTwo(exponent); 146 | } 147 | 148 | void TMC2209::setMicrostepsPerStepPowerOfTwo(uint8_t exponent) 149 | { 150 | switch (exponent) 151 | { 152 | case 0: 153 | { 154 | chopper_config_.mres = MRES_001; 155 | break; 156 | } 157 | case 1: 158 | { 159 | chopper_config_.mres = MRES_002; 160 | break; 161 | } 162 | case 2: 163 | { 164 | chopper_config_.mres = MRES_004; 165 | break; 166 | } 167 | case 3: 168 | { 169 | chopper_config_.mres = MRES_008; 170 | break; 171 | } 172 | case 4: 173 | { 174 | chopper_config_.mres = MRES_016; 175 | break; 176 | } 177 | case 5: 178 | { 179 | chopper_config_.mres = MRES_032; 180 | break; 181 | } 182 | case 6: 183 | { 184 | chopper_config_.mres = MRES_064; 185 | break; 186 | } 187 | case 7: 188 | { 189 | chopper_config_.mres = MRES_128; 190 | break; 191 | } 192 | case 8: 193 | default: 194 | { 195 | chopper_config_.mres = MRES_256; 196 | break; 197 | } 198 | } 199 | writeStoredChopperConfig(); 200 | } 201 | 202 | void TMC2209::setRunCurrent(uint8_t percent) 203 | { 204 | uint8_t run_current = percentToCurrentSetting(percent); 205 | driver_current_.irun = run_current; 206 | writeStoredDriverCurrent(); 207 | } 208 | 209 | void TMC2209::setHoldCurrent(uint8_t percent) 210 | { 211 | uint8_t hold_current = percentToCurrentSetting(percent); 212 | 213 | driver_current_.ihold = hold_current; 214 | writeStoredDriverCurrent(); 215 | } 216 | 217 | void TMC2209::setHoldDelay(uint8_t percent) 218 | { 219 | uint8_t hold_delay = percentToHoldDelaySetting(percent); 220 | 221 | driver_current_.iholddelay = hold_delay; 222 | writeStoredDriverCurrent(); 223 | } 224 | 225 | void TMC2209::setAllCurrentValues(uint8_t run_current_percent, 226 | uint8_t hold_current_percent, 227 | uint8_t hold_delay_percent) 228 | { 229 | uint8_t run_current = percentToCurrentSetting(run_current_percent); 230 | uint8_t hold_current = percentToCurrentSetting(hold_current_percent); 231 | uint8_t hold_delay = percentToHoldDelaySetting(hold_delay_percent); 232 | 233 | driver_current_.irun = run_current; 234 | driver_current_.ihold = hold_current; 235 | driver_current_.iholddelay = hold_delay; 236 | writeStoredDriverCurrent(); 237 | } 238 | 239 | void TMC2209::setRMSCurrent(uint16_t mA, 240 | float rSense, 241 | float holdMultiplier) 242 | { 243 | // Taken from https://github.com/teemuatlut/TMCStepper/blob/74e8e6881adc9241c2e626071e7328d7652f361a/src/source/TMCStepper.cpp#L41. 244 | 245 | uint8_t CS = 32.0*1.41421*mA/1000.0*(rSense+0.02)/0.325 - 1; 246 | // If Current Scale is too low, turn on high sensitivity R_sense and calculate again 247 | if (CS < 16) { 248 | enableVSense(); 249 | CS = 32.0*1.41421*mA/1000.0*(rSense+0.02)/0.180 - 1; 250 | } else { // If CS >= 16, turn off high_sense_r 251 | disableVSense(); 252 | } 253 | 254 | if (CS > 31) { 255 | CS = 31; 256 | } 257 | 258 | driver_current_.irun = CS; 259 | driver_current_.ihold = CS*holdMultiplier; 260 | writeStoredDriverCurrent(); 261 | } 262 | 263 | void TMC2209::enableDoubleEdge() 264 | { 265 | chopper_config_.double_edge = DOUBLE_EDGE_ENABLE; 266 | writeStoredChopperConfig(); 267 | } 268 | 269 | void TMC2209::disableDoubleEdge() 270 | { 271 | chopper_config_.double_edge = DOUBLE_EDGE_DISABLE; 272 | writeStoredChopperConfig(); 273 | } 274 | 275 | void TMC2209::enableVSense() 276 | { 277 | chopper_config_.vsense = VSENSE_ENABLE; 278 | writeStoredChopperConfig(); 279 | } 280 | 281 | void TMC2209::disableVSense() 282 | { 283 | chopper_config_.vsense = VSENSE_DISABLE; 284 | writeStoredChopperConfig(); 285 | } 286 | 287 | void TMC2209::enableInverseMotorDirection() 288 | { 289 | global_config_.shaft = 1; 290 | writeStoredGlobalConfig(); 291 | } 292 | 293 | void TMC2209::disableInverseMotorDirection() 294 | { 295 | global_config_.shaft = 0; 296 | writeStoredGlobalConfig(); 297 | } 298 | 299 | void TMC2209::setStandstillMode(TMC2209::StandstillMode mode) 300 | { 301 | pwm_config_.freewheel = mode; 302 | writeStoredPwmConfig(); 303 | } 304 | 305 | void TMC2209::enableAutomaticCurrentScaling() 306 | { 307 | pwm_config_.pwm_autoscale = STEPPER_DRIVER_FEATURE_ON; 308 | writeStoredPwmConfig(); 309 | } 310 | 311 | void TMC2209::disableAutomaticCurrentScaling() 312 | { 313 | pwm_config_.pwm_autoscale = STEPPER_DRIVER_FEATURE_OFF; 314 | writeStoredPwmConfig(); 315 | } 316 | 317 | void TMC2209::enableAutomaticGradientAdaptation() 318 | { 319 | pwm_config_.pwm_autograd = STEPPER_DRIVER_FEATURE_ON; 320 | writeStoredPwmConfig(); 321 | } 322 | 323 | void TMC2209::disableAutomaticGradientAdaptation() 324 | { 325 | pwm_config_.pwm_autograd = STEPPER_DRIVER_FEATURE_OFF; 326 | writeStoredPwmConfig(); 327 | } 328 | 329 | void TMC2209::setPwmOffset(uint8_t pwm_amplitude) 330 | { 331 | pwm_config_.pwm_offset = pwm_amplitude; 332 | writeStoredPwmConfig(); 333 | } 334 | 335 | void TMC2209::setPwmGradient(uint8_t pwm_amplitude) 336 | { 337 | pwm_config_.pwm_grad = pwm_amplitude; 338 | writeStoredPwmConfig(); 339 | } 340 | 341 | void TMC2209::setPowerDownDelay(uint8_t power_down_delay) 342 | { 343 | write(ADDRESS_TPOWERDOWN, power_down_delay); 344 | } 345 | 346 | void TMC2209::setReplyDelay(uint8_t reply_delay) 347 | { 348 | if (reply_delay > REPLY_DELAY_MAX) 349 | { 350 | reply_delay = REPLY_DELAY_MAX; 351 | } 352 | ReplyDelay reply_delay_data; 353 | reply_delay_data.bytes = 0; 354 | reply_delay_data.replydelay = reply_delay; 355 | write(ADDRESS_REPLYDELAY, reply_delay_data.bytes); 356 | } 357 | 358 | void TMC2209::moveAtVelocity(int32_t microsteps_per_period) 359 | { 360 | write(ADDRESS_VACTUAL, microsteps_per_period); 361 | } 362 | 363 | void TMC2209::moveUsingStepDirInterface() 364 | { 365 | write(ADDRESS_VACTUAL, VACTUAL_STEP_DIR_INTERFACE); 366 | } 367 | 368 | void TMC2209::enableStealthChop() 369 | { 370 | global_config_.enable_spread_cycle = 0; 371 | writeStoredGlobalConfig(); 372 | } 373 | 374 | void TMC2209::disableStealthChop() 375 | { 376 | global_config_.enable_spread_cycle = 1; 377 | writeStoredGlobalConfig(); 378 | } 379 | 380 | void TMC2209::setCoolStepDurationThreshold(uint32_t duration_threshold) 381 | { 382 | write(ADDRESS_TCOOLTHRS, duration_threshold); 383 | } 384 | 385 | void TMC2209::setStealthChopDurationThreshold(uint32_t duration_threshold) 386 | { 387 | write(ADDRESS_TPWMTHRS, duration_threshold); 388 | } 389 | 390 | void TMC2209::setStallGuardThreshold(uint8_t stall_guard_threshold) 391 | { 392 | write(ADDRESS_SGTHRS, stall_guard_threshold); 393 | } 394 | 395 | void TMC2209::enableCoolStep(uint8_t lower_threshold, 396 | uint8_t upper_threshold) 397 | { 398 | lower_threshold = constrain_(lower_threshold, SEMIN_MIN, SEMIN_MAX); 399 | cool_config_.semin = lower_threshold; 400 | upper_threshold = constrain_(upper_threshold, SEMAX_MIN, SEMAX_MAX); 401 | cool_config_.semax = upper_threshold; 402 | write(ADDRESS_COOLCONF, cool_config_.bytes); 403 | cool_step_enabled_ = true; 404 | } 405 | 406 | void TMC2209::disableCoolStep() 407 | { 408 | cool_config_.semin = SEMIN_OFF; 409 | write(ADDRESS_COOLCONF, cool_config_.bytes); 410 | cool_step_enabled_ = false; 411 | } 412 | 413 | void TMC2209::setCoolStepCurrentIncrement(CurrentIncrement current_increment) 414 | { 415 | cool_config_.seup = current_increment; 416 | write(ADDRESS_COOLCONF, cool_config_.bytes); 417 | } 418 | 419 | void TMC2209::setCoolStepMeasurementCount(MeasurementCount measurement_count) 420 | { 421 | cool_config_.sedn = measurement_count; 422 | write(ADDRESS_COOLCONF, cool_config_.bytes); 423 | } 424 | 425 | void TMC2209::enableAnalogCurrentScaling() 426 | { 427 | global_config_.i_scale_analog = 1; 428 | writeStoredGlobalConfig(); 429 | } 430 | 431 | void TMC2209::disableAnalogCurrentScaling() 432 | { 433 | global_config_.i_scale_analog = 0; 434 | writeStoredGlobalConfig(); 435 | } 436 | 437 | void TMC2209::useExternalSenseResistors() 438 | { 439 | global_config_.internal_rsense = 0; 440 | writeStoredGlobalConfig(); 441 | } 442 | 443 | void TMC2209::useInternalSenseResistors() 444 | { 445 | global_config_.internal_rsense = 1; 446 | writeStoredGlobalConfig(); 447 | } 448 | 449 | // bidirectional methods 450 | 451 | uint8_t TMC2209::getVersion() 452 | { 453 | Input input; 454 | input.bytes = read(ADDRESS_IOIN); 455 | 456 | return input.version; 457 | } 458 | 459 | bool TMC2209::isCommunicating() 460 | { 461 | return (getVersion() == VERSION); 462 | } 463 | 464 | bool TMC2209::isSetupAndCommunicating() 465 | { 466 | return serialOperationMode(); 467 | } 468 | 469 | bool TMC2209::isCommunicatingButNotSetup() 470 | { 471 | return (isCommunicating() && (not isSetupAndCommunicating())); 472 | } 473 | 474 | bool TMC2209::hardwareDisabled() 475 | { 476 | Input input; 477 | input.bytes = read(ADDRESS_IOIN); 478 | 479 | return input.enn; 480 | } 481 | 482 | uint16_t TMC2209::getMicrostepsPerStep() 483 | { 484 | uint16_t microsteps_per_step_exponent; 485 | switch (chopper_config_.mres) 486 | { 487 | case MRES_001: 488 | { 489 | microsteps_per_step_exponent = 0; 490 | break; 491 | } 492 | case MRES_002: 493 | { 494 | microsteps_per_step_exponent = 1; 495 | break; 496 | } 497 | case MRES_004: 498 | { 499 | microsteps_per_step_exponent = 2; 500 | break; 501 | } 502 | case MRES_008: 503 | { 504 | microsteps_per_step_exponent = 3; 505 | break; 506 | } 507 | case MRES_016: 508 | { 509 | microsteps_per_step_exponent = 4; 510 | break; 511 | } 512 | case MRES_032: 513 | { 514 | microsteps_per_step_exponent = 5; 515 | break; 516 | } 517 | case MRES_064: 518 | { 519 | microsteps_per_step_exponent = 6; 520 | break; 521 | } 522 | case MRES_128: 523 | { 524 | microsteps_per_step_exponent = 7; 525 | break; 526 | } 527 | case MRES_256: 528 | default: 529 | { 530 | microsteps_per_step_exponent = 8; 531 | break; 532 | } 533 | } 534 | return 1 << microsteps_per_step_exponent; 535 | } 536 | 537 | TMC2209::Settings TMC2209::getSettings() 538 | { 539 | Settings settings; 540 | settings.is_communicating = isCommunicating(); 541 | 542 | if (settings.is_communicating) 543 | { 544 | readAndStoreRegisters(); 545 | 546 | settings.is_setup = global_config_.pdn_disable; 547 | settings.software_enabled = (chopper_config_.toff > TOFF_DISABLE); 548 | settings.microsteps_per_step = getMicrostepsPerStep(); 549 | settings.inverse_motor_direction_enabled = global_config_.shaft; 550 | settings.stealth_chop_enabled = not global_config_.enable_spread_cycle; 551 | settings.standstill_mode = pwm_config_.freewheel; 552 | settings.irun_percent = currentSettingToPercent(driver_current_.irun); 553 | settings.irun_register_value = driver_current_.irun; 554 | settings.ihold_percent = currentSettingToPercent(driver_current_.ihold); 555 | settings.ihold_register_value = driver_current_.ihold; 556 | settings.iholddelay_percent = holdDelaySettingToPercent(driver_current_.iholddelay); 557 | settings.iholddelay_register_value = driver_current_.iholddelay; 558 | settings.automatic_current_scaling_enabled = pwm_config_.pwm_autoscale; 559 | settings.automatic_gradient_adaptation_enabled = pwm_config_.pwm_autograd; 560 | settings.pwm_offset = pwm_config_.pwm_offset; 561 | settings.pwm_gradient = pwm_config_.pwm_grad; 562 | settings.cool_step_enabled = cool_step_enabled_; 563 | settings.analog_current_scaling_enabled = global_config_.i_scale_analog; 564 | settings.internal_sense_resistors_enabled = global_config_.internal_rsense; 565 | } 566 | else 567 | { 568 | settings.is_setup = false; 569 | settings.software_enabled = false; 570 | settings.microsteps_per_step = 0; 571 | settings.inverse_motor_direction_enabled = false; 572 | settings.stealth_chop_enabled = false; 573 | settings.standstill_mode = pwm_config_.freewheel; 574 | settings.irun_percent = 0; 575 | settings.irun_register_value = 0; 576 | settings.ihold_percent = 0; 577 | settings.ihold_register_value = 0; 578 | settings.iholddelay_percent = 0; 579 | settings.iholddelay_register_value = 0; 580 | settings.automatic_current_scaling_enabled = false; 581 | settings.automatic_gradient_adaptation_enabled = false; 582 | settings.pwm_offset = 0; 583 | settings.pwm_gradient = 0; 584 | settings.cool_step_enabled = false; 585 | settings.analog_current_scaling_enabled = false; 586 | settings.internal_sense_resistors_enabled = false; 587 | } 588 | 589 | return settings; 590 | } 591 | 592 | TMC2209::Status TMC2209::getStatus() 593 | { 594 | DriveStatus drive_status; 595 | drive_status.bytes = 0; 596 | drive_status.bytes = read(ADDRESS_DRV_STATUS); 597 | return drive_status.status; 598 | } 599 | 600 | TMC2209::GlobalStatus TMC2209::getGlobalStatus() 601 | { 602 | GlobalStatusUnion global_status_union; 603 | global_status_union.bytes = 0; 604 | global_status_union.bytes = read(ADDRESS_GSTAT); 605 | return global_status_union.global_status; 606 | } 607 | 608 | void TMC2209::clearReset() 609 | { 610 | GlobalStatusUnion global_status_union; 611 | global_status_union.bytes = 0; 612 | global_status_union.global_status.reset = 1; 613 | write(ADDRESS_GSTAT, global_status_union.bytes); 614 | } 615 | 616 | void TMC2209::clearDriveError() 617 | { 618 | GlobalStatusUnion global_status_union; 619 | global_status_union.bytes = 0; 620 | global_status_union.global_status.drv_err = 1; 621 | write(ADDRESS_GSTAT, global_status_union.bytes); 622 | } 623 | 624 | uint8_t TMC2209::getInterfaceTransmissionCounter() 625 | { 626 | return read(ADDRESS_IFCNT); 627 | } 628 | 629 | uint32_t TMC2209::getInterstepDuration() 630 | { 631 | return read(ADDRESS_TSTEP); 632 | } 633 | 634 | uint16_t TMC2209::getStallGuardResult() 635 | { 636 | return read(ADDRESS_SG_RESULT); 637 | } 638 | 639 | uint8_t TMC2209::getPwmScaleSum() 640 | { 641 | PwmScale pwm_scale; 642 | pwm_scale.bytes = read(ADDRESS_PWM_SCALE); 643 | 644 | return pwm_scale.pwm_scale_sum; 645 | } 646 | 647 | int16_t TMC2209::getPwmScaleAuto() 648 | { 649 | PwmScale pwm_scale; 650 | pwm_scale.bytes = read(ADDRESS_PWM_SCALE); 651 | 652 | return pwm_scale.pwm_scale_auto; 653 | } 654 | 655 | uint8_t TMC2209::getPwmOffsetAuto() 656 | { 657 | PwmAuto pwm_auto; 658 | pwm_auto.bytes = read(ADDRESS_PWM_AUTO); 659 | 660 | return pwm_auto.pwm_offset_auto; 661 | } 662 | 663 | uint8_t TMC2209::getPwmGradientAuto() 664 | { 665 | PwmAuto pwm_auto; 666 | pwm_auto.bytes = read(ADDRESS_PWM_AUTO); 667 | 668 | return pwm_auto.pwm_gradient_auto; 669 | } 670 | 671 | uint16_t TMC2209::getMicrostepCounter() 672 | { 673 | return read(ADDRESS_MSCNT); 674 | } 675 | 676 | // private 677 | void TMC2209::initialize(long serial_baud_rate, 678 | SerialAddress serial_address) 679 | { 680 | serial_baud_rate_ = serial_baud_rate; 681 | 682 | setOperationModeToSerial(serial_address); 683 | setRegistersToDefaults(); 684 | clearDriveError(); 685 | 686 | minimizeMotorCurrent(); 687 | disable(); 688 | disableAutomaticCurrentScaling(); 689 | disableAutomaticGradientAdaptation(); 690 | } 691 | 692 | int TMC2209::serialAvailable() 693 | { 694 | if (hardware_serial_ptr_ != nullptr) 695 | { 696 | return hardware_serial_ptr_->available(); 697 | } 698 | #if SOFTWARE_SERIAL_INCLUDED 699 | else if (software_serial_ptr_ != nullptr) 700 | { 701 | return software_serial_ptr_->available(); 702 | } 703 | #endif 704 | return 0; 705 | } 706 | 707 | size_t TMC2209::serialWrite(uint8_t c) 708 | { 709 | if (hardware_serial_ptr_ != nullptr) 710 | { 711 | return hardware_serial_ptr_->write(c); 712 | } 713 | #if SOFTWARE_SERIAL_INCLUDED 714 | else if (software_serial_ptr_ != nullptr) 715 | { 716 | return software_serial_ptr_->write(c); 717 | } 718 | #endif 719 | return 0; 720 | } 721 | 722 | int TMC2209::serialRead() 723 | { 724 | if (hardware_serial_ptr_ != nullptr) 725 | { 726 | return hardware_serial_ptr_->read(); 727 | } 728 | #if SOFTWARE_SERIAL_INCLUDED 729 | else if (software_serial_ptr_ != nullptr) 730 | { 731 | return software_serial_ptr_->read(); 732 | } 733 | #endif 734 | return 0; 735 | } 736 | 737 | void TMC2209::serialFlush() 738 | { 739 | if (hardware_serial_ptr_ != nullptr) 740 | { 741 | return hardware_serial_ptr_->flush(); 742 | } 743 | } 744 | 745 | void TMC2209::setOperationModeToSerial(SerialAddress serial_address) 746 | { 747 | serial_address_ = serial_address; 748 | 749 | global_config_.bytes = 0; 750 | global_config_.i_scale_analog = 0; 751 | global_config_.pdn_disable = 1; 752 | global_config_.mstep_reg_select = 1; 753 | global_config_.multistep_filt = 1; 754 | 755 | writeStoredGlobalConfig(); 756 | } 757 | 758 | void TMC2209::setRegistersToDefaults() 759 | { 760 | driver_current_.bytes = 0; 761 | driver_current_.ihold = IHOLD_DEFAULT; 762 | driver_current_.irun = IRUN_DEFAULT; 763 | driver_current_.iholddelay = IHOLDDELAY_DEFAULT; 764 | write(ADDRESS_IHOLD_IRUN, driver_current_.bytes); 765 | 766 | chopper_config_.bytes = CHOPPER_CONFIG_DEFAULT; 767 | chopper_config_.tbl = TBL_DEFAULT; 768 | chopper_config_.hend = HEND_DEFAULT; 769 | chopper_config_.hstart = HSTART_DEFAULT; 770 | chopper_config_.toff = TOFF_DEFAULT; 771 | write(ADDRESS_CHOPCONF, chopper_config_.bytes); 772 | 773 | pwm_config_.bytes = PWM_CONFIG_DEFAULT; 774 | write(ADDRESS_PWMCONF, pwm_config_.bytes); 775 | 776 | cool_config_.bytes = COOLCONF_DEFAULT; 777 | write(ADDRESS_COOLCONF, cool_config_.bytes); 778 | 779 | write(ADDRESS_TPOWERDOWN, TPOWERDOWN_DEFAULT); 780 | write(ADDRESS_TPWMTHRS, TPWMTHRS_DEFAULT); 781 | write(ADDRESS_VACTUAL, VACTUAL_DEFAULT); 782 | write(ADDRESS_TCOOLTHRS, TCOOLTHRS_DEFAULT); 783 | write(ADDRESS_SGTHRS, SGTHRS_DEFAULT); 784 | write(ADDRESS_COOLCONF, COOLCONF_DEFAULT); 785 | } 786 | 787 | void TMC2209::readAndStoreRegisters() 788 | { 789 | global_config_.bytes = readGlobalConfigBytes(); 790 | chopper_config_.bytes = readChopperConfigBytes(); 791 | pwm_config_.bytes = readPwmConfigBytes(); 792 | } 793 | 794 | bool TMC2209::serialOperationMode() 795 | { 796 | GlobalConfig global_config; 797 | global_config.bytes = readGlobalConfigBytes(); 798 | 799 | return global_config.pdn_disable; 800 | } 801 | 802 | void TMC2209::minimizeMotorCurrent() 803 | { 804 | driver_current_.irun = CURRENT_SETTING_MIN; 805 | driver_current_.ihold = CURRENT_SETTING_MIN; 806 | writeStoredDriverCurrent(); 807 | } 808 | 809 | uint32_t TMC2209::reverseData(uint32_t data) 810 | { 811 | uint32_t reversed_data = 0; 812 | uint8_t right_shift; 813 | uint8_t left_shift; 814 | for (uint8_t i=0; i> right_shift) & BYTE_MAX_VALUE) << left_shift; 819 | } 820 | return reversed_data; 821 | } 822 | 823 | template 824 | uint8_t TMC2209::calculateCrc(Datagram & datagram, 825 | uint8_t datagram_size) 826 | { 827 | uint8_t crc = 0; 828 | uint8_t byte; 829 | for (uint8_t i=0; i<(datagram_size - 1); ++i) 830 | { 831 | byte = (datagram.bytes >> (i * BITS_PER_BYTE)) & BYTE_MAX_VALUE; 832 | for (uint8_t j=0; j> 7) ^ (byte & 0x01)) 835 | { 836 | crc = (crc << 1) ^ 0x07; 837 | } 838 | else 839 | { 840 | crc = crc << 1; 841 | } 842 | byte = byte >> 1; 843 | } 844 | } 845 | return crc; 846 | } 847 | 848 | template 849 | void TMC2209::sendDatagramUnidirectional(Datagram & datagram, 850 | uint8_t datagram_size) 851 | { 852 | uint8_t byte; 853 | 854 | for (uint8_t i=0; i> (i * BITS_PER_BYTE)) & BYTE_MAX_VALUE; 857 | serialWrite(byte); 858 | } 859 | } 860 | 861 | template 862 | void TMC2209::sendDatagramBidirectional(Datagram & datagram, 863 | uint8_t datagram_size) 864 | { 865 | uint8_t byte; 866 | 867 | // Wait for the transmission of outgoing serial data to complete 868 | serialFlush(); 869 | 870 | // clear the serial receive buffer if necessary 871 | while (serialAvailable() > 0) 872 | { 873 | byte = serialRead(); 874 | } 875 | 876 | // write datagram 877 | for (uint8_t i=0; i> (i * BITS_PER_BYTE)) & BYTE_MAX_VALUE; 880 | serialWrite(byte); 881 | } 882 | 883 | // Wait for the transmission of outgoing serial data to complete 884 | serialFlush(); 885 | 886 | // wait for bytes sent out on TX line to be echoed on RX line 887 | uint32_t echo_delay = 0; 888 | while ((serialAvailable() < datagram_size) and 889 | (echo_delay < ECHO_DELAY_MAX_MICROSECONDS)) 890 | { 891 | delayMicroseconds(ECHO_DELAY_INC_MICROSECONDS); 892 | echo_delay += ECHO_DELAY_INC_MICROSECONDS; 893 | } 894 | 895 | if (echo_delay >= ECHO_DELAY_MAX_MICROSECONDS) 896 | { 897 | return; 898 | } 899 | 900 | // clear RX buffer of echo bytes 901 | for (uint8_t i=0; i= REPLY_DELAY_MAX_MICROSECONDS) 945 | { 946 | return 0; 947 | } 948 | 949 | uint64_t byte; 950 | uint8_t byte_count = 0; 951 | WriteReadReplyDatagram read_reply_datagram; 952 | read_reply_datagram.bytes = 0; 953 | for (uint8_t i=0; i= SEIMIN_UPPER_CURRENT_LIMIT) 1032 | { 1033 | cool_config_.seimin = SEIMIN_UPPER_SETTING; 1034 | } 1035 | else 1036 | { 1037 | cool_config_.seimin = SEIMIN_LOWER_SETTING; 1038 | } 1039 | if (cool_step_enabled_) 1040 | { 1041 | write(ADDRESS_COOLCONF, cool_config_.bytes); 1042 | } 1043 | } 1044 | 1045 | void TMC2209::writeStoredChopperConfig() 1046 | { 1047 | write(ADDRESS_CHOPCONF, chopper_config_.bytes); 1048 | } 1049 | 1050 | uint32_t TMC2209::readChopperConfigBytes() 1051 | { 1052 | return read(ADDRESS_CHOPCONF); 1053 | } 1054 | 1055 | void TMC2209::writeStoredPwmConfig() 1056 | { 1057 | write(ADDRESS_PWMCONF, pwm_config_.bytes); 1058 | } 1059 | 1060 | uint32_t TMC2209::readPwmConfigBytes() 1061 | { 1062 | return read(ADDRESS_PWMCONF); 1063 | } 1064 | 1065 | uint32_t TMC2209::constrain_(uint32_t value, uint32_t low, uint32_t high) 1066 | { 1067 | return ((value)<(low)?(low):((value)>(high)?(high):(value))); 1068 | } 1069 | --------------------------------------------------------------------------------