Connecting to Dynamixel bus
Description: This tutorial describes how to connect and examine raw feedback from Robotis Dynamixel servos.Keywords: robotis,dynamixel,connecting,feedback
Tutorial Level: BEGINNER
Contents
Step 1: Create a package
Before we begin we need to create a package that has proper dependencies and will contain all the files we create in this tutorial. Note: before executing command listed below make sure that the current directory is on the ROS path.
roscreate-pkg dynamixel_tutorials dynamixel_controllers roscd dynamixel_tutorials
Step 2: Create a launch file for the manager node
We assume that the Dynamixel servos are connected to /dev/ttyUSB0 serial port.
First we need to start up the controller manager that will connect to the motors and publish raw feedback data (e.g. current position, goal position, error, etc.) at a specified rate. The easiest way to do that is to write a launch file that will set all necessary parameters. Let's copy and paste the following text into a controller_manager.launch file.
<launch>
<!-- Start the low-level driver manager with parameters -->
<node name="ttyUSB0_manager" pkg="dynamixel_controllers" type="controller_manager.py" output="screen">
<param name="port_name" type="str" value="/dev/ttyUSB0"/>
<param name="baud_rate" type="int" value="1000000"/>
<param name="min_motor_id" type="int" value="1"/>
<param name="max_motor_id" type="int" value="5"/>
<param name="update_rate" type="int" value="10"/>
</node>
</launch>Now if we execute:
roslaunch dynamixel_tutorials controller_manager.launch
We should see the status output similar to the following:
[INFO] 1295282870.051953: Pinging motor IDs 1 through 5... [INFO] 1295282870.103676: Found motors with IDs: [4]. [INFO] 1295282870.141504: There are 1 AX-12+ servos connected [INFO] 1295282870.141857: Dynamixel Manager on port /dev/ttyUSB0 initialized
Naturally the output depends on what motors are connected to the USB bus.
Step 3: Examine motor feedback
Now the controller manager is publishing feedback on /motor_states/ttyUSB0 topic. First, let's check that the topic is there:
rostopic list
The output should look similar to the one shown below:
/motor_states/ttyUSB0 /rosout /rosout_agg
One of the topic in the list should be the /motor_states/ttyUSB0 topic. Let's see what kind of information is published:
rostopic echo /motor_states/ttyUSB0
In this case we only have one AX-12+ motor with id 4 connected:
motor_states:
-
timestamp: 1295283169.24
id: 4
goal: 525
position: 543
error: 18
speed: 0
load: 0.5625
voltage: 12.3
temperature: 37
moving: FalseThat's it! To be able to actually control the servos we need to define controllers. We will learn how to do that in the next tutorial.






