A python library to control dynamixel servo motors
Project description
Acknowledgement
Most of the source code and architecture used in this project was adapted from the PyDynamixel_v2 library made by the amazing members of TauraBots.
About this library
This library wraps the dynamixel_sdk to hide its complexity and attempts to expose its features in a more user-friendly manner.
It has three classes.
DxlCommis responsible for opening and starting a communication port like USB.Servois responsible for controlling dynamixel motors. You can use it for things such as getting the position of the servo, sending to to a goal position etc.ServoGroupis responsible for sending commands and receiving data from servos with the same control table and protocol simultaneously.
Installing
Simple install
The quickest and easiest way of installing this library is through pip.
Run the command pip install dynamixel-py
Install from source
- Clone this repository using
git clone https://github.com/rohitthampy/dynamixel_py.git - Create a virtual environment and
pip install dynamixel-sdk - Create your python project at the root of this repository.
- Have a look at the examples for inspiration.
Usage Examples
Examples for controlling one motor at a time
- Getting position data from a servo
import time
from dynamixel_py import DxlComm, Servo
# Starting communication with U2D2 or similar device
serial = DxlComm(port="/dev/ttyUSB0") # Eg: COM28 for windows
# Declaring a servo object
servo1 = Servo(servo_id=1, control_table="XL330")
# Disabling torque for a single servo
servo1.torque_enabled(is_enabled=False)
try:
while True:
print(servo1.get_position())
time.sleep(0.1)
except KeyboardInterrupt:
print("Stopping program")
- Setting the position of a servo
import time
from dynamixel_py import DxlComm, Servo
# Starting communication with U2D2 or similar device
serial = DxlComm(port="/dev/ttyUSB0") # Eg: COM28 for windows
# Declaring a servo object
servo1 = Servo(servo_id=1, control_table="XL330")
# Enabling torque for a single servo
servo1.torque_enabled(is_enabled=True)
count_1 = 0
servo1.set_position(count_1)
time.sleep(1)
while count_1 < 359:
count_1 += 1
servo1.set_position(count_1)
while count_1 > 0:
count_1 -= 1
servo1.set_position(count_1)
servo1.set_position(180)
time.sleep(1)
- Controlling motors of Protocol 1.0 and Protocol 2.0
import time
from dynamixel_py import DxlComm, Servo
# Starting communication with U2D2 or similar device
serial = DxlComm(port="/dev/ttyUSB0", baud_rate=1000000) # Eg: COM28 for windows
# Declaring servo objects
# By default, the baud rate for the XC330 is 57600, this was changed to 1000000 to work with the AX12
servo1 = Servo(servo_id=1, control_table="XC330") # Using the default protocol version which is 2
servo2 = Servo(servo_id=11, control_table="AX12", protocol_version=1)
# Enabling torque for both servos
servo1.torque_enabled(is_enabled=True)
servo2.torque_enabled(is_enabled=True)
count_1 = 0
servo1.set_position(count_1)
time.sleep(1)
while count_1 < 359:
count_1 += 1
servo1.set_position(count_1)
servo2.set_position(count_1)
while count_1 > 0:
count_1 -= 1
servo1.set_position(count_1)
servo2.set_position(count_1)
servo1.set_position(180)
servo2.set_position(180)
time.sleep(1)
Examples using sync read/write to control motor simultaneously
- Using sync read to read positions of multiple motors
from dynamixel_py import DxlComm, Servo, ServoGroup
serial = DxlComm(port="/dev/ttyUSB0")
servo1 = Servo(servo_id=1, control_table="XL330")
servo2 = Servo(servo_id=12, control_table="XL330")
servo3 = Servo(servo_id=15, control_table="XL330")
servo_group = ServoGroup()
servo_group.add_servos([servo1, servo2, servo3])
print(servo_group.get_total_servos())
servo_group.sync_torques_enabled(False)
try:
while True:
print(servo_group.sync_get_positions())
except KeyboardInterrupt:
print("Stopping program")
- Using sync write to simultaneously control multiple servos
import time
from dynamixel_py import DxlComm, Servo, ServoGroup
serial = DxlComm(port="/dev/ttyUSB0")
servo1 = Servo(servo_id=1, control_table="XL330")
servo2 = Servo(servo_id=12, control_table="XL330")
servo3 = Servo(servo_id=15, control_table="XL330")
servo_group = ServoGroup()
servo_group.add_servos([servo1, servo2, servo3])
print(servo_group.get_total_servos())
servo_group.sync_torques_enabled(True)
servo_group.sync_set_positions([30, 45, 90])
time.sleep(1)
servo_group.remove_servos([servo1, servo2, servo3])
print(servo_group.get_total_servos())
- Using sync read and write together
import time
import random
from dynamixel_py import DxlComm, Servo, ServoGroup
serial = DxlComm(port="/dev/ttyUSB0")
servo1 = Servo(servo_id=1, control_table="XL330")
servo2 = Servo(servo_id=12, control_table="XL330")
servo3 = Servo(servo_id=15, control_table="XL330")
servo_group = ServoGroup()
servo_group.add_servos([servo1, servo2, servo3])
print(servo_group.get_total_servos())
servo_group.sync_torques_enabled(True)
print(servo_group.sync_get_positions())
servo_group.sync_set_positions([180, 180, 180])
time.sleep(0.5)
# Sends the servos to random positions between 0 and 350 degrees
for i in range(10):
servo_group.sync_set_positions([random.randint(0, 350),
random.randint(0, 350),
random.randint(0, 350)])
time.sleep(0.5)
print(servo_group.sync_get_positions())
servo_group.sync_set_positions([180, 180, 180])
time.sleep(0.5)
Project details
Release history Release notifications | RSS feed
Download files
Download the file for your platform. If you're not sure which to choose, learn more about installing packages.
Source Distribution
Built Distribution
Filter files by name, interpreter, ABI, and platform.
If you're not sure about the file name format, learn more about wheel file names.
Copy a direct link to the current filters
File details
Details for the file dynamixel_py-0.0.5.tar.gz.
File metadata
- Download URL: dynamixel_py-0.0.5.tar.gz
- Upload date:
- Size: 12.1 kB
- Tags: Source
- Uploaded using Trusted Publishing? No
- Uploaded via: twine/6.1.0 CPython/3.13.2
File hashes
| Algorithm | Hash digest | |
|---|---|---|
| SHA256 |
8cc2aedc1abf08fff8cb9922873abe280ad5c21f9e6b8f06f71e46dc6bb18efe
|
|
| MD5 |
79d07a68aa54986c76fed374ec37c8fc
|
|
| BLAKE2b-256 |
cedec55ad7ccfac03bf5a8d7d216b101a33c9344373fb6e84889ace6b4996b24
|
File details
Details for the file dynamixel_py-0.0.5-py3-none-any.whl.
File metadata
- Download URL: dynamixel_py-0.0.5-py3-none-any.whl
- Upload date:
- Size: 11.9 kB
- Tags: Python 3
- Uploaded using Trusted Publishing? No
- Uploaded via: twine/6.1.0 CPython/3.13.2
File hashes
| Algorithm | Hash digest | |
|---|---|---|
| SHA256 |
83a04b95c589f9a3fbc38f6e59b922501d447ae96f11ca6acb7491d1becaede1
|
|
| MD5 |
7c085299a9fe9a0e22826d374a1d1717
|
|
| BLAKE2b-256 |
f903aed8d5f097de91b9a1cd16c1a3f264b81a2f548f2b5d9f4ea9de6683ecc1
|