(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Dynamixel workbench single manager with command line

Description: This tutorial describes how to start single manager and control address value in linked Dynamixel using command line

Keywords: robotis, dynamixel, single manager

Tutorial Level: BEGINNER

Next Tutorial: Dynamixel workbench single manager with GUI

Step 1: Create a package

$ cd ~/catkin_ws/src
$ catkin_create_pkg my_dynamixel_workbench_tutorial std_msgs roscpp

Step 2: Create a launch file for the single manager node

First we need a launch file in launch folder in my_dynamixel_workbench_tutorial package. This launch file connects to the dynamixel_workbench_single_manager package and sets device name and baudrate of a Dynamixel. We assume that the Dynamixel is connected to /dev/ttyUSB0 and baudrate 57600. If not, make sure you set your device name and baudrate correctly. NOTE: IN THIS TUTORIAL, WE USE XM430-W210-R

1. Make a launch file in ros package which we created

$ cd my_dynamixel_workbench_tutorial
$ mkdir launch
$ cd launch
$ gedit single_manager.launch

2. Type or Copy&Paste code below to connect dynamixel_workbench_single manager packages and set parameters

<launch>
<arg name="use_ping"         default="false"/>
<arg name="id"               default="1"/>

<arg name="device_name"      default="/dev/ttyUSB0"/>
<arg name="baud_rate"        default="57600"/>

<arg name="scan_range"       default="10"/>

<param name="ping"             value="$(arg use_ping)"  type="bool"/>
<param name="ping_id"          value="$(arg id)"/>

<param name="device_name"      value="$(arg device_name)"/>
<param name="baud_rate"        value="$(arg baud_rate)"/>

<param name="scan_range"        value="$(arg scan_range)"/>

<node name="single_dynamixel_monitor" pkg="dynamixel_workbench_single_manager"
        type="single_dynamixel_monitor" required="true" output="screen"/>

<node name="single_dynamixel_controller" pkg="dynamixel_workbench_single_manager"
        type="single_dynamixel_controller" required="true" output="screen"/>
</launch>

NOTE: Each Dynamixel has different default baudrate (e.g. 1000000 or 57600). Before excute the single manager, it needs to be checked the baudrate of Dynamixel e-MANUAL

3. Before we operating this package, we need to access permission for USB device

$ sudo chmod a+rw /dev/ttyUSB0

4. Now we can run tutorial package:

$ cd ~/catkin_ws && catkin_make 
$ roslaunch my_dynamixel_workbench_tutorial single_manager.launch

If single_manager find linked Dynamixel, we could show state of it and command list:

[ID] 1, [Model Name] XM430-W210, [BAUD RATE] 57600 [VERSION] 2.0
dynamixel_workbench_single_manager : Init Success!

----------------------------------------------------------------------
Single Manager supports GUI (dynamixel_workbench_single_manager_gui)  
----------------------------------------------------------------------
Command list :
[help|h|?].........: help
[info].............: information of a Dynamixel
[table]............: check a control table of a Dynamixel
[torque_on]........: torque on Dynamixel
[torque_off].......: torque off Dynamixel
[goal].............: set data to goal position address ex) goal 1024
[id]...............: change id ex) id 3
[baud].............: change baud rate ex) baud 57600
[version]..........: change protocol version ex) version 2.0
[reboot]...........: reboot a Dynamixel(only protocol version 2.0)
[reset]............: command for all data back to factory settings values
[table_item].......: change address value of a Dynamixel ex) Goal_Position 1024
[exit].............: shutdown
----------------------------------------------------------------------
Press Enter Key To Command A Dynamixel
[CMD]

Step 3: Check state of Dynamixel

Now, we can check a state of linked Dynamixel through /dynamixel/[motor_name] topic:

$ rostopic echo /dynamixel/[motor_name]

For example:

Model_Number: 1030
Firmware_Version: 40
ID: 1
Baud_Rate: 1
Return_Delay_Time: 250
Drive_Mode: 0
Operating_Mode: 1
Secondary_ID: 255
Protocol_Version: 2
Homing_Offset: 0
Moving_Threshold: 10
Temperature_Limit: 80
Max_Voltage_Limit: 160
Min_Voltage_Limit: 95
PWM_Limit: 885
Current_Limit: 32767
Acceleration_Limit: 32767
Velocity_Limit: 480
Max_Position_Limit: 4095
Min_Position_Limit: 0
Shutdown: 1
Torque_Enable: 0
LED: 0
Status_Return_Level: 2
Registered_Instruction: 0
Hardware_Error_Status: 0
Velocity_I_Gain: 1920
Velocity_P_Gain: 100
Position_D_Gain: 0
Position_I_Gain: 0
Position_P_Gain: 800
Feedforward_2nd_Gain: 0
Feedforward_1st_Gain: 0
Bus_Watchdog: 0
Goal_PWM: 885
Goal_Current: 1193
Goal_Velocity: 480
Profile_Acceleration: 0
Profile_Velocity: 0
Goal_Position: 2320
Realtime_Tick: 30351
Moving: 0
Moving_Status: 0
Present_PWM: 0
Present_Load: 0
Present_Current: -3
Present_Velocity: 0
Present_Position: 2320
Velocity_Trajectory: 0
Position_Trajectory: 2320
Present_Input_Voltage: 121
Present_Temperature: 28

Step 3: Send command to Dynamixel

We operate a Dynamixel using command. Address names can be checked published message or using table command. If user wants to specific information about control table of a Dynamixel, please follow the link E-MANUAL. NOTE: BEFORE YOU COMMAND, YOU NEED TO PRESS ENTER KEY

 [CMD]torque_on
 [CMD]goal 2048

The Dynamixel is running!! If you have a question about running single_manager, please make anew issue.

Wiki: dynamixel_workbench_single_manager/Tutorials/CommandLine (last edited 2018-01-17 10:02:01 by Darby Lim)