(!) 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 multi port with joint command

Description: This tutorial describes how to running multi port

Keywords: robotis, dynamixel, position, multiport, pan, tilt

Tutorial Level: BEGINNER

IF YOU ALREADY CREATE my_dynamixel_workbench_tutorial PACKAGE, THEN YOU JUMP TO STEP 2.

Step 1: Create a package

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

Step 2: Prepare two Dynamixels

We need to prepare connected Dynamixels which are set same baudrate. In this tutorial shows connected three Dynamixels.

Step 3: Create a launch file for the multiport node

First we need a launch file in launch folder in my_dynamixel_workbench_tutorial package. This launch file connects to the dynamixel_workbench_controller 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-W350, MX-28

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

$ cd my_dynamixel_workbench_tutorial
$ mkdir launch
$ cd launch
$ gedit multi_port.launch

2. Type or copy&paste code below to connect dynamixel_workbench_controllers packages and set parameters

<launch>
<arg name="pan_device_name"      default="/dev/ttyUSB0"/>
<arg name="pan_baud_rate"        default="57600"/>

<arg name="tilt_device_name"      default="/dev/ttyUSB1"/>
<arg name="tilt_baud_rate"        default="57600"/>

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

<arg name="profile_velocity"           default="200"/>
<arg name="profile_acceleration"       default="50"/>

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

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

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

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

<node name="multi_port_example" pkg="dynamixel_workbench_controllers" type="multi_port" required="true" output="screen"/>
</launch>

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

$ sudo chmod a+rw /dev/ttyUSB0
$ sudo chmod a+rw /dev/ttyUSB1

4. Now we can run tutorial package:

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

If multi_controllers find linked Dynamixels, we could show state of it and command list and set torque on:

-----------------------------------------------------------------------
dynamixel_workbench controller; multi port example                    
-----------------------------------------------------------------------

MODEL   : XM430-W350
ID      : 1

MODEL   : XM430-W350
ID      : 2

-----------------------------------------------------------------------

MODEL   : MX-28
ID      : 1

-----------------------------------------------------------------------

Step 4: Check state of Dynamixel

Now, we can check a state of linked Dynamixels through /dynamixel_state topic::

$ rostopic echo /dynamixel_state

For example:

dynamixel_state: 
- 
    model_name: "XM430-W350"
    id: 1
    torque_enable: 1
    goal_current: 0
    goal_velocity: 0
    goal_position: 2050
    present_current: 0
    present_velocity: 0
    present_position: 2049
    moving: 0
- 
    model_name: "XM430-W350"
    id: 2
    torque_enable: 1
    goal_current: 0
    goal_velocity: 0
    goal_position: 1765
    present_current: 0
    present_velocity: 0
    present_position: 1765
    moving: 0
- 
    model_name: "MX-28"
    id: 1
    torque_enable: 1
    goal_current: 0
    goal_velocity: 0
    goal_position: 698
    present_current: 0
    present_velocity: 0
    present_position: 698
    moving: 0

Step 5: Run pan & tilt

We run the two linked Dynamixels using rosservice call or dynamixel_workbench_tutorials with different unit radian or raw value.

$ rosservice call /joint_command -- [unit] [id] [goal_position]

or

$ rosrun dynamixel_workbench_operators joint_operator [unit] [id] [goal_position]

Example

$ rosservice call /joint_command -- rad 1 2.0

or

$ rosrun dynamixel_workbench_operators joint_operator raw 1 3000

The pan & tilt is running!! If you have a question about running multi_port, please make anew issue.

Wiki: dynamixel_workbench_controllers/Tutorials/MultiPort (last edited 2018-01-17 10:14:03 by Darby Lim)