diff --git a/.gitignore b/.gitignore
index 322cc61..15daf4e 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1,6 +1,218 @@
-# Ignore all release packages
-*.zip
-*.rar
+# Byte-compiled / optimized / DLL files
+__pycache__/
+*.py[codz]
+*$py.class
-# Ignore all automation
-*.bat
+# C extensions
+*.so
+
+# Distribution / packaging
+.Python
+build/
+develop-eggs/
+dist/
+downloads/
+eggs/
+.eggs/
+lib/
+lib64/
+parts/
+sdist/
+var/
+wheels/
+share/python-wheels/
+*.egg-info/
+.installed.cfg
+*.egg
+MANIFEST
+
+# PyInstaller
+# Usually these files are written by a python script from a template
+# before PyInstaller builds the exe, so as to inject date/other infos into it.
+*.manifest
+*.spec
+
+# Installer logs
+pip-log.txt
+pip-delete-this-directory.txt
+
+# Unit test / coverage reports
+htmlcov/
+.tox/
+.nox/
+.coverage
+.coverage.*
+.cache
+nosetests.xml
+coverage.xml
+*.cover
+*.py.cover
+.hypothesis/
+.pytest_cache/
+cover/
+
+# Translations
+*.mo
+*.pot
+
+# Django stuff:
+*.log
+local_settings.py
+db.sqlite3
+db.sqlite3-journal
+
+# Flask stuff:
+instance/
+.webassets-cache
+
+# Scrapy stuff:
+.scrapy
+
+# Sphinx documentation
+docs/_build/
+
+# PyBuilder
+.pybuilder/
+target/
+
+# Jupyter Notebook
+.ipynb_checkpoints
+
+# IPython
+profile_default/
+ipython_config.py
+
+# pyenv
+# For a library or package, you might want to ignore these files since the code is
+# intended to run in multiple environments; otherwise, check them in:
+# .python-version
+
+# pipenv
+# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control.
+# However, in case of collaboration, if having platform-specific dependencies or dependencies
+# having no cross-platform support, pipenv may install dependencies that don't work, or not
+# install all needed dependencies.
+# Pipfile.lock
+
+# UV
+# Similar to Pipfile.lock, it is generally recommended to include uv.lock in version control.
+# This is especially recommended for binary packages to ensure reproducibility, and is more
+# commonly ignored for libraries.
+# uv.lock
+
+# poetry
+# Similar to Pipfile.lock, it is generally recommended to include poetry.lock in version control.
+# This is especially recommended for binary packages to ensure reproducibility, and is more
+# commonly ignored for libraries.
+# https://python-poetry.org/docs/basic-usage/#commit-your-poetrylock-file-to-version-control
+# poetry.lock
+# poetry.toml
+
+# pdm
+# Similar to Pipfile.lock, it is generally recommended to include pdm.lock in version control.
+# pdm recommends including project-wide configuration in pdm.toml, but excluding .pdm-python.
+# https://pdm-project.org/en/latest/usage/project/#working-with-version-control
+# pdm.lock
+# pdm.toml
+.pdm-python
+.pdm-build/
+
+# pixi
+# Similar to Pipfile.lock, it is generally recommended to include pixi.lock in version control.
+# pixi.lock
+# Pixi creates a virtual environment in the .pixi directory, just like venv module creates one
+# in the .venv directory. It is recommended not to include this directory in version control.
+.pixi
+
+# PEP 582; used by e.g. github.com/David-OConnor/pyflow and github.com/pdm-project/pdm
+__pypackages__/
+
+# Celery stuff
+celerybeat-schedule
+celerybeat.pid
+
+# Redis
+*.rdb
+*.aof
+*.pid
+
+# RabbitMQ
+mnesia/
+rabbitmq/
+rabbitmq-data/
+
+# ActiveMQ
+activemq-data/
+
+# SageMath parsed files
+*.sage.py
+
+# Environments
+.env
+.envrc
+.venv
+env/
+venv/
+ENV/
+env.bak/
+venv.bak/
+
+# Spyder project settings
+.spyderproject
+.spyproject
+
+# Rope project settings
+.ropeproject
+
+# mkdocs documentation
+/site
+
+# mypy
+.mypy_cache/
+.dmypy.json
+dmypy.json
+
+# Pyre type checker
+.pyre/
+
+# pytype static type analyzer
+.pytype/
+
+# Cython debug symbols
+cython_debug/
+
+# PyCharm
+# JetBrains specific template is maintained in a separate JetBrains.gitignore that can
+# be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore
+# and can be added to the global gitignore or merged into this file. For a more nuclear
+# option (not recommended) you can uncomment the following to ignore the entire idea folder.
+# .idea/
+
+# Abstra
+# Abstra is an AI-powered process automation framework.
+# Ignore directories containing user credentials, local state, and settings.
+# Learn more at https://abstra.io/docs
+.abstra/
+
+# Visual Studio Code
+# Visual Studio Code specific template is maintained in a separate VisualStudioCode.gitignore
+# that can be found at https://github.com/github/gitignore/blob/main/Global/VisualStudioCode.gitignore
+# and can be added to the global gitignore or merged into this file. However, if you prefer,
+# you could uncomment the following to ignore the entire vscode folder
+# .vscode/
+
+# Ruff stuff:
+.ruff_cache/
+
+# PyPI configuration file
+.pypirc
+
+# Marimo
+marimo/_static/
+marimo/_lsp/
+__marimo__/
+
+# Streamlit
+.streamlit/secrets.toml
+
+.vscode/
\ No newline at end of file
diff --git a/.python-version b/.python-version
new file mode 100644
index 0000000..3767b4b
--- /dev/null
+++ b/.python-version
@@ -0,0 +1 @@
+3.14
\ No newline at end of file
diff --git a/README.md b/README.md
index 40a9819..2265f2d 100644
--- a/README.md
+++ b/README.md
@@ -1,12 +1,98 @@
-# LSS_Libraries_Python
+# Lynxmotion Smart Servo (LSS) Python Library
+
Official Lynxmotion Smart Servo (LSS) libraries for Python
-Read more about the LSS on our [wiki](https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/).
+Read more about the LSS on our [wiki](https://wiki.lynxmotion.com/info/wiki/lynxmotion/view/ses-v2/lynxmotion-smart-servo/).
+
+If you want more details about the LSS protocol, go [here](https://wiki.lynxmotion.com/info/wiki/lynxmotion/view/ses-v2/lynxmotion-smart-servo/lss-communication-protocol/).
+
+To configure your LSS easily, we recommend you try out the [LSS Config](https://www.robotshop.com/products/lynxmotion-lss-configuration-software?qd=e28060e7570ef850c9f4421ea1dccf99).
+More details about it [on the wiki](https://wiki.lynxmotion.com/info/wiki/lynxmotion/view/ses-v2/lynxmotion-smart-servo/lss-configuration-software/).
+
+Purchase any LSS model on and accessories at [RobotShop](https://www.robotshop.com)!
+
+Check out blogs, tutorials and post questions on the RobotShop [community site](https://www.robotshop.com/community/).
+
+## Installation
+
+This project uses [uv](https://docs.astral.sh/uv/) for dependency management. If you don't have uv installed:
+
+```bash
+# Install uv (Linux/macOS)
+curl -LsSf https://astral.sh/uv/install.sh | sh
+
+# Or using pip
+pip install uv
+```
+
+### Install the library
+
+```bash
+# Clone the repository
+git clone https://github.com/motius/pyLSS
+cd PyLSS
+
+# Install dependencies
+uv sync
+
+# Or install in development mode with all dependencies
+uv sync --all-groups
+```
+
+### Using the library in your project
+
+```python
+import serial
+from pylss import LSS
+
+# Create and open a serial connection
+bus = serial.Serial('/dev/ttyUSB0', 115200, timeout=0.1)
+
+# Create an LSS servo controller for servo ID 5
+servo = LSS(5, bus)
+
+# Move to 45 degrees
+servo.move_deg(45.0)
+
+# Get current position
+position = servo.get_position_deg()
+print(f"Current position: {position}°")
+
+# Get servo information
+model = servo.get_model()
+voltage = servo.get_voltage()
+temperature = servo.get_temperature()
+
+print(f"Model: {model}")
+print(f"Voltage: {voltage}mV")
+print(f"Temperature: {temperature/10}°C")
+
+# Clean up
+bus.close()
+```
+
+## Running Examples
+
+The repository includes several example scripts in the [examples](examples/) directory:
+
+## Testing
+
+The library includes a comprehensive test suite using pytest with mocked serial communication, so no hardware is required to run tests.
+
+### Run all tests
+
+```bash
+# Run all tests
+uv run pytest tests/
-If you want more details about the LSS protocol, go [here](https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/).
+# Run with verbose output
+uv run pytest tests/ -v
-To configure your LSS easily, we recommend you try out the [LSS Config](https://www.robotshop.com/en/lynxmotion-smart-servo-lss-configuration-software.html). More details about it [on the wiki](https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-configuration-software/).
+# Run with coverage report
+uv run pytest tests/ --cov=pylss
-Purchase any LSS model on [RobotShop.com](https://www.robotshop.com/en/lynxmotion-smart-servos.html) and get [accessories](https://www.robotshop.com/en/lynxmotion-servos-accessories-1.html), too!
+# Run specific test class
+uv run pytest tests/test.py::TestLSSActionMethods -v
+```
-Check out blogs, tutorials and post questions on the Robotshop [community site](https://www.robotshop.com/community/).
+All tests use mocked serial objects, making them fast and reliable without requiring physical hardware.
diff --git a/examples/example_configure_once.py b/examples/example_configure_once.py
new file mode 100644
index 0000000..14d6545
--- /dev/null
+++ b/examples/example_configure_once.py
@@ -0,0 +1,122 @@
+# Author: Sebastien Parent-Charette (support@robotshop.com)
+# License: LGPL-3.0 (GNU Lesser General Public License version 3)
+# Description: Example of all the possible configurations for a LSS.
+
+import time
+import serial
+from pylss import LSS
+from pylss.constants import (
+ DEFAULT_BAUD,
+ LedColor,
+ GyreDirection, # noqa: F401 used in commented examples
+ SetType, # noqa: F401 used in commented examples
+)
+
+# Constants
+PORT = "/dev/ttyUSB0" # For Linux/Unix platforms
+# PORT = "COM230" # For Windows platforms
+BAUD_RATE = DEFAULT_BAUD
+
+
+def main() -> None:
+ """Configure an LSS servo and demonstrate LED color changes."""
+ # Create and open a serial port
+ bus = serial.Serial(PORT, BAUD_RATE, timeout=0.1)
+
+ try:
+ # Create an LSS object for servo ID 0
+ servo = LSS(0, bus)
+
+ # Uncomment any configurations that you wish to activate
+ # You can see above each configuration a link to its description in the Lynxmotion wiki
+ # Note: If you change a configuration to the same value that is already set,
+ # the LSS will ignore the operation since the value is not changed.
+
+ # *** Basic configurations ***
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H6.OriginOffsetAction28O29
+ # servo.set_origin_offset_deg(0.0, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H7.AngularRange28AR29
+ # servo.set_angular_range_deg(180.0, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H12.MaxSpeedinDegrees28SD29
+ # servo.set_max_speed_deg_per_sec(60.0, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H13.MaxSpeedinRPM28SR29
+ # servo.set_max_speed_rpm(100, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H14.LEDColor28LED29
+ # Options are:
+ # LedColor.BLACK = 0
+ # LedColor.RED = 1
+ # LedColor.GREEN = 2
+ # LedColor.BLUE = 3
+ # LedColor.YELLOW = 4
+ # LedColor.CYAN = 5
+ # LedColor.MAGENTA = 6
+ # LedColor.WHITE = 7
+ # servo.set_color_led(LedColor.BLACK, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H15.GyreRotationDirection28G29
+ # Options are:
+ # GyreDirection.CLOCKWISE = 1
+ # GyreDirection.COUNTER_CLOCKWISE = -1
+ # servo.set_gyre(GyreDirection.CLOCKWISE, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H19.FirstA0Position28Degrees29
+ # servo.set_first_position_deg(0.0)
+ # servo.clear_first_position()
+
+ # *** Advanced configurations ***
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA1.AngularStiffness28AS29
+ # servo.set_angular_stiffness(0, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA2.AngularHoldingStiffness28AH29
+ # servo.set_angular_holding_stiffness(4, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA3:AngularAcceleration28AA29
+ # servo.set_angular_acceleration(100, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA4:AngularDeceleration28AD29
+ # servo.set_angular_deceleration(100, SetType.CONFIG)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA5:MotionControl28EM29
+ # servo.set_motion_control_enabled(1)
+
+ # https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA6.ConfigureLEDBlinking28CLB29
+ # Options are an arithmetic addition of the following values:
+ # Limp 1
+ # Holding 2
+ # Accelerating 4
+ # Decelerating 8
+ # Free 16
+ # Traveling 32
+ # Therefore, 0 = no blinking and 63 = always blinking
+ # servo.set_blinking_led(0)
+
+ # Reset motor to complete change of configurations
+ servo.reset()
+
+ # Wait for reboot
+ time.sleep(2)
+
+ print("Cycling through LED colors. Press Ctrl+C to stop.")
+
+ # Loop through each of the 8 LED colors
+ while True:
+ for color in LedColor:
+ # Set the color (session) of the LSS
+ servo.set_color_led(color)
+ print(f"LED Color: {color.name}")
+ # Wait 1 second per color change
+ time.sleep(1)
+
+ except KeyboardInterrupt:
+ print("\nStopped by user")
+ finally:
+ # Clean up
+ bus.close()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/examples/example_knob_mimic.py b/examples/example_knob_mimic.py
new file mode 100644
index 0000000..a800068
--- /dev/null
+++ b/examples/example_knob_mimic.py
@@ -0,0 +1,77 @@
+# Author: Sebastien Parent-Charette (support@robotshop.com)
+# License: LGPL-3.0 (GNU Lesser General Public License version 3)
+# Description: Moves one LSS using the position of a second LSS.
+# One servo acts as an input (limp mode) and the other mimics its position.
+
+import time
+import serial
+from pylss import LSS
+from pylss.constants import DEFAULT_BAUD
+
+# Constants
+# PORT = "/dev/ttyUSB0" # For Linux/Unix platforms
+PORT = "COM230" # For Windows platforms
+BAUD_RATE = DEFAULT_BAUD
+
+# Hysteresis threshold in tenths of degrees (±2 tenths = ±0.2 degrees)
+POSITION_THRESHOLD = 2
+
+
+def main() -> None:
+ """Use one servo as input (knob) to control another servo (output)."""
+ # Create and open a serial port
+ bus = serial.Serial(PORT, BAUD_RATE, timeout=0.1)
+
+ try:
+ # Create two LSS objects: one for output (ID=0), one for input (ID=1)
+ output_servo = LSS(0, bus)
+ input_servo = LSS(1, bus)
+
+ # Initialize output servo to position 0.0 degrees
+ print("Initializing output servo to 0 degrees...")
+ output_servo.move_deg(0.0)
+
+ # Wait for it to get there
+ time.sleep(2)
+
+ # Configure output servo for smooth following
+ print("Configuring output servo...")
+ output_servo.set_angular_stiffness(4)
+ output_servo.set_max_speed_rpm(15)
+
+ # Make input servo limp (no active resistance, acts as a knob)
+ print("Setting input servo to limp mode...")
+ input_servo.limp()
+
+ print("\nMimicking input servo position. Press Ctrl+C to stop.")
+ print("Manually move the input servo to control the output servo.\n")
+
+ # Track last position to implement hysteresis
+ last_position_deg = 0.0
+
+ # Reproduce position of input_servo on output_servo
+ while True:
+ # Wait ~20 ms before sending another command (update at most 50 times per second)
+ time.sleep(0.02)
+
+ # Get position from input servo
+ current_position_deg = input_servo.get_position_deg()
+
+ # Check if position changed enough to warrant sending (hysteresis of ±0.2 degrees)
+ position_delta = abs(current_position_deg - last_position_deg)
+
+ if position_delta > (POSITION_THRESHOLD / 10):
+ # Send position to output servo and display
+ print(f"Input @ {current_position_deg:6.1f}° → Output")
+ output_servo.move_deg(current_position_deg)
+ last_position_deg = current_position_deg
+
+ except KeyboardInterrupt:
+ print("\nStopped by user")
+ finally:
+ # Clean up
+ bus.close()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/examples/example_query.py b/examples/example_query.py
new file mode 100644
index 0000000..54c4f4d
--- /dev/null
+++ b/examples/example_query.py
@@ -0,0 +1,58 @@
+# Author: Sebastien Parent-Charette (support@robotshop.com)
+# License: LGPL-3.0 (GNU Lesser General Public License version 3)
+# Description: Basic example of reading values from the LSS and displaying
+# them in the terminal.
+
+import time
+import serial
+from pylss import LSS
+from pylss.constants import DEFAULT_BAUD
+
+# Constants
+# PORT = "/dev/ttyUSB0" # For Linux/Unix platforms
+PORT = "COM230" # For Windows platforms
+BAUD_RATE = DEFAULT_BAUD
+
+
+def main() -> None:
+ """Query and display servo telemetry continuously."""
+ # Create and open a serial port
+ bus = serial.Serial(PORT, BAUD_RATE, timeout=0.1)
+
+ try:
+ # Create an LSS object for servo ID 0
+ servo = LSS(0, bus)
+
+ print("Querying LSS telemetry. Press Ctrl+C to stop.\n")
+
+ while True:
+ # Get the values from LSS
+ print("Querying LSS...")
+
+ position = servo.get_position_deg()
+ rpm = servo.get_speed_rpm()
+ current = servo.get_current()
+ voltage = servo.get_voltage()
+ temperature = servo.get_temperature()
+
+ # Display the values in terminal
+ print("\n---- Telemetry ----")
+ print(f"Position: {position:7.1f} degrees")
+ print(f"Speed: {rpm:7d} rpm")
+ print(f"Current: {current:7d} mA")
+ print(f"Voltage: {voltage:7d} mV ({voltage / 1000:.1f} V)")
+ print(f"Temperature: {temperature / 10:7.1f} °C")
+ print()
+
+ # Wait 1 second
+ time.sleep(1)
+
+ except KeyboardInterrupt:
+ print("\nStopped by user")
+ finally:
+ # Clean up
+ bus.close()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/examples/example_sweep.py b/examples/example_sweep.py
new file mode 100644
index 0000000..2e7378c
--- /dev/null
+++ b/examples/example_sweep.py
@@ -0,0 +1,58 @@
+# Author: Sebastien Parent-Charette (support@robotshop.com)
+# License: LGPL-3.0 (GNU Lesser General Public License version 3)
+# Description: Basic example of the LSS moving back and forth.
+
+import time
+import serial
+from pylss import LSS
+from pylss.constants import DEFAULT_BAUD
+
+# Constants
+# PORT = "/dev/ttyUSB0" # For Linux/Unix platforms
+PORT = "COM230" # For Windows platforms
+BAUD_RATE = DEFAULT_BAUD
+
+
+def main() -> None:
+ """Move the servo back and forth between -180 and +180 degrees."""
+ # Create and open a serial port
+ bus = serial.Serial(PORT, BAUD_RATE, timeout=0.1)
+
+ try:
+ # Create an LSS object for servo ID 0
+ servo = LSS(0, bus)
+
+ # Initialize LSS to position 0.0 degrees
+ servo.move_deg(0.0)
+ print("Moving to 0 degrees...")
+
+ # Wait for it to get there
+ time.sleep(2)
+
+ print("Starting sweep. Press Ctrl+C to stop.")
+
+ # Loop between -180.0 deg and 180.0 deg, pausing 2 seconds between moves
+ while True:
+ # Send LSS to half a turn counter-clockwise from zero (assumes gyre = 1)
+ print("Moving to -180 degrees")
+ servo.move_deg(-180.0)
+
+ # Wait for two seconds
+ time.sleep(2)
+
+ # Send LSS to half a turn clockwise from zero (assumes gyre = 1)
+ print("Moving to +180 degrees")
+ servo.move_deg(180.0)
+
+ # Wait for two seconds
+ time.sleep(2)
+
+ except KeyboardInterrupt:
+ print("\nStopped by user")
+ finally:
+ # Clean up
+ bus.close()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/extras/LICENSE b/extras/LICENSE
deleted file mode 100644
index 0a04128..0000000
--- a/extras/LICENSE
+++ /dev/null
@@ -1,165 +0,0 @@
- GNU LESSER GENERAL PUBLIC LICENSE
- Version 3, 29 June 2007
-
- Copyright (C) 2007 Free Software Foundation, Inc.
- Everyone is permitted to copy and distribute verbatim copies
- of this license document, but changing it is not allowed.
-
-
- This version of the GNU Lesser General Public License incorporates
-the terms and conditions of version 3 of the GNU General Public
-License, supplemented by the additional permissions listed below.
-
- 0. Additional Definitions.
-
- As used herein, "this License" refers to version 3 of the GNU Lesser
-General Public License, and the "GNU GPL" refers to version 3 of the GNU
-General Public License.
-
- "The Library" refers to a covered work governed by this License,
-other than an Application or a Combined Work as defined below.
-
- An "Application" is any work that makes use of an interface provided
-by the Library, but which is not otherwise based on the Library.
-Defining a subclass of a class defined by the Library is deemed a mode
-of using an interface provided by the Library.
-
- A "Combined Work" is a work produced by combining or linking an
-Application with the Library. The particular version of the Library
-with which the Combined Work was made is also called the "Linked
-Version".
-
- The "Minimal Corresponding Source" for a Combined Work means the
-Corresponding Source for the Combined Work, excluding any source code
-for portions of the Combined Work that, considered in isolation, are
-based on the Application, and not on the Linked Version.
-
- The "Corresponding Application Code" for a Combined Work means the
-object code and/or source code for the Application, including any data
-and utility programs needed for reproducing the Combined Work from the
-Application, but excluding the System Libraries of the Combined Work.
-
- 1. Exception to Section 3 of the GNU GPL.
-
- You may convey a covered work under sections 3 and 4 of this License
-without being bound by section 3 of the GNU GPL.
-
- 2. Conveying Modified Versions.
-
- If you modify a copy of the Library, and, in your modifications, a
-facility refers to a function or data to be supplied by an Application
-that uses the facility (other than as an argument passed when the
-facility is invoked), then you may convey a copy of the modified
-version:
-
- a) under this License, provided that you make a good faith effort to
- ensure that, in the event an Application does not supply the
- function or data, the facility still operates, and performs
- whatever part of its purpose remains meaningful, or
-
- b) under the GNU GPL, with none of the additional permissions of
- this License applicable to that copy.
-
- 3. Object Code Incorporating Material from Library Header Files.
-
- The object code form of an Application may incorporate material from
-a header file that is part of the Library. You may convey such object
-code under terms of your choice, provided that, if the incorporated
-material is not limited to numerical parameters, data structure
-layouts and accessors, or small macros, inline functions and templates
-(ten or fewer lines in length), you do both of the following:
-
- a) Give prominent notice with each copy of the object code that the
- Library is used in it and that the Library and its use are
- covered by this License.
-
- b) Accompany the object code with a copy of the GNU GPL and this license
- document.
-
- 4. Combined Works.
-
- You may convey a Combined Work under terms of your choice that,
-taken together, effectively do not restrict modification of the
-portions of the Library contained in the Combined Work and reverse
-engineering for debugging such modifications, if you also do each of
-the following:
-
- a) Give prominent notice with each copy of the Combined Work that
- the Library is used in it and that the Library and its use are
- covered by this License.
-
- b) Accompany the Combined Work with a copy of the GNU GPL and this license
- document.
-
- c) For a Combined Work that displays copyright notices during
- execution, include the copyright notice for the Library among
- these notices, as well as a reference directing the user to the
- copies of the GNU GPL and this license document.
-
- d) Do one of the following:
-
- 0) Convey the Minimal Corresponding Source under the terms of this
- License, and the Corresponding Application Code in a form
- suitable for, and under terms that permit, the user to
- recombine or relink the Application with a modified version of
- the Linked Version to produce a modified Combined Work, in the
- manner specified by section 6 of the GNU GPL for conveying
- Corresponding Source.
-
- 1) Use a suitable shared library mechanism for linking with the
- Library. A suitable mechanism is one that (a) uses at run time
- a copy of the Library already present on the user's computer
- system, and (b) will operate properly with a modified version
- of the Library that is interface-compatible with the Linked
- Version.
-
- e) Provide Installation Information, but only if you would otherwise
- be required to provide such information under section 6 of the
- GNU GPL, and only to the extent that such information is
- necessary to install and execute a modified version of the
- Combined Work produced by recombining or relinking the
- Application with a modified version of the Linked Version. (If
- you use option 4d0, the Installation Information must accompany
- the Minimal Corresponding Source and Corresponding Application
- Code. If you use option 4d1, you must provide the Installation
- Information in the manner specified by section 6 of the GNU GPL
- for conveying Corresponding Source.)
-
- 5. Combined Libraries.
-
- You may place library facilities that are a work based on the
-Library side by side in a single library together with other library
-facilities that are not Applications and are not covered by this
-License, and convey such a combined library under terms of your
-choice, if you do both of the following:
-
- a) Accompany the combined library with a copy of the same work based
- on the Library, uncombined with any other library facilities,
- conveyed under the terms of this License.
-
- b) Give prominent notice with the combined library that part of it
- is a work based on the Library, and explaining where to find the
- accompanying uncombined form of the same work.
-
- 6. Revised Versions of the GNU Lesser General Public License.
-
- The Free Software Foundation may publish revised and/or new versions
-of the GNU Lesser General Public License from time to time. Such new
-versions will be similar in spirit to the present version, but may
-differ in detail to address new problems or concerns.
-
- Each version is given a distinguishing version number. If the
-Library as you received it specifies that a certain numbered version
-of the GNU Lesser General Public License "or any later version"
-applies to it, you have the option of following the terms and
-conditions either of that published version or of any later version
-published by the Free Software Foundation. If the Library as you
-received it does not specify a version number of the GNU Lesser
-General Public License, you may choose any version of the GNU Lesser
-General Public License ever published by the Free Software Foundation.
-
- If the Library as you received it specifies that a proxy can decide
-whether future versions of the GNU Lesser General Public License shall
-apply, that proxy's public statement of acceptance of any version is
-permanent authorization for you to choose that version for the
-Library.
diff --git a/extras/README.html b/extras/README.html
deleted file mode 100644
index 38730f0..0000000
--- a/extras/README.html
+++ /dev/null
@@ -1,24 +0,0 @@
-
-
-
-
-
-# LSS_Libraries_Python
-
-Official Lynxmotion Smart Servo (LSS) libraries for Python
-
-
-
-Read more about the LSS on our wiki
-
-If you want more details about the LSS protocol, go here.
-
-To configure your LSS easily, we recommend you try out the LSS Config. More details about it on the wiki.
-
-Purchase any LSS model on RobotShop.com and get accessories, too!
-
-Check out blogs, tutorials and post questions on the Robotshop community site.
-
-
-
-
\ No newline at end of file
diff --git a/pylss/__init__.py b/pylss/__init__.py
new file mode 100644
index 0000000..fac8019
--- /dev/null
+++ b/pylss/__init__.py
@@ -0,0 +1,66 @@
+# Author: Sebastien Parent-Charette (support@robotshop.com)
+# License: LGPL-3.0 (GNU Lesser General Public License version 3)
+
+"""Lynxmotion Smart Servo (LSS) Python Library.
+
+This library provides an interface to control Lynxmotion Smart Servo (LSS)
+actuators via serial communication.
+
+Example:
+ >>> import serial
+ >>> from pylss import LSS
+ >>>
+ >>> bus = serial.Serial('/dev/ttyUSB0', 115200, timeout=0.1)
+ >>> servo = LSS(5, bus)
+ >>> servo.move_deg(45.0)
+ >>> position = servo.get_position_deg()
+ >>> bus.close()
+"""
+
+from .lss import LSS
+from .constants import (
+ DEFAULT_BAUD,
+ TIMEOUT_MS,
+ Action,
+ Query,
+ Config,
+ QueryType,
+ SetType,
+ Mode,
+ Status,
+ Model,
+ ModelString,
+ ServoID,
+ ComStatus,
+ GyreDirection,
+ LedColor,
+)
+
+__version__ = "0.1.0"
+__author__ = "Sebastien Parent-Charette, Sebastian Plamauer"
+__license__ = "LGPL-3.0-or-later"
+
+__all__ = [
+ # Main class
+ "LSS",
+ # Constants
+ "DEFAULT_BAUD",
+ "TIMEOUT_MS",
+ # Command enums
+ "Action",
+ "Query",
+ "Config",
+ # Parameter types
+ "QueryType",
+ "SetType",
+ "Mode",
+ # Status and identification
+ "Status",
+ "Model",
+ "ModelString",
+ "ServoID",
+ "ComStatus",
+ # Configuration
+ "GyreDirection",
+ "LedColor",
+]
diff --git a/pylss/constants.py b/pylss/constants.py
new file mode 100644
index 0000000..9022678
--- /dev/null
+++ b/pylss/constants.py
@@ -0,0 +1,211 @@
+# Author: Sebastien Parent-Charette (support@robotshop.com)
+# License: LGPL-3.0 (GNU Lesser General Public License version 3)
+
+from enum import IntEnum, StrEnum
+
+# List of constants
+
+# Bus communication
+DEFAULT_BAUD = 115200
+# Command Length
+# example: #999XXXX-2147483648\r Adding 1 for end string char (\0)
+MAX_TOTAL_COMMAND_LENGTH = 30 + 1
+TIMEOUT_MS = 100
+COMMAND_START = "#"
+COMMAND_REPLY_START = "*"
+COMMAND_END = "\r"
+FIRST_POSITION_DISABLED = "DIS"
+
+
+# LSS ID constants
+class ServoID(IntEnum):
+ """Servo ID range constants"""
+
+ DEFAULT = 0
+ MIN = 0
+ MAX = 250
+ MODE_255 = 255
+ BROADCAST = 254
+
+
+# Read/write status
+class ComStatus(IntEnum):
+ """Communication status codes"""
+
+ IDLE = 0
+ READ_SUCCESS = 1
+ READ_TIMEOUT = 2
+ READ_WRONG_ID = 3
+ READ_WRONG_IDENTIFIER = 4
+ READ_WRONG_FORMAT = 5
+ READ_NO_BUS = 6
+ READ_UNKNOWN = 7
+ WRITE_SUCCESS = 8
+ WRITE_NO_BUS = 9
+ WRITE_UNKNOWN = 10
+
+
+# LSS status
+class Status(IntEnum):
+ """Servo status codes"""
+
+ UNKNOWN = 0
+ LIMP = 1
+ FREE_MOVING = 2
+ ACCELERATING = 3
+ TRAVELING = 4
+ DECELERATING = 5
+ HOLDING = 6
+ OUTSIDE_LIMITS = 7
+ STUCK = 8 # cannot move at current speed setting
+ BLOCKED = 9 # same as stuck but reached maximum duty and still can't move
+ SAFE_MODE = 10
+ LAST = 11
+
+
+# LSS models
+class Model(IntEnum):
+ """Servo model types"""
+
+ HIGH_TORQUE = 0
+ STANDARD = 1
+ HIGH_SPEED = 2
+ UNKNOWN = 3
+
+
+# Model string constants
+class ModelString(StrEnum):
+ """Servo model string identifiers"""
+
+ HT1 = "LSS-HT1"
+ ST1 = "LSS-ST1"
+ HS1 = "LSS-HS1"
+
+
+# Parameter for query
+class QueryType(IntEnum):
+ """Query parameter types"""
+
+ SESSION = 0
+ CONFIG = 1
+ INSTANTANEOUS_SPEED = 2
+ TARGET_TRAVEL_SPEED = 3
+
+
+# Parameter for setter
+class SetType(IntEnum):
+ """Setter parameter types"""
+
+ SESSION = 0
+ CONFIG = 1
+
+
+# Parameter for Serial/RC mode change
+class Mode(IntEnum):
+ """Operating modes"""
+
+ SERIAL = 0
+ POSITION_RC = 1
+ WHEEL_RC = 2
+
+
+# Parameter for gyre direction
+class GyreDirection(IntEnum):
+ """Rotation direction"""
+
+ CLOCKWISE = 1
+ COUNTER_CLOCKWISE = -1
+
+
+# LED colors
+class LedColor(IntEnum):
+ """LED color codes"""
+
+ BLACK = 0
+ RED = 1
+ GREEN = 2
+ BLUE = 3
+ YELLOW = 4
+ CYAN = 5
+ MAGENTA = 6
+ WHITE = 7
+
+
+# Commands - actions
+class Action(StrEnum):
+ """Action command strings"""
+
+ RESET = "RESET"
+ LIMP = "L"
+ HOLD = "H"
+ PARAMETER_TIME = "T"
+ PARAMETER_SPEED = "S"
+ MOVE = "D"
+ MOVE_RELATIVE = "MD"
+ WHEEL = "WD"
+ WHEEL_RPM = "WR"
+ ORIGIN_OFFSET = "O"
+ ANGULAR_RANGE = "AR"
+ MAX_SPEED = "SD"
+ MAX_SPEED_RPM = "SR"
+ COLOR_LED = "LED"
+ GYRE_DIRECTION = "G"
+ ANGULAR_STIFFNESS = "AS"
+ ANGULAR_HOLDING_STIFFNESS = "AH"
+ ANGULAR_ACCELERATION = "AA"
+ ANGULAR_DECELERATION = "AD"
+ ENABLE_MOTION_CONTROL = "EM"
+
+
+# Commands - queries
+class Query(StrEnum):
+ """Query command strings"""
+
+ STATUS = "Q"
+ ORIGIN_OFFSET = "QO"
+ ANGULAR_RANGE = "QAR"
+ POSITION_PULSE = "QP"
+ POSITION = "QD"
+ SPEED = "QWD"
+ SPEED_RPM = "QWR"
+ SPEED_PULSE = "QS"
+ MAX_SPEED = "QSD"
+ MAX_SPEED_RPM = "QSR"
+ COLOR_LED = "QLED"
+ GYRE = "QG"
+ ID = "QID"
+ BAUD = "QB"
+ FIRST_POSITION = "QFD"
+ MODEL_STRING = "QMS"
+ SERIAL_NUMBER = "QN"
+ FIRMWARE_VERSION = "QF"
+ VOLTAGE = "QV"
+ TEMPERATURE = "QT"
+ CURRENT = "QC"
+ ANGULAR_STIFFNESS = "QAS"
+ ANGULAR_HOLDING_STIFFNESS = "QAH"
+ ANGULAR_ACCELERATION = "QAA"
+ ANGULAR_DECELERATION = "QAD"
+ ENABLE_MOTION_CONTROL = "QEM"
+ BLINKING_LED = "QLB"
+
+
+# Commands - configurations
+class Config(StrEnum):
+ """Configuration command strings"""
+
+ ID = "CID"
+ BAUD = "CB"
+ ORIGIN_OFFSET = "CO"
+ ANGULAR_RANGE = "CAR"
+ MAX_SPEED = "CSD"
+ MAX_SPEED_RPM = "CSR"
+ COLOR_LED = "CLED"
+ GYRE_DIRECTION = "CG"
+ FIRST_POSITION = "CFD"
+ MODE = "CRC"
+ ANGULAR_STIFFNESS = "CAS"
+ ANGULAR_HOLDING_STIFFNESS = "CAH"
+ ANGULAR_ACCELERATION = "CAA"
+ ANGULAR_DECELERATION = "CAD"
+ BLINKING_LED = "CLB"
diff --git a/pylss/lss.py b/pylss/lss.py
new file mode 100644
index 0000000..86154da
--- /dev/null
+++ b/pylss/lss.py
@@ -0,0 +1,554 @@
+# Author: Sebastien Parent-Charette (support@robotshop.com)
+# License: LGPL-3.0 (GNU Lesser General Public License version 3)
+
+import re
+import serial
+
+from .constants import (
+ TIMEOUT_MS,
+ COMMAND_START,
+ COMMAND_REPLY_START,
+ COMMAND_END,
+ Action,
+ Query,
+ Config,
+ QueryType,
+ SetType,
+)
+
+
+class LSS:
+ """Lynxmotion Smart Servo (LSS) controller class.
+
+ This class provides an interface to control LSS smart servos via serial communication.
+ Each instance represents a single servo on a shared serial bus.
+ """
+
+ def __init__(self, servo_id: int, bus: serial.Serial) -> None:
+ """Initialize an LSS servo controller.
+
+ Args:
+ servo_id: The ID of the servo to control (0-254)
+ bus: Serial connection to the servo bus
+ """
+ self.servo_id = servo_id
+ self.bus = bus
+ if self.bus:
+ self.bus.timeout = TIMEOUT_MS
+
+ def __del__(self) -> None:
+ """Close the serial connection when the object is deleted."""
+ if hasattr(self, "bus") and self.bus and self.bus.is_open:
+ self.bus.close()
+
+ def _write(self, cmd: str, param: int | str | None = None) -> None:
+ """Write a command to the servo.
+
+ Args:
+ cmd: Command string to send
+ param: Optional parameter value
+
+ Raises:
+ Exception: If serial bus is not available or not open
+ """
+ if not self.bus or not self.bus.is_open:
+ raise Exception("Serial bus is not available or not open")
+
+ if param is None:
+ message = f"{COMMAND_START}{self.servo_id}{cmd}{COMMAND_END}"
+ else:
+ message = f"{COMMAND_START}{self.servo_id}{cmd}{param}{COMMAND_END}"
+
+ self.bus.write(message.encode())
+
+ def _read_int(self, cmd: str) -> int:
+ """Read an integer response from the servo.
+
+ Args:
+ cmd: Command string that was sent
+
+ Returns:
+ Integer value from servo
+
+ Raises:
+ Exception: If serial bus is not available, timeout occurs, or response is invalid
+ """
+ if not self.bus or not self.bus.is_open:
+ raise Exception("Serial bus is not available or not open")
+
+ try:
+ # Find start of packet
+ c = self.bus.read()
+ while c.decode("utf-8") != COMMAND_REPLY_START:
+ c = self.bus.read()
+ if c.decode("utf-8") == "":
+ raise Exception(f"Timeout waiting for response to command '{cmd}'")
+
+ # Read until end marker
+ data = self.bus.read_until(COMMAND_END.encode("utf-8"))
+
+ # Parse response: ID + Command + Value
+ matches = re.match(
+ r"(\d{1,3})([A-Z]{1,4})(-?\d{1,18})", data.decode("utf-8"), re.I
+ )
+
+ if not matches:
+ raise Exception(
+ f"Malformed response for command '{cmd}': {data.decode('utf-8')}"
+ )
+
+ read_id, read_ident, read_value = matches.groups()
+
+ # Verify response matches request
+ if read_id != str(self.servo_id):
+ raise Exception(
+ f"Response from wrong servo ID: expected {self.servo_id}, got {read_id}"
+ )
+
+ if read_ident != cmd:
+ raise Exception(
+ f"Response command mismatch: expected '{cmd}', got '{read_ident}'"
+ )
+
+ return int(read_value)
+
+ except Exception as e:
+ if (
+ "Serial bus" in str(e)
+ or "Timeout" in str(e)
+ or "Malformed" in str(e)
+ or "Response" in str(e)
+ ):
+ raise
+ raise Exception(f"Communication error reading command '{cmd}': {str(e)}")
+
+ def _read_str(self, cmd: str, num_chars: int) -> str:
+ """Read a string response from the servo.
+
+ Args:
+ cmd: Command string that was sent
+ num_chars: Expected number of characters in response
+
+ Returns:
+ String value from servo
+
+ Raises:
+ Exception: If serial bus is not available, timeout occurs, or response is invalid
+ """
+ if not self.bus or not self.bus.is_open:
+ raise Exception("Serial bus is not available or not open")
+
+ try:
+ # Find start of packet
+ c = self.bus.read()
+ while c.decode("utf-8") != COMMAND_REPLY_START:
+ c = self.bus.read()
+ if c.decode("utf-8") == "":
+ raise Exception(f"Timeout waiting for response to command '{cmd}'")
+
+ # Read until end marker
+ data = self.bus.read_until(COMMAND_END.encode("utf-8"))[:-1]
+
+ # Parse response: ID + Command + Value
+ matches = re.match(
+ rf"(\d{{1,3}})([A-Z]{{1,4}})(.{{{num_chars}}})",
+ data.decode("utf-8"),
+ re.I,
+ )
+
+ if not matches:
+ raise Exception(
+ f"Malformed response for command '{cmd}': {data.decode('utf-8')}"
+ )
+
+ read_id, read_ident, read_value = matches.groups()
+
+ # Verify response matches request
+ if read_id != str(self.servo_id):
+ raise Exception(
+ f"Response from wrong servo ID: expected {self.servo_id}, got {read_id}"
+ )
+
+ if read_ident != cmd:
+ raise Exception(
+ f"Response command mismatch: expected '{cmd}', got '{read_ident}'"
+ )
+
+ return read_value
+
+ except Exception as e:
+ if (
+ "Serial bus" in str(e)
+ or "Timeout" in str(e)
+ or "Malformed" in str(e)
+ or "Response" in str(e)
+ ):
+ raise
+ raise Exception(f"Communication error reading command '{cmd}': {str(e)}")
+
+ # Action methods
+
+ def reset(self) -> None:
+ """Reset the servo."""
+ self._write(Action.RESET)
+
+ def limp(self) -> None:
+ """Put the servo in limp mode (no torque)."""
+ self._write(Action.LIMP)
+
+ def hold(self) -> None:
+ """Hold current position with torque."""
+ self._write(Action.HOLD)
+
+ def move_deg(self, degrees: float) -> None:
+ """Move to absolute position in degrees.
+
+ Args:
+ degrees: Target position in degrees
+ """
+ self._write(Action.MOVE, int(degrees * 10))
+
+ def move_relative_deg(self, degrees: float) -> None:
+ """Move relative to current position in degrees.
+
+ Args:
+ degrees: Relative position in degrees
+ """
+ self._write(Action.MOVE_RELATIVE, int(degrees * 10))
+
+ def wheel_deg_per_sec(self, degrees_per_sec: float) -> None:
+ """Continuous rotation at specified speed in degrees per second.
+
+ Args:
+ degrees_per_sec: Speed in degrees per second
+ """
+ self._write(Action.WHEEL, int(degrees_per_sec * 10))
+
+ def wheel_rpm(self, rpm: int) -> None:
+ """Continuous rotation at specified RPM.
+
+ Args:
+ rpm: Speed in RPM
+ """
+ self._write(Action.WHEEL_RPM, rpm)
+
+ # Query methods
+
+ def get_status(self) -> int:
+ """Get servo status."""
+ self._write(Query.STATUS)
+ return self._read_int(Query.STATUS)
+
+ def get_origin_offset_deg(self, query_type: QueryType = QueryType.SESSION) -> float:
+ """Get origin offset in degrees."""
+ self._write(Query.ORIGIN_OFFSET, query_type)
+ result = self._read_int(Query.ORIGIN_OFFSET)
+ return result / 10.0
+
+ def get_angular_range_deg(self, query_type: QueryType = QueryType.SESSION) -> float:
+ """Get angular range in degrees."""
+ self._write(Query.ANGULAR_RANGE, query_type)
+ result = self._read_int(Query.ANGULAR_RANGE)
+ return result / 10.0
+
+ def get_position_pulse(self) -> int:
+ """Get position in pulse units."""
+ self._write(Query.POSITION_PULSE)
+ return self._read_int(Query.POSITION_PULSE)
+
+ def get_position_deg(self) -> float:
+ """Get position in degrees."""
+ self._write(Query.POSITION)
+ result = self._read_int(Query.POSITION)
+ return result / 10.0
+
+ def get_speed_deg_per_sec(self) -> float:
+ """Get current speed in degrees per second."""
+ self._write(Query.SPEED)
+ result = self._read_int(Query.SPEED)
+ return result / 10.0
+
+ def get_speed_rpm(self) -> int:
+ """Get current speed in RPM."""
+ self._write(Query.SPEED_RPM)
+ return self._read_int(Query.SPEED_RPM)
+
+ def get_speed_pulse(self) -> int:
+ """Get current speed in pulse units."""
+ self._write(Query.SPEED_PULSE)
+ return self._read_int(Query.SPEED_PULSE)
+
+ def get_max_speed_deg(self, query_type: QueryType = QueryType.SESSION) -> float:
+ """Get maximum speed in degrees per second."""
+ self._write(Query.MAX_SPEED, query_type)
+ result = self._read_int(Query.MAX_SPEED)
+ return result / 10.0
+
+ def get_max_speed_rpm(self, query_type: QueryType = QueryType.SESSION) -> int:
+ """Get maximum speed in RPM."""
+ self._write(Query.MAX_SPEED_RPM, query_type)
+ return self._read_int(Query.MAX_SPEED_RPM)
+
+ def get_color_led(self, query_type: QueryType = QueryType.SESSION) -> int:
+ """Get LED color."""
+ self._write(Query.COLOR_LED, query_type)
+ return self._read_int(Query.COLOR_LED)
+
+ def get_gyre(self, query_type: QueryType = QueryType.SESSION) -> int:
+ """Get gyre direction."""
+ self._write(Query.GYRE, query_type)
+ return self._read_int(Query.GYRE)
+
+ def get_first_position_deg(self) -> float:
+ """Get first position in degrees (returns 0 if disabled)."""
+ self._write(Query.FIRST_POSITION)
+ result = self._read_int(Query.FIRST_POSITION)
+ return result / 10.0
+
+ def get_is_first_position_enabled(self) -> bool:
+ """Check if first position is enabled."""
+ try:
+ self._write(Query.FIRST_POSITION)
+ self._read_int(Query.FIRST_POSITION)
+ return True
+ except Exception:
+ return False
+
+ def get_model(self) -> str:
+ """Get servo model string."""
+ self._write(Query.MODEL_STRING)
+ return self._read_str(Query.MODEL_STRING, 7)
+
+ def get_serial_number(self) -> int:
+ """Get servo serial number."""
+ self._write(Query.SERIAL_NUMBER)
+ return self._read_int(Query.SERIAL_NUMBER)
+
+ def get_firmware_version(self) -> int:
+ """Get firmware version."""
+ self._write(Query.FIRMWARE_VERSION)
+ return self._read_int(Query.FIRMWARE_VERSION)
+
+ def get_voltage(self) -> int:
+ """Get voltage in mV."""
+ self._write(Query.VOLTAGE)
+ return self._read_int(Query.VOLTAGE)
+
+ def get_temperature(self) -> int:
+ """Get temperature in 1/10 degrees Celsius."""
+ self._write(Query.TEMPERATURE)
+ return self._read_int(Query.TEMPERATURE)
+
+ def get_current(self) -> int:
+ """Get current in mA."""
+ self._write(Query.CURRENT)
+ return self._read_int(Query.CURRENT)
+
+ def get_angular_stiffness(self, query_type: QueryType = QueryType.SESSION) -> int:
+ """Get angular stiffness."""
+ self._write(Query.ANGULAR_STIFFNESS, query_type)
+ return self._read_int(Query.ANGULAR_STIFFNESS)
+
+ def get_angular_holding_stiffness(
+ self, query_type: QueryType = QueryType.SESSION
+ ) -> int:
+ """Get angular holding stiffness."""
+ self._write(Query.ANGULAR_HOLDING_STIFFNESS, query_type)
+ return self._read_int(Query.ANGULAR_HOLDING_STIFFNESS)
+
+ def get_angular_acceleration(
+ self, query_type: QueryType = QueryType.SESSION
+ ) -> int:
+ """Get angular acceleration."""
+ self._write(Query.ANGULAR_ACCELERATION, query_type)
+ return self._read_int(Query.ANGULAR_ACCELERATION)
+
+ def get_angular_deceleration(
+ self, query_type: QueryType = QueryType.SESSION
+ ) -> int:
+ """Get angular deceleration."""
+ self._write(Query.ANGULAR_DECELERATION, query_type)
+ return self._read_int(Query.ANGULAR_DECELERATION)
+
+ def get_is_motion_control_enabled(self) -> int:
+ """Check if motion control is enabled."""
+ self._write(Query.ENABLE_MOTION_CONTROL)
+ return self._read_int(Query.ENABLE_MOTION_CONTROL)
+
+ def get_blinking_led(self) -> int:
+ """Get LED blinking configuration."""
+ self._write(Query.BLINKING_LED)
+ return self._read_int(Query.BLINKING_LED)
+
+ def set_origin_offset_deg(
+ self, degrees: float, set_type: SetType = SetType.SESSION
+ ) -> None:
+ """Set origin offset in degrees.
+
+ Args:
+ degrees: Offset position in degrees
+ set_type: SESSION or CONFIG
+ """
+ pos = int(degrees * 10)
+ if set_type == SetType.SESSION:
+ self._write(Action.ORIGIN_OFFSET, pos)
+ else:
+ self._write(Config.ORIGIN_OFFSET, pos)
+
+ def set_angular_range_deg(
+ self, degrees: float, set_type: SetType = SetType.SESSION
+ ) -> None:
+ """Set angular range in degrees.
+
+ Args:
+ degrees: Range in degrees
+ set_type: SESSION or CONFIG
+ """
+ delta = int(degrees * 10)
+ if set_type == SetType.SESSION:
+ self._write(Action.ANGULAR_RANGE, delta)
+ else:
+ self._write(Config.ANGULAR_RANGE, delta)
+
+ def set_max_speed_deg_per_sec(
+ self, degrees_per_sec: float, set_type: SetType = SetType.SESSION
+ ) -> None:
+ """Set maximum speed in degrees per second.
+
+ Args:
+ degrees_per_sec: Speed in degrees per second
+ set_type: SESSION or CONFIG
+ """
+ speed = int(degrees_per_sec * 10)
+ if set_type == SetType.SESSION:
+ self._write(Action.MAX_SPEED, speed)
+ else:
+ self._write(Config.MAX_SPEED, speed)
+
+ def set_max_speed_rpm(self, rpm: int, set_type: SetType = SetType.SESSION) -> None:
+ """Set maximum speed in RPM.
+
+ Args:
+ rpm: Speed in RPM
+ set_type: SESSION or CONFIG
+ """
+ if set_type == SetType.SESSION:
+ self._write(Action.MAX_SPEED_RPM, rpm)
+ else:
+ self._write(Config.MAX_SPEED_RPM, rpm)
+
+ def set_color_led(self, color: int, set_type: SetType = SetType.SESSION) -> None:
+ """Set LED color.
+
+ Args:
+ color: Color code (use LedColor enum)
+ set_type: SESSION or CONFIG
+ """
+ if set_type == SetType.SESSION:
+ self._write(Action.COLOR_LED, color)
+ else:
+ self._write(Config.COLOR_LED, color)
+
+ def set_gyre(self, gyre: int, set_type: SetType = SetType.SESSION) -> None:
+ """Set gyre direction.
+
+ Args:
+ gyre: Direction (use GyreDirection enum)
+ set_type: SESSION or CONFIG
+ """
+ if set_type == SetType.SESSION:
+ self._write(Action.GYRE_DIRECTION, gyre)
+ else:
+ self._write(Config.GYRE_DIRECTION, gyre)
+
+ def set_first_position_deg(self, degrees: float) -> None:
+ """Set first position in degrees.
+
+ Args:
+ degrees: Position in degrees
+ """
+ self._write(Config.FIRST_POSITION, int(degrees * 10))
+
+ def clear_first_position(self) -> None:
+ """Clear (disable) first position."""
+ self._write(Config.FIRST_POSITION)
+
+ def set_mode(self, mode: int) -> None:
+ """Set operating mode.
+
+ Args:
+ mode: Mode (use Mode enum)
+ """
+ self._write(Config.MODE, mode)
+
+ def set_angular_stiffness(
+ self, value: int, set_type: SetType = SetType.SESSION
+ ) -> None:
+ """Set angular stiffness.
+
+ Args:
+ value: Stiffness value
+ set_type: SESSION or CONFIG
+ """
+ if set_type == SetType.SESSION:
+ self._write(Action.ANGULAR_STIFFNESS, value)
+ else:
+ self._write(Config.ANGULAR_STIFFNESS, value)
+
+ def set_angular_holding_stiffness(
+ self, value: int, set_type: SetType = SetType.SESSION
+ ) -> None:
+ """Set angular holding stiffness.
+
+ Args:
+ value: Holding stiffness value
+ set_type: SESSION or CONFIG
+ """
+ if set_type == SetType.SESSION:
+ self._write(Action.ANGULAR_HOLDING_STIFFNESS, value)
+ else:
+ self._write(Config.ANGULAR_HOLDING_STIFFNESS, value)
+
+ def set_angular_acceleration(
+ self, value: int, set_type: SetType = SetType.SESSION
+ ) -> None:
+ """Set angular acceleration.
+
+ Args:
+ value: Acceleration value
+ set_type: SESSION or CONFIG
+ """
+ if set_type == SetType.SESSION:
+ self._write(Action.ANGULAR_ACCELERATION, value)
+ else:
+ self._write(Config.ANGULAR_ACCELERATION, value)
+
+ def set_angular_deceleration(
+ self, value: int, set_type: SetType = SetType.SESSION
+ ) -> None:
+ """Set angular deceleration.
+
+ Args:
+ value: Deceleration value
+ set_type: SESSION or CONFIG
+ """
+ if set_type == SetType.SESSION:
+ self._write(Action.ANGULAR_DECELERATION, value)
+ else:
+ self._write(Config.ANGULAR_DECELERATION, value)
+
+ def set_motion_control_enabled(self, value: int) -> None:
+ """Enable or disable motion control.
+
+ Args:
+ value: 1 to enable, 0 to disable
+ """
+ self._write(Action.ENABLE_MOTION_CONTROL, value)
+
+ def set_blinking_led(self, state: int) -> None:
+ """Set LED blinking configuration.
+
+ Args:
+ state: Bitmask of states to blink on
+ """
+ self._write(Config.BLINKING_LED, state)
diff --git a/pyproject.toml b/pyproject.toml
new file mode 100644
index 0000000..02ab18c
--- /dev/null
+++ b/pyproject.toml
@@ -0,0 +1,31 @@
+[project]
+name = "pylss"
+version = "0.1.0"
+description = "Lynxmotion Smart Servo (LSS) Python Library"
+readme = "README.md"
+requires-python = ">=3.14"
+dependencies = [
+ "pyserial>=3.5",
+ "pytest>=9.0.2",
+]
+authors = [
+ { name = "Sebastien Parent-Charette", email = "support@robotshop.com"},
+ { name = "Sebastian Plamauer", email = "sebastian.plamauer@motius.de"}
+ ]
+license = "LGPL-3.0-or-later"
+
+[dependency-groups]
+dev = [
+ "pytest-cov>=7.0.0",
+ "ruff>=0.14.13",
+ "ty>=0.0.12",
+]
+test = [
+ "pytest>=8.0",
+]
+
+[tool.pytest.ini_options]
+testpaths = ["tests"]
+python_files = ["test_*.py", "*_test.py", "test.py"]
+python_classes = ["Test*"]
+python_functions = ["test_*"]
diff --git a/src/example_configure_once.py b/src/example_configure_once.py
deleted file mode 100644
index 5bdaceb..0000000
--- a/src/example_configure_once.py
+++ /dev/null
@@ -1,110 +0,0 @@
-#
-# Author: Sebastien Parent-Charette (support@robotshop.com)
-# Version: 1.0.0
-# Licence: LGPL-3.0 (GNU Lesser General Public License version 3)
-#
-# Desscription: Example of all the possible configurations for a LSS.
-#
-
-# Import required liraries
-import time
-import serial
-
-# Import LSS library
-import lss
-import lss_const as lssc
-
-# Constants
-#CST_LSS_Port = "/dev/ttyUSB0" # For Linux/Unix platforms
-CST_LSS_Port = "COM230" # For windows platforms
-CST_LSS_Baud = lssc.LSS_DefaultBaud
-
-# Create and open a serial port
-lss.initBus(CST_LSS_Port, CST_LSS_Baud)
-
-# Create an LSS object
-myLSS = lss.LSS(0)
-
-# Uncomment any configurations that you wish to activate
-# You can see above each configuration a link to its description in the Lynxmotion wiki
-# Note: If you change a configuration to the same value that is already set,
-# the LSS will ignore the operation since the value is not changed.
-
-# *** Basic configurations ***
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H6.OriginOffsetAction28O29
-###myLSS.setOriginOffset(0)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H7.AngularRange28AR29
-###myLSS.setAngularRange(1800, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H12.MaxSpeedinDegrees28SD29
-# Set maximum speed in (1/10 deg)/s
-###myLSS.setMaxSpeed(600, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H13.MaxSpeedinRPM28SR29
-###myLSS.setMaxSpeedRPM(100, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H14.LEDColor28LED29
-# Options are:
-# LSS_LED_Black = 0
-# LSS_LED_Red = 1
-# LSS_LED_Green = 2
-# LSS_LED_Blue = 3
-# LSS_LED_Yellow = 4
-# LSS_LED_Cyan = 5
-# LSS_LED_Magenta = 6
-# LSS_LED_White = 7
-###myLSS.setColorLED(lssc.LSS_LED_Black, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H15.GyreRotationDirection28G29
-# Options are:
-# LSS_GyreClockwise = 1
-# LSS_GyreCounterClockwise = -1
-###myLSS.setGyre(lssc.LSS_GyreClockwise, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#H19.FirstA0Position28Degrees29
-###myLSS.setFirstPosition(0)
-###myLSS.clearFirstPosition()
-
-# *** Advaned configurations ***
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA1.AngularStiffness28AS29
-###myLSS.setAngularStiffness(0, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA2.AngularHoldingStiffness28AH29
-###myLSS.setAngularHoldingStiffness(4, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA3:AngularAcceleration28AA29
-###myLSS.setAngularAcceleration(100, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA4:AngularDeceleration28AD29
-###myLSS.setAngularDeceleration(100, lssc.LSS_SetConfig)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA5:MotionControl28EM29
-###myLSS.setMotionControlEnabled(True)
-
-# https://www.robotshop.com/info/wiki/lynxmotion/view/lynxmotion-smart-servo/lss-communication-protocol/#HA6.ConfigureLEDBlinking28CLB29
-# Options are an arithmetic addition of the following values:
-# Limp 1
-# Holding 2
-# Accelerating 4
-# Decelerating 8
-# Free 16
-# Travelling 32
-# Therefore, 0 = no blinking and 63 = always blinking
-###myLSS.setBlinkingLED(0)
-
-# Reset motor to complete change of configurations
-myLSS.reset()
-
-# Wait for reboot
-time.sleep(2)
-
-while 1:
- # Loop through each of the 8 LED color (black = 0, red = 1, ..., white = 7)
- for i in range (0, 7):
- # Set the color (session) of the LSS
- myLSS.setColorLED(i)
- # Wait 1 second per color change
- time.sleep(1)
-
-### EOF #######################################################################
diff --git a/src/example_knob_mimic.py b/src/example_knob_mimic.py
deleted file mode 100644
index 9c3b3f5..0000000
--- a/src/example_knob_mimic.py
+++ /dev/null
@@ -1,60 +0,0 @@
-#
-# Author: Sebastien Parent-Charette (support@robotshop.com)
-# Version: 1.0.0
-# Licence: LGPL-3.0 (GNU Lesser General Public License version 3)
-#
-# Desscription: Moves one LSS using the position of a second LSS.
-#
-
-# Import required liraries
-import time
-import serial
-
-# Import LSS library
-import lss
-import lss_const as lssc
-
-# Constants
-#CST_LSS_Port = "/dev/ttyUSB0" # For Linux/Unix platforms
-CST_LSS_Port = "COM230" # For windows platforms
-CST_LSS_Baud = lssc.LSS_DefaultBaud
-
-# Create and open a serial port
-lss.initBus(CST_LSS_Port, CST_LSS_Baud)
-
-# Create two LSS object; one for output (ID=0), one for input (ID=1)
-myLSS_Output = lss.LSS(0)
-myLSS_Input = lss.LSS(1)
-
-# Initialize LSS output to position 0.0
-myLSS_Output.move(0)
-
-# Wait for it to get there
-time.sleep(2)
-
-# Lower output servo stiffness
-myLSS_Output.setAngularStiffness(4)
-myLSS_Output.setMaxSpeedRPM(15)
-
-# Make input servo limp (no active resistance)
-myLSS_Input.limp();
-
-# Reproduces position of myLSS_Input on myLSS_Output
-pos = 0
-while 1:
- # Wait ~20 ms before sending another command (update at most 50 times per second)
- time.sleep(0.02)
-
- # Get position & check if it is valid (ex: servo missing)
- lastPos = pos
- posRead = myLSS_Input.getPosition()
- if(posRead is not None):
- pos = int(posRead,10)
-
- # Check if pos changed enough to warrant sending/showing (hysterisis of ±2)
- if ((pos < (lastPos - 2)) or (pos > (lastPos + 2))):
- # Send position to output servo and terminal
- print("Input @ " + str(pos))
- myLSS_Output.move(pos)
-
-### EOF #######################################################################
diff --git a/src/example_query.py b/src/example_query.py
deleted file mode 100644
index 03a4c59..0000000
--- a/src/example_query.py
+++ /dev/null
@@ -1,49 +0,0 @@
-#
-# Author: Sebastien Parent-Charette (support@robotshop.com)
-# Version: 1.0.0
-# Licence: LGPL-3.0 (GNU Lesser General Public License version 3)
-#
-# Desscription: Basic example of reading values from the LSS and placing
-# them on the terminal.
-#
-
-# Import required liraries
-import time
-import serial
-
-# Import LSS library
-import lss
-import lss_const as lssc
-
-# Constants
-#CST_LSS_Port = "/dev/ttyUSB0" # For Linux/Unix platforms
-CST_LSS_Port = "COM230" # For windows platforms
-CST_LSS_Baud = lssc.LSS_DefaultBaud
-
-# Create and open a serial port
-lss.initBus(CST_LSS_Port, CST_LSS_Baud)
-
-# Create an LSS object
-myLSS = lss.LSS(0)
-
-while 1:
- # Get the values from LSS
- print("\r\nQuerying LSS...")
- pos = myLSS.getPosition()
- rpm= myLSS.getSpeedRPM()
- curr = myLSS.getCurrent()
- volt = myLSS.getVoltage()
- temp = myLSS.getTemperature()
-
- # Display the values in terminal
- print("\r\n---- Telemetry ----")
- print("Position (1/10 deg) = " + str(pos));
- print("Speed (rpm) = " + str(rpm));
- print("Curent (mA) = " + str(curr));
- print("Voltage (mV) = " + str(volt));
- print("Temperature (1/10 C) = " + str(temp));
-
- # Wait 1 second
- time.sleep(1)
-
-### EOF #######################################################################
diff --git a/src/example_sweep.py b/src/example_sweep.py
deleted file mode 100644
index e7a0b66..0000000
--- a/src/example_sweep.py
+++ /dev/null
@@ -1,48 +0,0 @@
-#
-# Author: Sebastien Parent-Charette (support@robotshop.com)
-# Version: 1.0.0
-# Licence: LGPL-3.0 (GNU Lesser General Public License version 3)
-#
-# Desscription: Basic example of the LSS moving back and forth.
-#
-
-# Import required liraries
-import time
-import serial
-
-# Import LSS library
-import lss
-import lss_const as lssc
-
-# Constants
-#CST_LSS_Port = "/dev/ttyUSB0" # For Linux/Unix platforms
-CST_LSS_Port = "COM230" # For windows platforms
-CST_LSS_Baud = lssc.LSS_DefaultBaud
-
-# Create and open a serial port
-lss.initBus(CST_LSS_Port, CST_LSS_Baud)
-
-# Create an LSS object
-myLSS = lss.LSS(0)
-
-# Initialize LSS to position 0.0 deg
-myLSS.move(0)
-
-# Wait for it to get there
-time.sleep(2)
-
-# Loops between -180.0 deg and 180 deg, taking 1 second pause between each half-circle move.
-while 1:
- # Send LSS to half a turn counter-clockwise from zero (assumes gyre = 1)
- myLSS.move(-1800)
-
- # Wait for two seconds
- time.sleep(2)
-
- # Send LSS to half a turn clockwise from zero (assumes gyre = 1)
- myLSS.move(1800)
-
- # Wait for two seconds
- time.sleep(2)
-
-### EOF #######################################################################
diff --git a/src/lss.py b/src/lss.py
deleted file mode 100644
index 9652ef5..0000000
--- a/src/lss.py
+++ /dev/null
@@ -1,335 +0,0 @@
-###############################################################################
-# Author: Sebastien Parent-Charette (support@robotshop.com)
-# Version: 1.0.0
-# Licence: LGPL-3.0 (GNU Lesser General Public License version 3)
-#
-# Desscription: A library that makes using the LSS simple.
-# Offers support for most Python platforms.
-# Uses the Python serial library (pySerial).
-###############################################################################
-
-### Import required liraries
-import re
-import serial
-from math import sqrt, atan, acos, fabs
-
-### Import constants
-import lss_const as lssc
-
-### Class functions
-def initBus(portName, portBaud):
- LSS.bus = serial.Serial(portName, portBaud)
- LSS.bus.timeout = 0.1
-
-def closeBus():
- if LSS.bus is not None:
- LSS.bus.close()
- del LSS.bus
-
-# Write with a an optional parameter
-def genericWrite(id, cmd, param = None):
- if LSS.bus is None:
- return False
- if param is None:
- LSS.bus.write((lssc.LSS_CommandStart + str(id) + cmd + lssc.LSS_CommandEnd).encode())
- else:
- LSS.bus.write((lssc.LSS_CommandStart + str(id) + cmd + str(param) + lssc.LSS_CommandEnd).encode())
- return True
-
-# Read an integer result
-def genericRead_Blocking_int(id, cmd):
- if LSS.bus is None:
- return None
- try:
- # Get start of packet and discard header and everything before
- c = LSS.bus.read()
- while (c.decode("utf-8") != lssc.LSS_CommandReplyStart):
- c = LSS.bus.read()
- if(c.decode("utf-8") == ""):
- break
- # Get packet
- data = LSS.bus.read_until(lssc.LSS_CommandEnd.encode('utf-8')) #Otherwise (without ".encode('utf-8')") the received LSS_CommandEnd is not recognized by read_until, making it wait until timeout.
- # Parse packet
- matches = re.match("(\d{1,3})([A-Z]{1,4})(-?\d{1,18})", data.decode("utf-8"), re.I)
- # Check if matches are found
- if(matches is None):
- return(None)
- if((matches.group(1) is None) or (matches.group(2) is None) or (matches.group(3) is None)):
- return(None)
- # Get values from match
- readID = matches.group(1)
- readIdent = matches.group(2)
- readValue = matches.group(3)
- # Check id
- if(readID != str(id)):
- return(None)
- # Check identifier
- if(readIdent != cmd):
- return(None)
- except:
- return(None)
- # return value
- return(readValue)
-
-# Read a string result
-#@classmethod
-def genericRead_Blocking_str(id, cmd, numChars):
- if LSS.bus is None:
- return None
- if LSS.bus is None:
- return None
- try:
- # Get start of packet and discard header and everything before
- c = LSS.bus.read()
- while (c.decode("utf-8") != lssc.LSS_CommandReplyStart):
- c = LSS.bus.read()
- if(c.decode("utf-8") == ""):
- break
- # Get packet
- data = LSS.bus.read_until(lssc.LSS_CommandEnd.encode('utf-8')) #Otherwise (without ".encode('utf-8')") the received LSS_CommandEnd is not recognized by read_until, making it wait until timeout.
- data = (data[:-1])
- # Parse packet
- matches = re.match("(\d{1,3})([A-Z]{1,4})(.{" + str(numChars) + "})", data.decode("utf-8"), re.I)
- # Check if matches are found
- if(matches is None):
- return(None)
- if((matches.group(1) is None) or (matches.group(2) is None) or (matches.group(3) is None)):
- return(None)
- # Get values from match
- readID = matches.group(1)
- readIdent = matches.group(2)
- readValue = matches.group(3)
- # Check id
- if(readID != str(id)):
- return(None)
- # Check identifier
- if(readIdent != cmd):
- return(None)
- except:
- return(None)
- # return value
- return(readValue)
-
-class LSS:
- # Class attribute
- bus = None
-
- ### Constructor
- def __init__(self, id = 0):
- self.servoID = id
-
- ### Attributes
- servoID = 0
-
- ### Functions
- #> Actions
- def reset(self):
- return (genericWrite(self.servoID, lssc.LSS_ActionReset))
-
- def limp(self):
- return (genericWrite(self.servoID, lssc.LSS_ActionLimp))
-
- def hold(self):
- return (genericWrite(self.servoID, lssc.LSS_ActionHold))
-
- def move(self, pos):
- return (genericWrite(self.servoID, lssc.LSS_ActionMove, pos))
-
- def moveRelative(self, delta):
- return (genericWrite(self.servoID, lssc.LSS_ActionMoveRelative, delta))
-
- def wheel(self, speed):
- return (genericWrite(self.servoID, lssc.LSS_ActionWheel, speed))
-
- def wheelRPM(self, rpm):
- return (genericWrite(self.servoID, lssc.LSS_ActionWheelRPM, rpm))
-
- #> Queries
- #def getID(self):
- #def getBaud(self):
-
- def getStatus(self):
- genericWrite(self.servoID, lssc.LSS_QueryStatus)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryStatus))
-
- def getOriginOffset(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryOriginOffset, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryOriginOffset))
-
- def getAngularRange(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryAngularRange, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryAngularRange))
-
- def getPositionPulse(self):
- genericWrite(self.servoID, lssc.LSS_QueryPositionPulse)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryPositionPulse))
-
- def getPosition(self):
- genericWrite(self.servoID, lssc.LSS_QueryPosition)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryPosition))
-
- def getSpeed(self):
- genericWrite(self.servoID, lssc.LSS_QuerySpeed)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QuerySpeed))
-
- def getSpeedRPM(self):
- genericWrite(self.servoID, lssc.LSS_QuerySpeedRPM)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QuerySpeedRPM))
-
- def getSpeedPulse(self):
- genericWrite(self.servoID, lssc.LSS_QuerySpeedPulse)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QuerySpeedPulse))
-
- def getMaxSpeed(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryMaxSpeed, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryMaxSpeed))
-
- def getMaxSpeedRPM(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryMaxSpeedRPM, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryMaxSpeedRPM))
-
- def getColorLED(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryColorLED, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryColorLED))
-
- def getGyre(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryGyre, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryGyre))
-
- # returns 0 if "DIS"
- def getFirstPosition(self):
- genericWrite(self.servoID, lssc.LSS_QueryFirstPosition)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryFirstPosition))
-
- # returns true/false based on if QFD returns "DIS" (= False)
- def getIsFirstPositionEnabled(self):
- genericWrite(self.servoID, lssc.LSS_QueryFirstPosition)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryFirstPosition) is not None)
-
- def getModel(self):
- genericWrite(self.servoID, lssc.LSS_QueryModelString)
- return (genericRead_Blocking_str(self.servoID, lssc.LSS_QueryModelString, 7))
-
- def getSerialNumber(self):
- genericWrite(self.servoID, lssc.LSS_QuerySerialNumber)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QuerySerialNumber))
-
- def getFirmwareVersion(self):
- genericWrite(self.servoID, lssc.LSS_QueryFirmwareVersion)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryFirmwareVersion))
-
- def getVoltage(self):
- genericWrite(self.servoID, lssc.LSS_QueryVoltage)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryVoltage))
-
- def getTemperature(self):
- genericWrite(self.servoID, lssc.LSS_QueryTemperature)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryTemperature))
-
- def getCurrent(self):
- genericWrite(self.servoID, lssc.LSS_QueryCurrent)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryCurrent))
-
- #> Queries (advanced)
- def getAngularStiffness(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryAngularStiffness, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryAngularStiffness))
-
- def getAngularHoldingStiffness(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryAngularHoldingStiffness, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryAngularHoldingStiffness))
-
- def getAngularAcceleration(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryAngularAcceleration, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryAngularAcceleration))
-
- def getAngularDeceleration(self, queryType = lssc.LSS_QuerySession):
- genericWrite(self.servoID, lssc.LSS_QueryAngularDeceleration, queryType)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryAngularDeceleration))
-
- def getIsMotionControlEnabled(self):
- genericWrite(self.servoID, lssc.LSS_QueryEnableMotionControl)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryEnableMotionControl))
-
- def getBlinkingLED(self):
- genericWrite(self.servoID, lssc.LSS_QueryBlinkingLED)
- return (genericRead_Blocking_int(self.servoID, lssc.LSS_QueryBlinkingLED))
-
- #> Configs
- def setOriginOffset(self, pos, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionOriginOffset, pos))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigOriginOffset, pos))
-
- def setAngularRange(self, delta, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionAngularRange, delta))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigAngularRange, delta))
-
- def setMaxSpeed(self, speed, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionMaxSpeed, speed))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigMaxSpeed, speed))
-
- def setMaxSpeedRPM(self, rpm, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionMaxSpeedRPM, rpm))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigMaxSpeedRPM, rpm))
-
- def setColorLED(self, color, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionColorLED, color))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigColorLED, color))
-
- def setGyre(self, gyre, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionGyreDirection, gyre))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigGyreDirection, gyre))
-
- def setFirstPosition(self, pos):
- return (genericWrite(self.servoID, lssc.LSS_ConfigFirstPosition, pos))
-
- def clearFirstPosition(self):
- return (genericWrite(self.servoID, lssc.LSS_ConfigFirstPosition))
-
- def setMode(self, mode):
- return (genericWrite(self.servoID, lssc.LSS_ConfigMode, mode))
-
- #> Configs (advanced)
- def setAngularStiffness(self, value, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionAngularStiffness, value))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigAngularStiffness, value))
-
- def setAngularHoldingStiffness(self, value, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionAngularHoldingStiffness, value))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigAngularHoldingStiffness, value))
-
- def setAngularAcceleration(self, value, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionAngularAcceleration, value))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigAngularAcceleration, value))
-
- def setAngularDeceleration(self, value, setType = lssc.LSS_SetSession):
- if setType == lssc.LSS_SetSession:
- return (genericWrite(self.servoID, lssc.LSS_ActionAngularDeceleration, value))
- elif setType == lssc.LSS_SetConfig:
- return (genericWrite(self.servoID, lssc.LSS_ConfigAngularDeceleration, value))
-
- def setMotionControlEnabled(self, value):
- return (genericWrite(self.servoID, lssc.LSS_ActionEnableMotionControl, value))
-
- def setBlinkingLED(self, state):
- return (genericWrite(self.servoID, lssc.LSS_ConfigBlinkingLED, state))
-
-### EOF #######################################################################
diff --git a/src/lss_const.py b/src/lss_const.py
deleted file mode 100644
index 9c15f41..0000000
--- a/src/lss_const.py
+++ /dev/null
@@ -1,172 +0,0 @@
-###############################################################################
-# Author: Sebastien Parent-Charette (support@robotshop.com)
-# Version: 1.0.0
-# Licence: LGPL-3.0 (GNU Lesser General Public License version 3)
-#
-# Desscription: A library that makes using the LSS simple.
-# Offers support for most Python platforms.
-# Uses the Python serial library (pySerial).
-###############################################################################
-
-### List of constants
-
-# Bus communication
-LSS_DefaultBaud = 115200
-LSS_MaxTotalCommandLength = (30 + 1) # ex: #999XXXX-2147483648\r Adding 1 for end string char (\0)
-# # ex: #999XX000000000000000000\r
-LSS_Timeout = 100 # in ms
-LSS_CommandStart = "#"
-LSS_CommandReplyStart = "*"
-LSS_CommandEnd = "\r"
-LSS_FirstPositionDisabled = "DIS"
-
-# LSS constants
-LSS_ID_Default = 0
-LSS_ID_Min = 0
-LSS_ID_Max = 250
-LSS_Mode255ID = 255
-LSS_BroadcastID = 254
-
-# Read/write status
-LSS_CommStatus_Idle = 0
-LSS_CommStatus_ReadSuccess = 1
-LSS_CommStatus_ReadTimeout = 2
-LSS_CommStatus_ReadWrongID = 3
-LSS_CommStatus_ReadWrongIdentifier = 4
-LSS_CommStatus_ReadWrongFormat = 5
-LSS_CommStatus_ReadNoBus = 6
-LSS_CommStatus_ReadUnknown = 7
-LSS_CommStatus_WriteSuccess = 8
-LSS_CommStatus_WriteNoBus = 9
-LSS_CommStatus_WriteUnknown = 10
-
-# LSS status
-LSS_StatusUnknown = 0
-LSS_StatusLimp = 1
-LSS_StatusFreeMoving = 2
-LSS_StatusAccelerating = 3
-LSS_StatusTravelling = 4
-LSS_StatusDecelerating = 5
-LSS_StatusHolding = 6
-LSS_StatusOutsideLimits = 7
-LSS_StatusStuck = 8 #cannot move at current speed setting
-LSS_StatusBlocked = 9 #same as stuck but reached maximum duty and still can't move
-LSS_StatusSafeMode = 10
-LSS_StatusLast = 11
-
-# LSS models
-LSS_ModelHighTorque = 0
-LSS_ModelStandard = 1
-LSS_ModelHighSpeed = 2
-LSS_ModelUnknown = 3
-
-LSS_ModelHT1 = "LSS-HT1"
-LSS_ModelST1 = "LSS-ST1"
-LSS_ModelHS1 = "LSS-HS1"
-
-# Parameter for query
-LSS_QuerySession = 0
-LSS_QueryConfig = 1
-LSS_QueryInstantaneousSpeed = 2
-LSS_QueryTargetTravelSpeed = 3
-
-# Parameter for setter
-LSS_SetSession = 0
-LSS_SetConfig = 1
-
-# Parameter for Serial/RC mode change
-LSS_ModeSerial = 0
-LSS_ModePositionRC = 1
-LSS_ModeWheelRC = 2
-
-# Parameter for gyre direction
-LSS_GyreClockwise = 1
-LSS_GyreCounterClockwise = -1
-
-# LED colors
-LSS_LED_Black = 0
-LSS_LED_Red = 1
-LSS_LED_Green = 2
-LSS_LED_Blue = 3
-LSS_LED_Yellow = 4
-LSS_LED_Cyan = 5
-LSS_LED_Magenta = 6
-LSS_LED_White = 7
-
-# Commands - actions
-LSS_ActionReset = "RESET"
-LSS_ActionLimp = "L"
-LSS_ActionHold = "H"
-LSS_ActionParameterTime = "T"
-LSS_ActionParameterSpeed = "S"
-LSS_ActionMove = "D"
-LSS_ActionMoveRelative = "MD"
-LSS_ActionWheel = "WD"
-LSS_ActionWheelRPM = "WR"
-
-# Commands - actions settings
-LSS_ActionOriginOffset = "O"
-LSS_ActionAngularRange = "AR"
-LSS_ActionMaxSpeed = "SD"
-LSS_ActionMaxSpeedRPM = "SR"
-LSS_ActionColorLED = "LED"
-LSS_ActionGyreDirection = "G"
-
-# Commands - actions advanced settings
-LSS_ActionAngularStiffness = "AS"
-LSS_ActionAngularHoldingStiffness = "AH"
-LSS_ActionAngularAcceleration = "AA"
-LSS_ActionAngularDeceleration = "AD"
-LSS_ActionEnableMotionControl = "EM"
-
-# Commands - queries
-LSS_QueryStatus = "Q"
-LSS_QueryOriginOffset = "QO"
-LSS_QueryAngularRange = "QAR"
-LSS_QueryPositionPulse = "QP"
-LSS_QueryPosition = "QD"
-LSS_QuerySpeed = "QWD"
-LSS_QuerySpeedRPM = "QWR"
-LSS_QuerySpeedPulse = "QS"
-LSS_QueryMaxSpeed = "QSD"
-LSS_QueryMaxSpeedRPM = "QSR"
-LSS_QueryColorLED = "QLED"
-LSS_QueryGyre = "QG"
-LSS_QueryID = "QID"
-LSS_QueryBaud = "QB"
-LSS_QueryFirstPosition = "QFD"
-LSS_QueryModelString = "QMS"
-LSS_QuerySerialNumber = "QN"
-LSS_QueryFirmwareVersion = "QF"
-LSS_QueryVoltage = "QV"
-LSS_QueryTemperature = "QT"
-LSS_QueryCurrent = "QC"
-
-# Commands - queries advanced
-LSS_QueryAngularStiffness = "QAS"
-LSS_QueryAngularHoldingStiffness = "QAH"
-LSS_QueryAngularAcceleration = "QAA"
-LSS_QueryAngularDeceleration = "QAD"
-LSS_QueryEnableMotionControl = "QEM"
-LSS_QueryBlinkingLED = "QLB"
-
-# Commands - configurations
-LSS_ConfigID = "CID"
-LSS_ConfigBaud = "CB"
-LSS_ConfigOriginOffset = "CO"
-LSS_ConfigAngularRange = "CAR"
-LSS_ConfigMaxSpeed = "CSD"
-LSS_ConfigMaxSpeedRPM = "CSR"
-LSS_ConfigColorLED = "CLED"
-LSS_ConfigGyreDirection = "CG"
-LSS_ConfigFirstPosition = "CFD"
-LSS_ConfigMode = "CRC"
-
-# Commands - configurations advanced
-LSS_ConfigAngularStiffness = "CAS"
-LSS_ConfigAngularHoldingStiffness = "CAH"
-LSS_ConfigAngularAcceleration = "CAA"
-LSS_ConfigAngularDeceleration = "CAD"
-LSS_ConfigBlinkingLED = "CLB"
-
-### EOF #######################################################################
diff --git a/src/test.py b/src/test.py
deleted file mode 100644
index 199aa96..0000000
--- a/src/test.py
+++ /dev/null
@@ -1,46 +0,0 @@
-###############################################################################
-# Author: Sebastien Parent-Charette (support@robotshop.com)
-# Version: 1.0.0
-# Licence: LGPL-3.0 (GNU Lesser General Public License version 3)
-#
-# Desscription: An example using the LSS and the Python module.
-###############################################################################
-
-# Import required liraries
-import time
-import serial
-
-# Import LSS library
-import lss
-import lss_const as lssc
-
-# Constants
-#CST_LSS_Port = "/dev/ttyUSB0" # For Linux/Unix platforms
-CST_LSS_Port = "COM230" # For windows platforms
-CST_LSS_Baud = lssc.LSS_DefaultBaud
-
-# Create and open a serial port
-lss.initBus(CST_LSS_Port, CST_LSS_Baud)
-
-# Create LSS objects
-myLSS1 = lss.LSS(0)
-myLSS2 = lss.LSS(1)
-
-#myLSS1.move(-300)
-#myLSS2.move(300)
-
-print("myLSS1; position = " + str(myLSS1.getPosition()))
-print("myLSS2; position = " + str(myLSS2.getPosition()))
-print("myLSS1; model = " + str(myLSS1.getModel()))
-
-#myLSS1.reset()
-#myLSS2.reset()
-
-# Destroy objects
-del myLSS1
-del myLSS2
-
-# Destroy the bus
-lss.closeBus()
-
-### EOF #######################################################################
diff --git a/tests/__init__.py b/tests/__init__.py
new file mode 100644
index 0000000..030cb5c
--- /dev/null
+++ b/tests/__init__.py
@@ -0,0 +1 @@
+# Tests for pylss library
diff --git a/tests/test.py b/tests/test.py
new file mode 100644
index 0000000..0930b3f
--- /dev/null
+++ b/tests/test.py
@@ -0,0 +1,618 @@
+# Author: Sebastian Plamauer
+# License: LGPL-3.0 (GNU Lesser General Public License version 3)
+
+import pytest
+from unittest.mock import Mock
+from pylss.lss import LSS
+from pylss.constants import (
+ Action,
+ Query,
+ QueryType,
+ SetType,
+)
+
+
+class TestLSSCommandGeneration:
+ """Test that commands are properly formatted."""
+
+ def test_write_command_without_parameter(self):
+ """Test command format without parameter."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss._write(Action.RESET)
+
+ mock_bus.write.assert_called_once_with(b"#5RESET\r")
+
+ def test_write_command_with_integer_parameter(self):
+ """Test command format with integer parameter."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(10, mock_bus)
+
+ lss._write(Action.MOVE, 1500)
+
+ mock_bus.write.assert_called_once_with(b"#10D1500\r")
+
+ def test_write_command_with_negative_parameter(self):
+ """Test command format with negative parameter."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(2, mock_bus)
+
+ lss._write(Action.MOVE, -450)
+
+ mock_bus.write.assert_called_once_with(b"#2D-450\r")
+
+ def test_write_raises_when_bus_not_open(self):
+ """Test that writing raises exception when bus is not open."""
+ mock_bus = Mock()
+ mock_bus.is_open = False
+ lss = LSS(5, mock_bus)
+
+ with pytest.raises(Exception, match="Serial bus is not available or not open"):
+ lss._write(Action.RESET)
+
+ def test_write_raises_when_bus_is_none(self):
+ """Test that writing raises exception when bus is None."""
+ mock_bus = None
+ lss = LSS(5, mock_bus) # type: ignore
+
+ with pytest.raises(Exception, match="Serial bus is not available or not open"):
+ lss._write(Action.RESET)
+
+
+class TestLSSResponseParsing:
+ """Test response parsing from servo."""
+
+ def test_read_int_valid_response(self):
+ """Test reading valid integer response."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ # Simulate response: *5QD1234\r
+ mock_bus.read.side_effect = [b"*", b"*"] # First read finds start marker
+ mock_bus.read_until.return_value = b"5QD1234\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss._read_int(Query.POSITION)
+
+ assert result == 1234
+
+ def test_read_int_negative_value(self):
+ """Test reading negative integer response."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"3QD-900\r"
+
+ lss = LSS(3, mock_bus)
+ result = lss._read_int(Query.POSITION)
+
+ assert result == -900
+
+ def test_read_int_wrong_servo_id(self):
+ """Test error when response has wrong servo ID."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"7QD1234\r" # Wrong ID
+
+ lss = LSS(5, mock_bus)
+
+ with pytest.raises(Exception, match="Response from wrong servo ID"):
+ lss._read_int(Query.POSITION)
+
+ def test_read_int_wrong_command(self):
+ """Test error when response has wrong command identifier."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QV1234\r" # Wrong command
+
+ lss = LSS(5, mock_bus)
+
+ with pytest.raises(Exception, match="Response command mismatch"):
+ lss._read_int(Query.POSITION)
+
+ def test_read_int_malformed_response(self):
+ """Test error on malformed response."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"INVALID\r"
+
+ lss = LSS(5, mock_bus)
+
+ with pytest.raises(Exception, match="Malformed response"):
+ lss._read_int(Query.POSITION)
+
+ def test_read_int_timeout(self):
+ """Test timeout when waiting for response."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"", b""] # Empty reads simulate timeout
+
+ lss = LSS(5, mock_bus)
+
+ with pytest.raises(Exception, match="Timeout waiting for response"):
+ lss._read_int(Query.POSITION)
+
+ def test_read_str_valid_response(self):
+ """Test reading valid string response."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QMSLSS-ST1\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss._read_str(Query.MODEL_STRING, 7)
+
+ assert result == "LSS-ST1"
+
+ def test_read_raises_when_bus_not_open(self):
+ """Test that reading raises exception when bus is not open."""
+ mock_bus = Mock()
+ mock_bus.is_open = False
+ lss = LSS(5, mock_bus)
+
+ with pytest.raises(Exception, match="Serial bus is not available or not open"):
+ lss._read_int(Query.POSITION)
+
+
+class TestLSSActionMethods:
+ """Test action methods that send commands."""
+
+ def test_reset(self):
+ """Test reset command."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(1, mock_bus)
+
+ lss.reset()
+
+ mock_bus.write.assert_called_once_with(b"#1RESET\r")
+
+ def test_limp(self):
+ """Test limp command."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(2, mock_bus)
+
+ lss.limp()
+
+ mock_bus.write.assert_called_once_with(b"#2L\r")
+
+ def test_hold(self):
+ """Test hold command."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(3, mock_bus)
+
+ lss.hold()
+
+ mock_bus.write.assert_called_once_with(b"#3H\r")
+
+ def test_move_deg(self):
+ """Test move_deg converts degrees to tenths."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.move_deg(45.5)
+
+ mock_bus.write.assert_called_once_with(b"#5D455\r")
+
+ def test_move_deg_negative(self):
+ """Test move_deg with negative degrees."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.move_deg(-90.3)
+
+ mock_bus.write.assert_called_once_with(b"#5D-903\r")
+
+ def test_move_relative_deg(self):
+ """Test move_relative_deg converts degrees to tenths."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.move_relative_deg(10.5)
+
+ mock_bus.write.assert_called_once_with(b"#5MD105\r")
+
+ def test_wheel_deg_per_sec(self):
+ """Test wheel_deg_per_sec converts to tenths."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.wheel_deg_per_sec(30.0)
+
+ mock_bus.write.assert_called_once_with(b"#5WD300\r")
+
+ def test_wheel_rpm(self):
+ """Test wheel_rpm."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.wheel_rpm(60)
+
+ mock_bus.write.assert_called_once_with(b"#5WR60\r")
+
+
+class TestLSSQueryMethods:
+ """Test query methods that read responses."""
+
+ def test_get_position_deg(self):
+ """Test get_position_deg converts tenths to degrees."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QD455\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_position_deg()
+
+ assert result == 45.5
+ mock_bus.write.assert_called_once_with(b"#5QD\r")
+
+ def test_get_position_pulse(self):
+ """Test get_position_pulse returns raw pulse value."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QP12345\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_position_pulse()
+
+ assert result == 12345
+
+ def test_get_status(self):
+ """Test get_status."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5Q6\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_status()
+
+ assert result == 6 # HOLDING
+
+ def test_get_voltage(self):
+ """Test get_voltage."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QV12000\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_voltage()
+
+ assert result == 12000 # 12V in mV
+
+ def test_get_temperature(self):
+ """Test get_temperature."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QT250\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_temperature()
+
+ assert result == 250 # 25.0°C
+
+ def test_get_current(self):
+ """Test get_current."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QC500\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_current()
+
+ assert result == 500 # 500mA
+
+ def test_get_model(self):
+ """Test get_model returns string."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QMSLSS-HT1\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_model()
+
+ assert result == "LSS-HT1"
+
+ def test_get_serial_number(self):
+ """Test get_serial_number."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QN123456\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_serial_number()
+
+ assert result == 123456
+
+ def test_get_firmware_version(self):
+ """Test get_firmware_version."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QF368\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_firmware_version()
+
+ assert result == 368
+
+ def test_get_speed_deg_per_sec(self):
+ """Test get_speed_deg_per_sec converts tenths to degrees."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QWD300\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_speed_deg_per_sec()
+
+ assert result == 30.0
+
+ def test_get_speed_rpm(self):
+ """Test get_speed_rpm."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QWR60\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_speed_rpm()
+
+ assert result == 60
+
+ def test_get_origin_offset_deg_with_query_type(self):
+ """Test get_origin_offset_deg with SESSION query type."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QO50\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_origin_offset_deg(QueryType.SESSION)
+
+ assert result == 5.0
+ mock_bus.write.assert_called_once_with(b"#5QO0\r")
+
+ def test_get_angular_range_deg_config(self):
+ """Test get_angular_range_deg with CONFIG query type."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ mock_bus.read.side_effect = [b"*"]
+ mock_bus.read_until.return_value = b"5QAR1800\r"
+
+ lss = LSS(5, mock_bus)
+ result = lss.get_angular_range_deg(QueryType.CONFIG)
+
+ assert result == 180.0
+ mock_bus.write.assert_called_once_with(b"#5QAR1\r")
+
+
+class TestLSSConfigurationMethods:
+ """Test configuration setter methods."""
+
+ def test_set_origin_offset_deg_session(self):
+ """Test set_origin_offset_deg with SESSION type."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_origin_offset_deg(5.0, SetType.SESSION)
+
+ mock_bus.write.assert_called_once_with(b"#5O50\r")
+
+ def test_set_origin_offset_deg_config(self):
+ """Test set_origin_offset_deg with CONFIG type."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_origin_offset_deg(5.0, SetType.CONFIG)
+
+ mock_bus.write.assert_called_once_with(b"#5CO50\r")
+
+ def test_set_max_speed_deg_per_sec_session(self):
+ """Test set_max_speed_deg_per_sec with SESSION type."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_max_speed_deg_per_sec(90.0, SetType.SESSION)
+
+ mock_bus.write.assert_called_once_with(b"#5SD900\r")
+
+ def test_set_max_speed_rpm_config(self):
+ """Test set_max_speed_rpm with CONFIG type."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_max_speed_rpm(30, SetType.CONFIG)
+
+ mock_bus.write.assert_called_once_with(b"#5CSR30\r")
+
+ def test_set_color_led(self):
+ """Test set_color_led."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_color_led(3) # BLUE
+
+ mock_bus.write.assert_called_once_with(b"#5LED3\r")
+
+ def test_set_gyre(self):
+ """Test set_gyre."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_gyre(-1, SetType.SESSION) # COUNTER_CLOCKWISE
+
+ mock_bus.write.assert_called_once_with(b"#5G-1\r")
+
+ def test_set_first_position_deg(self):
+ """Test set_first_position_deg."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_first_position_deg(0.0)
+
+ mock_bus.write.assert_called_once_with(b"#5CFD0\r")
+
+ def test_clear_first_position(self):
+ """Test clear_first_position."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.clear_first_position()
+
+ mock_bus.write.assert_called_once_with(b"#5CFD\r")
+
+ def test_set_angular_stiffness(self):
+ """Test set_angular_stiffness."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_angular_stiffness(4, SetType.SESSION)
+
+ mock_bus.write.assert_called_once_with(b"#5AS4\r")
+
+ def test_set_motion_control_enabled(self):
+ """Test set_motion_control_enabled."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.set_motion_control_enabled(1)
+
+ mock_bus.write.assert_called_once_with(b"#5EM1\r")
+
+
+class TestLSSEdgeCases:
+ """Test edge cases and boundary conditions."""
+
+ def test_servo_id_zero(self):
+ """Test with servo ID 0."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(0, mock_bus)
+
+ lss.reset()
+
+ mock_bus.write.assert_called_once_with(b"#0RESET\r")
+
+ def test_servo_id_max(self):
+ """Test with maximum servo ID 254."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(254, mock_bus)
+
+ lss.reset()
+
+ mock_bus.write.assert_called_once_with(b"#254RESET\r")
+
+ def test_large_position_value(self):
+ """Test with large position values."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.move_deg(1800.0) # 180 degrees * 10
+
+ mock_bus.write.assert_called_once_with(b"#5D18000\r")
+
+ def test_negative_position_value(self):
+ """Test with negative position values."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.move_deg(-1800.0)
+
+ mock_bus.write.assert_called_once_with(b"#5D-18000\r")
+
+ def test_fractional_degrees_rounding(self):
+ """Test that fractional degrees are properly converted."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.move_deg(12.34)
+
+ # 12.34 * 10 = 123.4, int() truncates to 123
+ mock_bus.write.assert_called_once_with(b"#5D123\r")
+
+
+class TestLSSObjectLifecycle:
+ """Test object initialization and cleanup."""
+
+ def test_init_sets_servo_id(self):
+ """Test that __init__ sets servo_id correctly."""
+ mock_bus = Mock()
+ lss = LSS(42, mock_bus)
+
+ assert lss.servo_id == 42
+
+ def test_init_sets_bus(self):
+ """Test that __init__ sets bus correctly."""
+ mock_bus = Mock()
+ lss = LSS(5, mock_bus)
+
+ assert lss.bus is mock_bus
+
+ def test_init_sets_timeout(self):
+ """Test that __init__ sets bus timeout."""
+ mock_bus = Mock()
+ LSS(5, mock_bus)
+
+ assert mock_bus.timeout == 100 # TIMEOUT_MS
+
+ def test_del_closes_open_bus(self):
+ """Test that __del__ closes an open bus."""
+ mock_bus = Mock()
+ mock_bus.is_open = True
+ lss = LSS(5, mock_bus)
+
+ lss.__del__()
+
+ mock_bus.close.assert_called_once()
+
+ def test_del_skips_closed_bus(self):
+ """Test that __del__ doesn't close already closed bus."""
+ mock_bus = Mock()
+ mock_bus.is_open = False
+ lss = LSS(5, mock_bus)
+
+ lss.__del__()
+
+ mock_bus.close.assert_not_called()
+
+ def test_del_handles_none_bus(self):
+ """Test that __del__ handles None bus gracefully."""
+ lss = LSS(5, None) # type: ignore
+
+ # Should not raise exception
+ lss.__del__()
diff --git a/uv.lock b/uv.lock
new file mode 100644
index 0000000..f14164b
--- /dev/null
+++ b/uv.lock
@@ -0,0 +1,206 @@
+version = 1
+revision = 3
+requires-python = ">=3.14"
+
+[[package]]
+name = "colorama"
+version = "0.4.6"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/d8/53/6f443c9a4a8358a93a6792e2acffb9d9d5cb0a5cfd8802644b7b1c9a02e4/colorama-0.4.6.tar.gz", hash = "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44", size = 27697, upload-time = "2022-10-25T02:36:22.414Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/d1/d6/3965ed04c63042e047cb6a3e6ed1a63a35087b6a609aa3a15ed8ac56c221/colorama-0.4.6-py2.py3-none-any.whl", hash = "sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6", size = 25335, upload-time = "2022-10-25T02:36:20.889Z" },
+]
+
+[[package]]
+name = "coverage"
+version = "7.13.1"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/23/f9/e92df5e07f3fc8d4c7f9a0f146ef75446bf870351cd37b788cf5897f8079/coverage-7.13.1.tar.gz", hash = "sha256:b7593fe7eb5feaa3fbb461ac79aac9f9fc0387a5ca8080b0c6fe2ca27b091afd", size = 825862, upload-time = "2025-12-28T15:42:56.969Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/aa/8e/ba0e597560c6563fc0adb902fda6526df5d4aa73bb10adf0574d03bd2206/coverage-7.13.1-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:97ab3647280d458a1f9adb85244e81587505a43c0c7cff851f5116cd2814b894", size = 218996, upload-time = "2025-12-28T15:42:04.978Z" },
+ { url = "https://files.pythonhosted.org/packages/6b/8e/764c6e116f4221dc7aa26c4061181ff92edb9c799adae6433d18eeba7a14/coverage-7.13.1-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:8f572d989142e0908e6acf57ad1b9b86989ff057c006d13b76c146ec6a20216a", size = 219326, upload-time = "2025-12-28T15:42:06.691Z" },
+ { url = "https://files.pythonhosted.org/packages/4f/a6/6130dc6d8da28cdcbb0f2bf8865aeca9b157622f7c0031e48c6cf9a0e591/coverage-7.13.1-cp314-cp314-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:d72140ccf8a147e94274024ff6fd8fb7811354cf7ef88b1f0a988ebaa5bc774f", size = 250374, upload-time = "2025-12-28T15:42:08.786Z" },
+ { url = "https://files.pythonhosted.org/packages/82/2b/783ded568f7cd6b677762f780ad338bf4b4750205860c17c25f7c708995e/coverage-7.13.1-cp314-cp314-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:d3c9f051b028810f5a87c88e5d6e9af3c0ff32ef62763bf15d29f740453ca909", size = 252882, upload-time = "2025-12-28T15:42:10.515Z" },
+ { url = "https://files.pythonhosted.org/packages/cd/b2/9808766d082e6a4d59eb0cc881a57fc1600eb2c5882813eefff8254f71b5/coverage-7.13.1-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f398ba4df52d30b1763f62eed9de5620dcde96e6f491f4c62686736b155aa6e4", size = 254218, upload-time = "2025-12-28T15:42:12.208Z" },
+ { url = "https://files.pythonhosted.org/packages/44/ea/52a985bb447c871cb4d2e376e401116520991b597c85afdde1ea9ef54f2c/coverage-7.13.1-cp314-cp314-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:132718176cc723026d201e347f800cd1a9e4b62ccd3f82476950834dad501c75", size = 250391, upload-time = "2025-12-28T15:42:14.21Z" },
+ { url = "https://files.pythonhosted.org/packages/7f/1d/125b36cc12310718873cfc8209ecfbc1008f14f4f5fa0662aa608e579353/coverage-7.13.1-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:9e549d642426e3579b3f4b92d0431543b012dcb6e825c91619d4e93b7363c3f9", size = 252239, upload-time = "2025-12-28T15:42:16.292Z" },
+ { url = "https://files.pythonhosted.org/packages/6a/16/10c1c164950cade470107f9f14bbac8485f8fb8515f515fca53d337e4a7f/coverage-7.13.1-cp314-cp314-musllinux_1_2_i686.whl", hash = "sha256:90480b2134999301eea795b3a9dbf606c6fbab1b489150c501da84a959442465", size = 250196, upload-time = "2025-12-28T15:42:18.54Z" },
+ { url = "https://files.pythonhosted.org/packages/2a/c6/cd860fac08780c6fd659732f6ced1b40b79c35977c1356344e44d72ba6c4/coverage-7.13.1-cp314-cp314-musllinux_1_2_riscv64.whl", hash = "sha256:e825dbb7f84dfa24663dd75835e7257f8882629fc11f03ecf77d84a75134b864", size = 250008, upload-time = "2025-12-28T15:42:20.365Z" },
+ { url = "https://files.pythonhosted.org/packages/f0/3a/a8c58d3d38f82a5711e1e0a67268362af48e1a03df27c03072ac30feefcf/coverage-7.13.1-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:623dcc6d7a7ba450bbdbeedbaa0c42b329bdae16491af2282f12a7e809be7eb9", size = 251671, upload-time = "2025-12-28T15:42:22.114Z" },
+ { url = "https://files.pythonhosted.org/packages/f0/bc/fd4c1da651d037a1e3d53e8cb3f8182f4b53271ffa9a95a2e211bacc0349/coverage-7.13.1-cp314-cp314-win32.whl", hash = "sha256:6e73ebb44dca5f708dc871fe0b90cf4cff1a13f9956f747cc87b535a840386f5", size = 221777, upload-time = "2025-12-28T15:42:23.919Z" },
+ { url = "https://files.pythonhosted.org/packages/4b/50/71acabdc8948464c17e90b5ffd92358579bd0910732c2a1c9537d7536aa6/coverage-7.13.1-cp314-cp314-win_amd64.whl", hash = "sha256:be753b225d159feb397bd0bf91ae86f689bad0da09d3b301478cd39b878ab31a", size = 222592, upload-time = "2025-12-28T15:42:25.619Z" },
+ { url = "https://files.pythonhosted.org/packages/f7/c8/a6fb943081bb0cc926499c7907731a6dc9efc2cbdc76d738c0ab752f1a32/coverage-7.13.1-cp314-cp314-win_arm64.whl", hash = "sha256:228b90f613b25ba0019361e4ab81520b343b622fc657daf7e501c4ed6a2366c0", size = 221169, upload-time = "2025-12-28T15:42:27.629Z" },
+ { url = "https://files.pythonhosted.org/packages/16/61/d5b7a0a0e0e40d62e59bc8c7aa1afbd86280d82728ba97f0673b746b78e2/coverage-7.13.1-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:60cfb538fe9ef86e5b2ab0ca8fc8d62524777f6c611dcaf76dc16fbe9b8e698a", size = 219730, upload-time = "2025-12-28T15:42:29.306Z" },
+ { url = "https://files.pythonhosted.org/packages/a3/2c/8881326445fd071bb49514d1ce97d18a46a980712b51fee84f9ab42845b4/coverage-7.13.1-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:57dfc8048c72ba48a8c45e188d811e5efd7e49b387effc8fb17e97936dde5bf6", size = 220001, upload-time = "2025-12-28T15:42:31.319Z" },
+ { url = "https://files.pythonhosted.org/packages/b5/d7/50de63af51dfa3a7f91cc37ad8fcc1e244b734232fbc8b9ab0f3c834a5cd/coverage-7.13.1-cp314-cp314t-manylinux1_i686.manylinux_2_28_i686.manylinux_2_5_i686.whl", hash = "sha256:3f2f725aa3e909b3c5fdb8192490bdd8e1495e85906af74fe6e34a2a77ba0673", size = 261370, upload-time = "2025-12-28T15:42:32.992Z" },
+ { url = "https://files.pythonhosted.org/packages/e1/2c/d31722f0ec918fd7453b2758312729f645978d212b410cd0f7c2aed88a94/coverage-7.13.1-cp314-cp314t-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:9ee68b21909686eeb21dfcba2c3b81fee70dcf38b140dcd5aa70680995fa3aa5", size = 263485, upload-time = "2025-12-28T15:42:34.759Z" },
+ { url = "https://files.pythonhosted.org/packages/fa/7a/2c114fa5c5fc08ba0777e4aec4c97e0b4a1afcb69c75f1f54cff78b073ab/coverage-7.13.1-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:724b1b270cb13ea2e6503476e34541a0b1f62280bc997eab443f87790202033d", size = 265890, upload-time = "2025-12-28T15:42:36.517Z" },
+ { url = "https://files.pythonhosted.org/packages/65/d9/f0794aa1c74ceabc780fe17f6c338456bbc4e96bd950f2e969f48ac6fb20/coverage-7.13.1-cp314-cp314t-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:916abf1ac5cf7eb16bc540a5bf75c71c43a676f5c52fcb9fe75a2bd75fb944e8", size = 260445, upload-time = "2025-12-28T15:42:38.646Z" },
+ { url = "https://files.pythonhosted.org/packages/49/23/184b22a00d9bb97488863ced9454068c79e413cb23f472da6cbddc6cfc52/coverage-7.13.1-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:776483fd35b58d8afe3acbd9988d5de592ab6da2d2a865edfdbc9fdb43e7c486", size = 263357, upload-time = "2025-12-28T15:42:40.788Z" },
+ { url = "https://files.pythonhosted.org/packages/7d/bd/58af54c0c9199ea4190284f389005779d7daf7bf3ce40dcd2d2b2f96da69/coverage-7.13.1-cp314-cp314t-musllinux_1_2_i686.whl", hash = "sha256:b6f3b96617e9852703f5b633ea01315ca45c77e879584f283c44127f0f1ec564", size = 260959, upload-time = "2025-12-28T15:42:42.808Z" },
+ { url = "https://files.pythonhosted.org/packages/4b/2a/6839294e8f78a4891bf1df79d69c536880ba2f970d0ff09e7513d6e352e9/coverage-7.13.1-cp314-cp314t-musllinux_1_2_riscv64.whl", hash = "sha256:bd63e7b74661fed317212fab774e2a648bc4bb09b35f25474f8e3325d2945cd7", size = 259792, upload-time = "2025-12-28T15:42:44.818Z" },
+ { url = "https://files.pythonhosted.org/packages/ba/c3/528674d4623283310ad676c5af7414b9850ab6d55c2300e8aa4b945ec554/coverage-7.13.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:933082f161bbb3e9f90d00990dc956120f608cdbcaeea15c4d897f56ef4fe416", size = 262123, upload-time = "2025-12-28T15:42:47.108Z" },
+ { url = "https://files.pythonhosted.org/packages/06/c5/8c0515692fb4c73ac379d8dc09b18eaf0214ecb76ea6e62467ba7a1556ff/coverage-7.13.1-cp314-cp314t-win32.whl", hash = "sha256:18be793c4c87de2965e1c0f060f03d9e5aff66cfeae8e1dbe6e5b88056ec153f", size = 222562, upload-time = "2025-12-28T15:42:49.144Z" },
+ { url = "https://files.pythonhosted.org/packages/05/0e/c0a0c4678cb30dac735811db529b321d7e1c9120b79bd728d4f4d6b010e9/coverage-7.13.1-cp314-cp314t-win_amd64.whl", hash = "sha256:0e42e0ec0cd3e0d851cb3c91f770c9301f48647cb2877cb78f74bdaa07639a79", size = 223670, upload-time = "2025-12-28T15:42:51.218Z" },
+ { url = "https://files.pythonhosted.org/packages/f5/5f/b177aa0011f354abf03a8f30a85032686d290fdeed4222b27d36b4372a50/coverage-7.13.1-cp314-cp314t-win_arm64.whl", hash = "sha256:eaecf47ef10c72ece9a2a92118257da87e460e113b83cc0d2905cbbe931792b4", size = 221707, upload-time = "2025-12-28T15:42:53.034Z" },
+ { url = "https://files.pythonhosted.org/packages/cc/48/d9f421cb8da5afaa1a64570d9989e00fb7955e6acddc5a12979f7666ef60/coverage-7.13.1-py3-none-any.whl", hash = "sha256:2016745cb3ba554469d02819d78958b571792bb68e31302610e898f80dd3a573", size = 210722, upload-time = "2025-12-28T15:42:54.901Z" },
+]
+
+[[package]]
+name = "iniconfig"
+version = "2.3.0"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/72/34/14ca021ce8e5dfedc35312d08ba8bf51fdd999c576889fc2c24cb97f4f10/iniconfig-2.3.0.tar.gz", hash = "sha256:c76315c77db068650d49c5b56314774a7804df16fee4402c1f19d6d15d8c4730", size = 20503, upload-time = "2025-10-18T21:55:43.219Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/cb/b1/3846dd7f199d53cb17f49cba7e651e9ce294d8497c8c150530ed11865bb8/iniconfig-2.3.0-py3-none-any.whl", hash = "sha256:f631c04d2c48c52b84d0d0549c99ff3859c98df65b3101406327ecc7d53fbf12", size = 7484, upload-time = "2025-10-18T21:55:41.639Z" },
+]
+
+[[package]]
+name = "packaging"
+version = "25.0"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/a1/d4/1fc4078c65507b51b96ca8f8c3ba19e6a61c8253c72794544580a7b6c24d/packaging-25.0.tar.gz", hash = "sha256:d443872c98d677bf60f6a1f2f8c1cb748e8fe762d2bf9d3148b5599295b0fc4f", size = 165727, upload-time = "2025-04-19T11:48:59.673Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl", hash = "sha256:29572ef2b1f17581046b3a2227d5c611fb25ec70ca1ba8554b24b0e69331a484", size = 66469, upload-time = "2025-04-19T11:48:57.875Z" },
+]
+
+[[package]]
+name = "pluggy"
+version = "1.6.0"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/f9/e2/3e91f31a7d2b083fe6ef3fa267035b518369d9511ffab804f839851d2779/pluggy-1.6.0.tar.gz", hash = "sha256:7dcc130b76258d33b90f61b658791dede3486c3e6bfb003ee5c9bfb396dd22f3", size = 69412, upload-time = "2025-05-15T12:30:07.975Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/54/20/4d324d65cc6d9205fabedc306948156824eb9f0ee1633355a8f7ec5c66bf/pluggy-1.6.0-py3-none-any.whl", hash = "sha256:e920276dd6813095e9377c0bc5566d94c932c33b27a3e3945d8389c374dd4746", size = 20538, upload-time = "2025-05-15T12:30:06.134Z" },
+]
+
+[[package]]
+name = "pygments"
+version = "2.19.2"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/b0/77/a5b8c569bf593b0140bde72ea885a803b82086995367bf2037de0159d924/pygments-2.19.2.tar.gz", hash = "sha256:636cb2477cec7f8952536970bc533bc43743542f70392ae026374600add5b887", size = 4968631, upload-time = "2025-06-21T13:39:12.283Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/c7/21/705964c7812476f378728bdf590ca4b771ec72385c533964653c68e86bdc/pygments-2.19.2-py3-none-any.whl", hash = "sha256:86540386c03d588bb81d44bc3928634ff26449851e99741617ecb9037ee5ec0b", size = 1225217, upload-time = "2025-06-21T13:39:07.939Z" },
+]
+
+[[package]]
+name = "pylss"
+version = "0.1.0"
+source = { virtual = "." }
+dependencies = [
+ { name = "pyserial" },
+ { name = "pytest" },
+]
+
+[package.dev-dependencies]
+dev = [
+ { name = "pytest-cov" },
+ { name = "ruff" },
+ { name = "ty" },
+]
+test = [
+ { name = "pytest" },
+]
+
+[package.metadata]
+requires-dist = [
+ { name = "pyserial", specifier = ">=3.5" },
+ { name = "pytest", specifier = ">=9.0.2" },
+]
+
+[package.metadata.requires-dev]
+dev = [
+ { name = "pytest-cov", specifier = ">=7.0.0" },
+ { name = "ruff", specifier = ">=0.14.13" },
+ { name = "ty", specifier = ">=0.0.12" },
+]
+test = [{ name = "pytest", specifier = ">=8.0" }]
+
+[[package]]
+name = "pyserial"
+version = "3.5"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/1e/7d/ae3f0a63f41e4d2f6cb66a5b57197850f919f59e558159a4dd3a818f5082/pyserial-3.5.tar.gz", hash = "sha256:3c77e014170dfffbd816e6ffc205e9842efb10be9f58ec16d3e8675b4925cddb", size = 159125, upload-time = "2020-11-23T03:59:15.045Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/07/bc/587a445451b253b285629263eb51c2d8e9bcea4fc97826266d186f96f558/pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0", size = 90585, upload-time = "2020-11-23T03:59:13.41Z" },
+]
+
+[[package]]
+name = "pytest"
+version = "9.0.2"
+source = { registry = "https://pypi.org/simple" }
+dependencies = [
+ { name = "colorama", marker = "sys_platform == 'win32'" },
+ { name = "iniconfig" },
+ { name = "packaging" },
+ { name = "pluggy" },
+ { name = "pygments" },
+]
+sdist = { url = "https://files.pythonhosted.org/packages/d1/db/7ef3487e0fb0049ddb5ce41d3a49c235bf9ad299b6a25d5780a89f19230f/pytest-9.0.2.tar.gz", hash = "sha256:75186651a92bd89611d1d9fc20f0b4345fd827c41ccd5c299a868a05d70edf11", size = 1568901, upload-time = "2025-12-06T21:30:51.014Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/3b/ab/b3226f0bd7cdcf710fbede2b3548584366da3b19b5021e74f5bde2a8fa3f/pytest-9.0.2-py3-none-any.whl", hash = "sha256:711ffd45bf766d5264d487b917733b453d917afd2b0ad65223959f59089f875b", size = 374801, upload-time = "2025-12-06T21:30:49.154Z" },
+]
+
+[[package]]
+name = "pytest-cov"
+version = "7.0.0"
+source = { registry = "https://pypi.org/simple" }
+dependencies = [
+ { name = "coverage" },
+ { name = "pluggy" },
+ { name = "pytest" },
+]
+sdist = { url = "https://files.pythonhosted.org/packages/5e/f7/c933acc76f5208b3b00089573cf6a2bc26dc80a8aece8f52bb7d6b1855ca/pytest_cov-7.0.0.tar.gz", hash = "sha256:33c97eda2e049a0c5298e91f519302a1334c26ac65c1a483d6206fd458361af1", size = 54328, upload-time = "2025-09-09T10:57:02.113Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/ee/49/1377b49de7d0c1ce41292161ea0f721913fa8722c19fb9c1e3aa0367eecb/pytest_cov-7.0.0-py3-none-any.whl", hash = "sha256:3b8e9558b16cc1479da72058bdecf8073661c7f57f7d3c5f22a1c23507f2d861", size = 22424, upload-time = "2025-09-09T10:57:00.695Z" },
+]
+
+[[package]]
+name = "ruff"
+version = "0.14.13"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/50/0a/1914efb7903174b381ee2ffeebb4253e729de57f114e63595114c8ca451f/ruff-0.14.13.tar.gz", hash = "sha256:83cd6c0763190784b99650a20fec7633c59f6ebe41c5cc9d45ee42749563ad47", size = 6059504, upload-time = "2026-01-15T20:15:16.918Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/c3/ae/0deefbc65ca74b0ab1fd3917f94dc3b398233346a74b8bbb0a916a1a6bf6/ruff-0.14.13-py3-none-linux_armv6l.whl", hash = "sha256:76f62c62cd37c276cb03a275b198c7c15bd1d60c989f944db08a8c1c2dbec18b", size = 13062418, upload-time = "2026-01-15T20:14:50.779Z" },
+ { url = "https://files.pythonhosted.org/packages/47/df/5916604faa530a97a3c154c62a81cb6b735c0cb05d1e26d5ad0f0c8ac48a/ruff-0.14.13-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:914a8023ece0528d5cc33f5a684f5f38199bbb566a04815c2c211d8f40b5d0ed", size = 13442344, upload-time = "2026-01-15T20:15:07.94Z" },
+ { url = "https://files.pythonhosted.org/packages/4c/f3/e0e694dd69163c3a1671e102aa574a50357536f18a33375050334d5cd517/ruff-0.14.13-py3-none-macosx_11_0_arm64.whl", hash = "sha256:d24899478c35ebfa730597a4a775d430ad0d5631b8647a3ab368c29b7e7bd063", size = 12354720, upload-time = "2026-01-15T20:15:09.854Z" },
+ { url = "https://files.pythonhosted.org/packages/c3/e8/67f5fcbbaee25e8fc3b56cc33e9892eca7ffe09f773c8e5907757a7e3bdb/ruff-0.14.13-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9aaf3870f14d925bbaf18b8a2347ee0ae7d95a2e490e4d4aea6813ed15ebc80e", size = 12774493, upload-time = "2026-01-15T20:15:20.908Z" },
+ { url = "https://files.pythonhosted.org/packages/6b/ce/d2e9cb510870b52a9565d885c0d7668cc050e30fa2c8ac3fb1fda15c083d/ruff-0.14.13-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:ac5b7f63dd3b27cc811850f5ffd8fff845b00ad70e60b043aabf8d6ecc304e09", size = 12815174, upload-time = "2026-01-15T20:15:05.74Z" },
+ { url = "https://files.pythonhosted.org/packages/88/00/c38e5da58beebcf4fa32d0ddd993b63dfacefd02ab7922614231330845bf/ruff-0.14.13-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:78d2b1097750d90ba82ce4ba676e85230a0ed694178ca5e61aa9b459970b3eb9", size = 13680909, upload-time = "2026-01-15T20:15:14.537Z" },
+ { url = "https://files.pythonhosted.org/packages/61/61/cd37c9dd5bd0a3099ba79b2a5899ad417d8f3b04038810b0501a80814fd7/ruff-0.14.13-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:7d0bf87705acbbcb8d4c24b2d77fbb73d40210a95c3903b443cd9e30824a5032", size = 15144215, upload-time = "2026-01-15T20:15:22.886Z" },
+ { url = "https://files.pythonhosted.org/packages/56/8a/85502d7edbf98c2df7b8876f316c0157359165e16cdf98507c65c8d07d3d/ruff-0.14.13-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a3eb5da8e2c9e9f13431032fdcbe7681de9ceda5835efee3269417c13f1fed5c", size = 14706067, upload-time = "2026-01-15T20:14:48.271Z" },
+ { url = "https://files.pythonhosted.org/packages/7e/2f/de0df127feb2ee8c1e54354dc1179b4a23798f0866019528c938ba439aca/ruff-0.14.13-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:642442b42957093811cd8d2140dfadd19c7417030a7a68cf8d51fcdd5f217427", size = 14133916, upload-time = "2026-01-15T20:14:57.357Z" },
+ { url = "https://files.pythonhosted.org/packages/0d/77/9b99686bb9fe07a757c82f6f95e555c7a47801a9305576a9c67e0a31d280/ruff-0.14.13-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4acdf009f32b46f6e8864af19cbf6841eaaed8638e65c8dac845aea0d703c841", size = 13859207, upload-time = "2026-01-15T20:14:55.111Z" },
+ { url = "https://files.pythonhosted.org/packages/7d/46/2bdcb34a87a179a4d23022d818c1c236cb40e477faf0d7c9afb6813e5876/ruff-0.14.13-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:591a7f68860ea4e003917d19b5c4f5ac39ff558f162dc753a2c5de897fd5502c", size = 14043686, upload-time = "2026-01-15T20:14:52.841Z" },
+ { url = "https://files.pythonhosted.org/packages/1a/a9/5c6a4f56a0512c691cf143371bcf60505ed0f0860f24a85da8bd123b2bf1/ruff-0.14.13-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:774c77e841cc6e046fc3e91623ce0903d1cd07e3a36b1a9fe79b81dab3de506b", size = 12663837, upload-time = "2026-01-15T20:15:18.921Z" },
+ { url = "https://files.pythonhosted.org/packages/fe/bb/b920016ece7651fa7fcd335d9d199306665486694d4361547ccb19394c44/ruff-0.14.13-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:61f4e40077a1248436772bb6512db5fc4457fe4c49e7a94ea7c5088655dd21ae", size = 12805867, upload-time = "2026-01-15T20:14:59.272Z" },
+ { url = "https://files.pythonhosted.org/packages/7d/b3/0bd909851e5696cd21e32a8fc25727e5f58f1934b3596975503e6e85415c/ruff-0.14.13-py3-none-musllinux_1_2_i686.whl", hash = "sha256:6d02f1428357fae9e98ac7aa94b7e966fd24151088510d32cf6f902d6c09235e", size = 13208528, upload-time = "2026-01-15T20:15:03.732Z" },
+ { url = "https://files.pythonhosted.org/packages/3b/3b/e2d94cb613f6bbd5155a75cbe072813756363eba46a3f2177a1fcd0cd670/ruff-0.14.13-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:e399341472ce15237be0c0ae5fbceca4b04cd9bebab1a2b2c979e015455d8f0c", size = 13929242, upload-time = "2026-01-15T20:15:11.918Z" },
+ { url = "https://files.pythonhosted.org/packages/6a/c5/abd840d4132fd51a12f594934af5eba1d5d27298a6f5b5d6c3be45301caf/ruff-0.14.13-py3-none-win32.whl", hash = "sha256:ef720f529aec113968b45dfdb838ac8934e519711da53a0456038a0efecbd680", size = 12919024, upload-time = "2026-01-15T20:14:43.647Z" },
+ { url = "https://files.pythonhosted.org/packages/c2/55/6384b0b8ce731b6e2ade2b5449bf07c0e4c31e8a2e68ea65b3bafadcecc5/ruff-0.14.13-py3-none-win_amd64.whl", hash = "sha256:6070bd026e409734b9257e03e3ef18c6e1a216f0435c6751d7a8ec69cb59abef", size = 14097887, upload-time = "2026-01-15T20:15:01.48Z" },
+ { url = "https://files.pythonhosted.org/packages/4d/e1/7348090988095e4e39560cfc2f7555b1b2a7357deba19167b600fdf5215d/ruff-0.14.13-py3-none-win_arm64.whl", hash = "sha256:7ab819e14f1ad9fe39f246cfcc435880ef7a9390d81a2b6ac7e01039083dd247", size = 13080224, upload-time = "2026-01-15T20:14:45.853Z" },
+]
+
+[[package]]
+name = "ty"
+version = "0.0.12"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/b5/78/ba1a4ad403c748fbba8be63b7e774a90e80b67192f6443d624c64fe4aaab/ty-0.0.12.tar.gz", hash = "sha256:cd01810e106c3b652a01b8f784dd21741de9fdc47bd595d02c122a7d5cefeee7", size = 4981303, upload-time = "2026-01-14T22:30:48.537Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/7d/8f/c21314d074dda5fb13d3300fa6733fd0d8ff23ea83a721818740665b6314/ty-0.0.12-py3-none-linux_armv6l.whl", hash = "sha256:eb9da1e2c68bd754e090eab39ed65edf95168d36cbeb43ff2bd9f86b4edd56d1", size = 9614164, upload-time = "2026-01-14T22:30:44.016Z" },
+ { url = "https://files.pythonhosted.org/packages/09/28/f8a4d944d13519d70c486e8f96d6fa95647ac2aa94432e97d5cfec1f42f6/ty-0.0.12-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:c181f42aa19b0ed7f1b0c2d559980b1f1d77cc09419f51c8321c7ddf67758853", size = 9542337, upload-time = "2026-01-14T22:30:05.687Z" },
+ { url = "https://files.pythonhosted.org/packages/e1/9c/f576e360441de7a8201daa6dc4ebc362853bc5305e059cceeb02ebdd9a48/ty-0.0.12-py3-none-macosx_11_0_arm64.whl", hash = "sha256:1f829e1eecd39c3e1b032149db7ae6a3284f72fc36b42436e65243a9ed1173db", size = 8909582, upload-time = "2026-01-14T22:30:46.089Z" },
+ { url = "https://files.pythonhosted.org/packages/d6/13/0898e494032a5d8af3060733d12929e3e7716db6c75eac63fa125730a3e7/ty-0.0.12-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f45162e7826e1789cf3374627883cdeb0d56b82473a0771923e4572928e90be3", size = 9384932, upload-time = "2026-01-14T22:30:13.769Z" },
+ { url = "https://files.pythonhosted.org/packages/e4/1a/b35b6c697008a11d4cedfd34d9672db2f0a0621ec80ece109e13fca4dfef/ty-0.0.12-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:d11fec40b269bec01e751b2337d1c7ffa959a2c2090a950d7e21c2792442cccd", size = 9453140, upload-time = "2026-01-14T22:30:11.131Z" },
+ { url = "https://files.pythonhosted.org/packages/dd/1e/71c9edbc79a3c88a0711324458f29c7dbf6c23452c6e760dc25725483064/ty-0.0.12-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:09d99e37e761a4d2651ad9d5a610d11235fbcbf35dc6d4bc04abf54e7cf894f1", size = 9960680, upload-time = "2026-01-14T22:30:33.621Z" },
+ { url = "https://files.pythonhosted.org/packages/0e/75/39375129f62dd22f6ad5a99cd2a42fd27d8b91b235ce2db86875cdad397d/ty-0.0.12-py3-none-manylinux_2_17_ppc64.manylinux2014_ppc64.whl", hash = "sha256:d9ca0cdb17bd37397da7b16a7cd23423fc65c3f9691e453ad46c723d121225a1", size = 10904518, upload-time = "2026-01-14T22:30:08.464Z" },
+ { url = "https://files.pythonhosted.org/packages/32/5e/26c6d88fafa11a9d31ca9f4d12989f57782ec61e7291d4802d685b5be118/ty-0.0.12-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fcf2757b905e7eddb7e456140066335b18eb68b634a9f72d6f54a427ab042c64", size = 10525001, upload-time = "2026-01-14T22:30:16.454Z" },
+ { url = "https://files.pythonhosted.org/packages/c2/a5/2f0b91894af13187110f9ad7ee926d86e4e6efa755c9c88a820ed7f84c85/ty-0.0.12-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:00cf34c1ebe1147efeda3021a1064baa222c18cdac114b7b050bbe42deb4ca80", size = 10307103, upload-time = "2026-01-14T22:30:41.221Z" },
+ { url = "https://files.pythonhosted.org/packages/4b/77/13d0410827e4bc713ebb7fdaf6b3590b37dcb1b82e0a81717b65548f2442/ty-0.0.12-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2bb3a655bd869352e9a22938d707631ac9fbca1016242b1f6d132d78f347c851", size = 10072737, upload-time = "2026-01-14T22:30:51.783Z" },
+ { url = "https://files.pythonhosted.org/packages/e1/dd/fc36d8bac806c74cf04b4ca735bca14d19967ca84d88f31e121767880df1/ty-0.0.12-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:4658e282c7cb82be304052f8f64f9925f23c3c4f90eeeb32663c74c4b095d7ba", size = 9368726, upload-time = "2026-01-14T22:30:18.683Z" },
+ { url = "https://files.pythonhosted.org/packages/54/70/9e8e461647550f83e2fe54bc632ccbdc17a4909644783cdbdd17f7296059/ty-0.0.12-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:c167d838eaaa06e03bb66a517f75296b643d950fbd93c1d1686a187e5a8dbd1f", size = 9454704, upload-time = "2026-01-14T22:30:22.759Z" },
+ { url = "https://files.pythonhosted.org/packages/04/9b/6292cf7c14a0efeca0539cf7d78f453beff0475cb039fbea0eb5d07d343d/ty-0.0.12-py3-none-musllinux_1_2_i686.whl", hash = "sha256:2956e0c9ab7023533b461d8a0e6b2ea7b78e01a8dde0688e8234d0fce10c4c1c", size = 9649829, upload-time = "2026-01-14T22:30:31.234Z" },
+ { url = "https://files.pythonhosted.org/packages/49/bd/472a5d2013371e4870886cff791c94abdf0b92d43d305dd0f8e06b6ff719/ty-0.0.12-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:5c6a3fd7479580009f21002f3828320621d8a82d53b7ba36993234e3ccad58c8", size = 10162814, upload-time = "2026-01-14T22:30:36.174Z" },
+ { url = "https://files.pythonhosted.org/packages/31/e9/2ecbe56826759845a7c21d80aa28187865ea62bc9757b056f6cbc06f78ed/ty-0.0.12-py3-none-win32.whl", hash = "sha256:a91c24fd75c0f1796d8ede9083e2c0ec96f106dbda73a09fe3135e075d31f742", size = 9140115, upload-time = "2026-01-14T22:30:38.903Z" },
+ { url = "https://files.pythonhosted.org/packages/5d/6d/d9531eff35a5c0ec9dbc10231fac21f9dd6504814048e81d6ce1c84dc566/ty-0.0.12-py3-none-win_amd64.whl", hash = "sha256:df151894be55c22d47068b0f3b484aff9e638761e2267e115d515fcc9c5b4a4b", size = 9884532, upload-time = "2026-01-14T22:30:25.112Z" },
+ { url = "https://files.pythonhosted.org/packages/e9/f3/20b49e75967023b123a221134548ad7000f9429f13fdcdda115b4c26305f/ty-0.0.12-py3-none-win_arm64.whl", hash = "sha256:cea99d334b05629de937ce52f43278acf155d3a316ad6a35356635f886be20ea", size = 9313974, upload-time = "2026-01-14T22:30:27.44Z" },
+]