Skip to main content

A library to control dynamixel AX-12+ servos with python

Project description

Documentation Status

PyAX-12

Copyright (c) 2010,2015 Jeremie DECOCK (http://www.jdhp.org)

In collaboration with http://www.vorobotics.com

Description

PyAX-12 is an open source lightweight Python library to control Dynamixel AX-12+ actuators.

Watch a demo on youtube

Note:

This project is still in beta stage, so the API is not finalized yet.

Dependencies

PyAX-12 is tested to work with Python 3.4 under Gnu/Linux (Debian 8), MacOSX (Mavericks 10.9) and Windows (7). Any Python 3.X version under recent Gnu/Linux, MaxOSX and Windows systems should suit too.

PyAX-12 can also be run on Raspberry Pi through the GPIO connector.

Python-serial is the only dependency required to install PyAX-12.

Note:

If you use pip to install PyAX-12, Python-serial will be automatically downloaded and installed (see the following install section).

Installation

Gnu/Linux

You can install, upgrade, uninstall PyAX-12 with these commands (in a terminal):

pip install --pre pyax12
pip install --upgrade pyax12
pip uninstall pyax12

Or, if you have downloaded the PyAX-12 source code:

python3 setup.py install

Windows

You can install, upgrade, uninstall PyAX-12 with these commands (in a command prompt):

py -m pip install --pre pyax12
py -m pip install --upgrade pyax12
py -m pip uninstall pyax12

Or, if you have downloaded the PyAX-12 source code:

py setup.py install

MacOSX

You can install, upgrade, uninstall PyAX-12 with these commands (in a terminal):

pip install --pre pyax12
pip install --upgrade pyax12
pip uninstall pyax12

Or, if you have downloaded the PyAX-12 source code:

python3 setup.py install

Hardware setup

Official AX-12 documentation (archive).

Connecting AX-12 actuators to a computer (including Raspberry Pi computers) through USB port

The USB2Dynamixel can be used to connect AX-12 actuators to your computer. Actually, any FTDI serial/USB converter device should do the job.

For more information on USB2Dynamixel setup, check the official documentation.

Connecting AX-12 actuators to a Raspberry Pi through GPIO port

A small electronic circuit is needed to convert Raspberry Pi UART signals (on RX and TX pins) to the half-duplex ones required by Dynamixels (see this archive).

The chips that converts full-duplex into half-duplex are either 74HC126/74HC04 or 74LS241.

Control Dynamixel AX-12 with the 74LS241

Here are the schematics of the electronic circuit required to control Dynamixel AX-12 with the 74LS241.

74LS241 breadboard 74LS241 schematic

Additional explanation can be found on the following pages:

A PCB by Thiago Hersan is freely available here:

For other schematics, check the following pages:

Control Dynamixel AX-12 with the 774HC126/74HC04

For the 74HC126/74HC04, check the following page:

UART configuration

Increasing the bandwidth up to 1Mbps may require a special setup (not tested yet):

Otherwise keeping the bandwidth to 57600bps should work out of the box (make sure you use the right Dynamixel ID and the Dynamixel bandwidth is properly setup to 56700bps).

Additional information

See also: https://github.com/jeremiedecock/raspberry-pi-python-snippets/tree/master/dynamixel_ax12

Documentation

Example usage

In the following examples, the dynamixel_id, port and baudrate values should be adapted depending on your configuration:

  • for Linux users:

    • the port value should be something like

      • “/dev/ttyS0”, “/dev/ttyS1”, … if you use an actual serial port

      • “/dev/ttyUSB0”, “/dev/ttyUSB1”, … if you use an USB to serial adapter (like the USB2Dynamixel adapter)

    • the baudrate value should be the same than the one configured in Dynamixel units

  • for Windows users:

    • the port value should be something like “COM2”, “COM3”, … (see the COM port configuration in the Windows device manager)

    • the baudrate value should be the same than the one configured in the Dynamixel units and the Windows device manager (i.e. check the COM port configuration in the Windows device manager)

  • for MacOSX users:

    • the port value should be something like “/dev/tty.usbserial-XXX” if you use an USB to serial adapter like the USB2Dynamixel adapter

    • the baudrate value should be the same than the one configured in Dynamixel units

  • for Raspberry Pi users:

    • if you want to control AX-12 actuators through GPIO connector, don’t forget to set rpi_gpio to True in the Connection constructor (check the first following example)

    • the port value should be “/dev/ttyAMA0”

If you use the USB2Dynamixel device, make sure its switch is set on “TTL”.

Some other examples are available in the examples directory.

Ping a Dynamixel

This snippet prints True if the specified Dynamixel unit is connected and available at the given baudrate; otherwise it prints False.

from pyax12.connection import Connection

# Connect to the serial port
serial_connection = Connection(port="/dev/ttyUSB0", baudrate=57600)

dynamixel_id = 3

# Ping the third dynamixel unit
is_available = serial_connection.ping(dynamixel_id)

print(is_available)

# Close the serial connection
serial_connection.close()

Raspberry Pi users who connected AX-12 actuators to the GPIO connector should use the following code instead:

from pyax12.connection import Connection

# Connect to the serial port
serial_connection = Connection(port="/dev/ttyAMA0", rpi_gpio=True)

dynamixel_id = 3

# Ping the third dynamixel unit
is_available = serial_connection.ping(dynamixel_id)

print(is_available)

# Close the serial connection
serial_connection.close()

Scan (search available Dynamixel units)

This snippet prints the ID list of connected and available Dynamixel units (at the given baudrate).

from pyax12.connection import Connection

# Connect to the serial port
serial_connection = Connection(port="/dev/ttyUSB0", baudrate=57600)

# Ping the dynamixel unit(s)
ids_available = serial_connection.scan()

for dynamixel_id in ids_available:
    print(dynamixel_id)

# Close the serial connection
serial_connection.close()

Move the first Dynamixel unit to various position angles

This snippet moves the first Dynamixel unit to 0°, then -45°, -90°, -135°, -150° (the maximum CW angle), +150° (the maximum CCW angle), +135°, +90°, +45° and finally goes back to 0°.

from pyax12.connection import Connection
import time

# Connect to the serial port
serial_connection = Connection(port="/dev/ttyUSB0", baudrate=57600)

dynamixel_id = 1

# Go to 0°
serial_connection.goto(dynamixel_id, 0, speed=512, degrees=True)
time.sleep(1)    # Wait 1 second

# Go to -45° (45° CW)
serial_connection.goto(dynamixel_id, -45, speed=512, degrees=True)
time.sleep(1)    # Wait 1 second

# Go to -90° (90° CW)
serial_connection.goto(dynamixel_id, -90, speed=512, degrees=True)
time.sleep(1)    # Wait 1 second

# Go to -135° (135° CW)
serial_connection.goto(dynamixel_id, -135, speed=512, degrees=True)
time.sleep(1)    # Wait 1 second

# Go to -150° (150° CW)
serial_connection.goto(dynamixel_id, -150, speed=512, degrees=True)
time.sleep(1)    # Wait 1 second

# Go to +150° (150° CCW)
serial_connection.goto(dynamixel_id, 150, speed=512, degrees=True)
time.sleep(2)    # Wait 2 seconds

# Go to +135° (135° CCW)
serial_connection.goto(dynamixel_id, 135, speed=512, degrees=True)
time.sleep(1)    # Wait 1 second

# Go to +90° (90° CCW)
serial_connection.goto(dynamixel_id, 90, speed=512, degrees=True)
time.sleep(1)    # Wait 1 second

# Go to +45° (45° CCW)
serial_connection.goto(dynamixel_id, 45, speed=512, degrees=True)
time.sleep(1)    # Wait 1 second

# Go back to 0°
serial_connection.goto(dynamixel_id, 0, speed=512, degrees=True)

# Close the serial connection
serial_connection.close()

Bug reports

To search for bugs or report them, please use the PyAX-12 Bug Tracker at:

https://github.com/jeremiedecock/pyax12/issues

License

The PyAX-12 library is provided under the terms and conditions of the MIT License.

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distribution

pyax12-0.5.dev3.tar.gz (1.2 MB view hashes)

Uploaded source

Supported by

AWS AWS Cloud computing and Security Sponsor Datadog Datadog Monitoring Fastly Fastly CDN Google Google Download Analytics Microsoft Microsoft PSF Sponsor Pingdom Pingdom Monitoring Sentry Sentry Error logging StatusPage StatusPage Status page