├── .gitignore ├── LICENSE.txt ├── README.md ├── TMCL ├── __init__.py ├── bus.py ├── commands.py ├── motor.py └── reply.py ├── dist └── TMCL-1.0.tar.gz ├── examples └── example1.py ├── setup.cfg └── setup.py /.gitignore: -------------------------------------------------------------------------------- 1 | *.egg-info 2 | *.pyc 3 | /.idea 4 | /.venv 5 | /dist 6 | /build 7 | -------------------------------------------------------------------------------- /LICENSE.txt: -------------------------------------------------------------------------------- 1 | Copyright 2017 Native Design Ltd 2 | 3 | Permission is hereby granted, free of charge, to any person 4 | obtaining a copy of this software and associated documentation 5 | files (the "Software"), to deal in the Software without 6 | restriction, including without limitation the rights to use, 7 | copy, modify, merge, publish, distribute, sublicense, and/or 8 | sell copies of the Software, and to permit persons to whom 9 | the Software is furnished to do so, subject to the following 10 | conditions: 11 | 12 | The above copyright notice and this permission notice shall be 13 | included in all copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, 16 | EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES 17 | OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND 18 | NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT 19 | HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, 20 | WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING 21 | FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR 22 | OTHER DEALINGS IN THE SOFTWARE. 23 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | Python TMCL client library 2 | ========================== 3 | 4 | Python wrapper around Trinamic's TMCL serial interface for controlling TMCM stepper modules 5 | via a serial-to-rs485 converter. 6 | 7 | 8 | 9 | Installation 10 | ------------ 11 | 12 | ### Install using pip 13 | ```sh 14 | > pip install tmcl 15 | ``` 16 | 17 | ### Install without pip 18 | ```sh 19 | > git clone https://github.com/NativeDesign/python-tmcl.git 20 | > cd python-tmcl 21 | > python setup.py install 22 | ``` 23 | 24 | 25 | Usage 26 | ----- 27 | 28 | Use an RS485-to-serial adapter to connect your PC to one or more TMCM modules. 29 | Before starting you should check the modules' serial-address and baud-rate is 30 | a known value. Out of the box (_warning: anecdotal_) modules usually have an address 31 | of `1` and a baud-rate of `9600` but this is not guarenteed. The easiest way to check 32 | these values is by using the [TMCL IDE][1] on a windows machine. 33 | 34 | If using multiple TMCM modules attached to the same rs485 bus you __must__ ensure that 35 | each module is set to a _different_ serial-address so that they don't clash. 36 | 37 | 38 | ### Example usage (single-axis modules) 39 | ```python 40 | from serial import Serial 41 | from time import sleep 42 | import TMCL 43 | 44 | ## serial-address as set on the TMCM module. 45 | MODULE_ADDRESS = 1 46 | 47 | ## Open the serial port presented by your rs485 adapter 48 | serial_port = Serial("/dev/tty.usbmodem1241") 49 | 50 | ## Create a Bus instance using the open serial port 51 | bus = TMCL.connect(serial_port) 52 | 53 | ## Get the motor 54 | motor = bus.get_motor(MODULE_ADDRESS) 55 | 56 | ## From this point you can start issuing TMCL commands 57 | ## to the motor as per the TMCL docs. This example will 58 | ## rotate the motor left at a speed of 1234 for 2 seconds 59 | motor.rotate_left(1234) 60 | sleep(2) 61 | motor.stop() 62 | ``` 63 | 64 | 65 | ### Example usage (multi-axis modules) 66 | ```python 67 | from serial import Serial 68 | import TMCL 69 | 70 | ## Open the serial port presented by your rs485 adapter 71 | serial_port = Serial("/dev/tty.usbmodem1241") 72 | 73 | ## Create a Bus instance using the open serial port 74 | bus = TMCL.connect(serial_port) 75 | 76 | ## Get the motor on axis 0 of module with address 1 77 | module = bus.get_module( 1 ) 78 | 79 | a0 = module.get_motor(0) 80 | a1 = module.get_motor(1) 81 | a2 = module.get_motor(2) 82 | 83 | ``` 84 | 85 | 86 | 87 | 88 | API Overview 89 | ------------ 90 | 91 | 92 | #### class Motor (bus, address, axis) 93 | 94 | ##### `move_absolute (position)` 95 | Move the motor to the specified _absolute_ position. 96 | 97 | ##### `move_relative (offset)` 98 | Move the motor by the specified offset _relative to current position_. 99 | 100 | ##### `reference_search (rfs_type)` 101 | Start a reference search routine to locate limit switches. 102 | 103 | ##### `rotate_left (velocity)` 104 | Rotate the motor left-wards at the specified velocity. 105 | 106 | ##### `rotate_right (velocity)` 107 | Rotate the motor right-wards at the specified velocity. 108 | 109 | ##### `run_command (cmd)` 110 | Execute a predefined user subroutine written to TMCM module firmware 111 | 112 | ##### `send (cmd, type, motorbank, value)` 113 | Send a raw TMCL command to the motor. 114 | 115 | ##### `stop ()` 116 | Stop the motor 117 | 118 | 119 | [1]: https://www.trinamic.com/support/software/tmcl-ide/ 120 | -------------------------------------------------------------------------------- /TMCL/__init__.py: -------------------------------------------------------------------------------- 1 | from .bus import Bus 2 | from .motor import Motor 3 | from .commands import Command 4 | from .reply import Reply 5 | 6 | def connect ( serial_port, CAN = False ): 7 | return Bus(serial_port, CAN) 8 | -------------------------------------------------------------------------------- /TMCL/bus.py: -------------------------------------------------------------------------------- 1 | import struct 2 | from .motor import Module, Motor 3 | from .reply import Reply, TrinamicException 4 | 5 | 6 | # MSG_STRUCTURE = ">BBBBIB" 7 | MSG_STRUCTURE = ">BBBBiB" 8 | MSG_STRUCTURE_CAN = ">BBBI" 9 | 10 | # REPLY_STRUCTURE = ">BBBBIB" 11 | REPLY_STRUCTURE = ">BBBBiB" 12 | REPLY_STRUCTURE_CAN = ">BBBI" 13 | REPLY_STRUCTURE_IIC = ">BBBIB" 14 | 15 | REPLY_LENGTH = 9 16 | REPLY_LENGTH_CAN = 7 17 | REPLY_LENGTH_IIC = 8 18 | 19 | 20 | class Bus (object): 21 | 22 | def __init__( self, serial, CAN = False ): 23 | self.CAN = CAN 24 | self.serial = serial 25 | 26 | def send ( self, address, command, type, motorbank, value ): 27 | """ 28 | Send a message to the specified module. 29 | This is a blocking function that will not return until a reply 30 | has been received from the module. 31 | 32 | See the TMCL docs for full descriptions of the parameters 33 | 34 | :param address: Module address to send command to 35 | :param command: Instruction no 36 | :param type: Type 37 | :param motorbank: Mot/Bank 38 | :param value: Value 39 | 40 | :rtype: Reply 41 | """ 42 | if self.CAN: 43 | msg = struct.pack(MSG_STRUCTURE_CAN, command, type, motorbank,value) 44 | self.serial.write(msg) 45 | resp = [0] 46 | data = self.serial.read(REPLY_LENGTH_CAN) 47 | resp.extend(struct.unpack(REPLY_STRUCTURE_CAN, data)) 48 | reply = Reply(resp) 49 | return self._handle_reply(reply) 50 | else: 51 | checksum = self._binaryadd(address, command, type, motorbank, value) 52 | msg = struct.pack(MSG_STRUCTURE, address, command, type, motorbank, value, checksum) 53 | self.serial.write(msg) 54 | rep = self.serial.read(REPLY_LENGTH) 55 | reply = Reply(struct.unpack(REPLY_STRUCTURE, rep)) 56 | return self._handle_reply(reply) 57 | 58 | def get_module( self, address=1 ): 59 | """ 60 | Returns a Module object targeting the device at address `address` 61 | You can use this object to retrieve one or more axis motors. 62 | 63 | :param address: 64 | Bus address to the target TMCM module 65 | :type address: int 66 | 67 | :rtype: Module 68 | """ 69 | return Module(self, address) 70 | 71 | def get_motor( self, address=1, motor_id=0 ): 72 | """ 73 | Returns object addressing motor number `motor_id` on module `address`. 74 | `address` defaults to 1 (doc for TMCM310 starts counting addresses at 1). 75 | `motor_id` defaults to 0 (1st axis). 76 | 77 | This is an alias for `get_module(address).get_motor(motor_id)` so that 78 | backward-compatibility with v1.1.1 is maintained. 79 | 80 | :param address: 81 | Bus address of the target TMCM module 82 | :type address: int 83 | 84 | :param motor_id: 85 | ID of the motor/axis to target 86 | :type motor_id: int 87 | 88 | :rtype: Motor 89 | """ 90 | return Motor(self, address, motor_id) 91 | 92 | def _handle_reply (self, reply): 93 | if reply.status < Reply.Status.SUCCESS: 94 | raise TrinamicException(reply) 95 | return reply 96 | 97 | def _binaryadd( self, address, command, type, motorbank, value ): 98 | checksum_struct = struct.pack(MSG_STRUCTURE[:-1], address, command, type, motorbank, value) 99 | checksum = 0 100 | for s in checksum_struct: 101 | checksum += int(s) % 256 102 | checksum = checksum % 256 103 | return checksum 104 | 105 | 106 | -------------------------------------------------------------------------------- /TMCL/commands.py: -------------------------------------------------------------------------------- 1 | class Command: 2 | ROL = 2 # Rotate left 3 | ROR = 1 # Rotate right 4 | MVP = 4 # Move to position 5 | MST = 3 # Motor stop 6 | RFS = 13 # Reference search 7 | SCO = 30 # Store coordinate 8 | CCO = 32 # Capture coordinate 9 | GCO = 31 # Get coordinate 10 | SAP = 5 # Set axis parameter 11 | GAP = 6 # Get axis parameter 12 | STAP = 7 # Store axis parameter into EEPROM 13 | RSAP = 8 # Restors axis parameter from EEPROM 14 | SGP = 9 # Set global parameter 15 | GGP = 10 # Get global parameter 16 | STGP = 11 # Store global parameter into EEPROM 17 | RSGP = 12 # Restore global parameter from EEPROM 18 | SIO = 14 # Set output 19 | GIO = 15 # Get input 20 | SAC = 29 # Access to external SPI device 21 | JA = 22 # Jump always 22 | JC = 21 # Jump conditional 23 | COMP = 20 # Compare accumulator with constant value 24 | CLE = 36 # Clear error flags 25 | CSUB = 23 # Call subroutine 26 | RSUB = 24 # Return from subroutine 27 | WAIT = 27 # Wait for a specified event 28 | STOP = 28 # End of a TMCL program 29 | CALC = 19 # Calculate using the accumulator and a constant value 30 | CALCX = 33 # Calculate using the accumulator and the X register 31 | AAP = 34 # Copy accumulator to an axis parameter 32 | AGP = 35 # Copy accumulator to a global parameter 33 | STOP_APPLICATION = 128 34 | RUN_APPLICATION = 129 35 | STEP_APPLICATION = 130 36 | RESET_APPLICATION = 131 37 | START_DOWNLOAD_MODE = 132 38 | QUIT_DOWNLOAD_MODE = 133 39 | READ_TMCL_MEMORY = 134 40 | GET_APPLICATION_STATUS = 135 41 | GET_FIRMWARE_VERSION = 136 42 | RESTORE_FACTORY_SETTINGS = 137 43 | -------------------------------------------------------------------------------- /TMCL/motor.py: -------------------------------------------------------------------------------- 1 | from .commands import Command 2 | 3 | 4 | class Module(object): 5 | """ 6 | Represents a single TMCM module present on the bus. 7 | """ 8 | 9 | def __init__( self, bus, address=1 ): 10 | """ 11 | :param bus: 12 | A Bus instance that is connected to one or more 13 | physical TMCM modules via serial port 14 | :type bus: TMCL.Bus 15 | 16 | :param address: 17 | Module address. This defaults to 1 18 | :type address: int 19 | 20 | """ 21 | self.bus = bus 22 | self.address = address 23 | 24 | 25 | def get_motor( self, axis=0 ): 26 | """ 27 | Return an interface to a single axis (motor) connected to 28 | this module. 29 | 30 | :param axis: 31 | Axis ID (defaults to 0) 32 | :type axis: int 33 | 34 | :return: An interface to the desired axis/motor 35 | :rtype: Motor 36 | """ 37 | return Motor(self.bus, self.address, axis) 38 | 39 | 40 | 41 | class Motor(object): 42 | RFS_START = 0 43 | RFS_STOP = 1 44 | RFS_STATUS = 2 45 | 46 | def __init__( self, bus, address=1, axis=0 ): 47 | self.bus = bus 48 | self.module_id = address 49 | self.motor_id = axis 50 | self.axis = AxisParameterInterface(self) 51 | 52 | def send( self, cmd, type, motorbank, value ): 53 | return self.bus.send(self.module_id, cmd, type, motorbank, value) 54 | 55 | def stop( self ): 56 | self.send(Command.MST, 0, self.motor_id, 0) 57 | 58 | def get_user_var( self, n ): 59 | reply = self.send(Command.GGP, n, 2, 0) 60 | return reply.value 61 | 62 | def set_user_var( self, n, value ): 63 | reply = self.send(Command.SGP, n, 2, value) 64 | return reply.status 65 | 66 | def rotate_left (self, velocity ): 67 | reply = self.send(Command.ROL, 0, self.motor_id, velocity) 68 | return reply.status 69 | 70 | def rotate_right(self, velocity): 71 | reply = self.send(Command.ROR, 0, self.motor_id, velocity) 72 | return reply.status 73 | 74 | def move_absolute (self, position): 75 | reply = self.send(Command.MVP, 0, self.motor_id, position) 76 | return reply.status 77 | 78 | def move_relative (self, offset): 79 | reply = self.send(Command.MVP, 1, self.motor_id, offset) 80 | 81 | def run_command( self, cmdIndex ): 82 | reply = self.send(Command.RUN_APPLICATION, 1, self.motor_id, cmdIndex) 83 | return reply.status 84 | 85 | def reference_search( self, rfs_type ): 86 | reply = self.send(Command.RFS, rfs_type, self.motor_id, 99) 87 | return reply.status 88 | 89 | 90 | class AxisParameterInterface(object): 91 | def __init__( self, motor ): 92 | """ 93 | 94 | :param motor: 95 | :type motor: Motor 96 | """ 97 | self.motor = motor 98 | 99 | def get( self, param ): 100 | reply = self.motor.send(Command.GAP, param, self.motor.motor_id, 0) 101 | return reply.value 102 | 103 | def set( self, param, value ): 104 | reply = self.motor.send(Command.SAP, param, self.motor.motor_id, value) 105 | return reply.status 106 | 107 | @property 108 | def target_position( self ): 109 | return self.get(0) 110 | 111 | @target_position.setter 112 | def target_position( self, value ): 113 | self.set(0, value) 114 | 115 | @property 116 | def actual_position( self ): 117 | return self.get(1) 118 | 119 | @actual_position.setter 120 | def actual_position( self, value ): 121 | self.set(1, value) 122 | 123 | @property 124 | def target_speed( self ): 125 | return self.get(2) 126 | 127 | @target_speed.setter 128 | def target_speed( self, value ): 129 | self.set(2, value) 130 | 131 | @property 132 | def actual_speed( self ): 133 | return self.get(3) 134 | 135 | @property 136 | def max_positioning_speed( self ): 137 | return self.get(4) 138 | 139 | @max_positioning_speed.setter 140 | def max_positioning_speed( self, value ): 141 | self.set(4, value) 142 | 143 | @property 144 | def max_accelleration( self ): 145 | return self.get(5) 146 | 147 | @max_accelleration.setter 148 | def max_accelleration( self, value ): 149 | self.set(5, value) 150 | 151 | @property 152 | def max_current( self ): 153 | return self.get(6) 154 | 155 | @max_current.setter 156 | def max_current( self, value ): 157 | self.set(6, value) 158 | 159 | @property 160 | def standby_current( self ): 161 | return self.get(7) 162 | 163 | @standby_current.setter 164 | def standby_current( self, value ): 165 | self.set(7, value) 166 | 167 | @property 168 | def target_position_reached( self ): 169 | return self.get(8) 170 | 171 | @property 172 | def ref_switch_status( self ): 173 | return self.get(9) 174 | 175 | @property 176 | def right_limit_status( self ): 177 | return self.get(10) 178 | 179 | @property 180 | def left_limit_status( self ): 181 | return self.get(11) 182 | 183 | @property 184 | def right_limit_switch_disabled( self ): 185 | return True if self.get(12) == 1 else False 186 | 187 | @right_limit_switch_disabled.setter 188 | def right_limit_switch_disabled( self, value ): 189 | self.set(12, 1 if value else 0) 190 | 191 | @property 192 | def left_limit_switch_disabled( self ): 193 | return True if self.get(13) == 1 else False 194 | 195 | @left_limit_switch_disabled.setter 196 | def left_limit_switch_disabled( self, value ): 197 | self.set(13, 1 if value else 0) 198 | -------------------------------------------------------------------------------- /TMCL/reply.py: -------------------------------------------------------------------------------- 1 | class TrinamicException(Exception): 2 | def __init__( self, reply ): 3 | super(TrinamicException, self).__init__(Reply.Status.messages[reply.status]) 4 | self.reply = reply 5 | 6 | 7 | class Reply(object): 8 | def __init__( self, reply_struct ): 9 | self.reply_address = reply_struct[0] 10 | self.module_address = reply_struct[1] 11 | self.status = reply_struct[2] 12 | self.command = reply_struct[3] 13 | self.value = reply_struct[4] 14 | self.checksum = reply_struct[5] 15 | 16 | 17 | class Status(object): 18 | SUCCESS = 100 19 | COMMAND_LOADED = 101 20 | WRONG_CHECKSUM = 1 21 | INVALID_COMMAND = 2 22 | WRONG_TYPE = 3 23 | INVALID_VALUE = 4 24 | EEPROM_LOCKED = 5 25 | COMMAND_NOT_AVAILABLE = 6 26 | 27 | messages = { 28 | 1: "Incorrect Checksum", 29 | 2: "Invalid Command", 30 | 3: "Wrong Type", 31 | 4: "Invalid Value", 32 | 5: "EEPROM Locked", 33 | 6: "Command not Available" 34 | } 35 | -------------------------------------------------------------------------------- /dist/TMCL-1.0.tar.gz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/NativeDesign/python-tmcl/7d79359274ef7e59ca561a1bf474e94bfdc5973c/dist/TMCL-1.0.tar.gz -------------------------------------------------------------------------------- /examples/example1.py: -------------------------------------------------------------------------------- 1 | from serial import Serial 2 | import TMCL 3 | 4 | 5 | def simple_example (): 6 | ## Open a serial port to connect to the bus 7 | serial_port = Serial("/dev/tty.usbmodem1241") 8 | bus = TMCL.connect(serial_port) 9 | 10 | ## Get the motor on axis 0 of module with address 1 11 | motor = bus.get_motor(1) 12 | 13 | 14 | 15 | 16 | def example_for_multi_axis_modules(): 17 | ## Open a serial port to connect to the bus 18 | serial_port = Serial("/dev/tty.usbmodem1241") 19 | bus = TMCL.connect(serial_port) 20 | 21 | ## Get the module at address 1 22 | module = bus.get_module(1) 23 | 24 | ## Get the motor on axis '0' of the module 25 | motor = module.get_motor(0) 26 | 27 | ## Start sending commands to the motor 28 | motor.stop() 29 | -------------------------------------------------------------------------------- /setup.cfg: -------------------------------------------------------------------------------- 1 | [metadata] 2 | description-file = README.md 3 | -------------------------------------------------------------------------------- /setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import setup 2 | 3 | setup(name='TMCL', 4 | version='1.2', 5 | description='Talk to Trinamic Stepper Motors using TMCL over serial', 6 | url='https://github.com/NativeDesign/python-tmcl', 7 | author='Alan Pich', 8 | author_email='alanp@native.com', 9 | license='MIT', 10 | packages=['TMCL'], 11 | install_requires=[ 12 | 'pyserial' 13 | ], 14 | keywords = [ 15 | 'tmcl', 16 | 'trinamic', 17 | 'rs485', 18 | 'stepper', 19 | 'motor', 20 | 'tmcm' 21 | ], 22 | zip_safe=False) 23 | --------------------------------------------------------------------------------