Edit on GitHub

[ROS] Controller Package

NOTE:

  • The test is done on ROS Kinetic Kame installed in Ubuntu 16.04.
  • Make sure ROS dependencies are installed before performing these instructions - Install ROS Packages

You can control each joint of OpenMANIPULATOR-X and check states of OpenMANIPULATOR-X through messages by utilizing an exclusive controller program.

Before launching the controller, please check open_manipulator_controller launch file in open_manipulator_controller package.

  <launch>
    <arg name="use_robot_name"         default="open_manipulator"/>

    <arg name="dynamixel_usb_port"     default="/dev/ttyUSB0"/>
    <arg name="dynamixel_baud_rate"    default="1000000"/>

    <arg name="control_period"         default="0.010"/>

    <arg name="use_platform"           default="true"/>

    <arg name="use_moveit"             default="false"/>
    <arg name="planning_group_name"    default="arm"/>
    <arg name="moveit_sample_duration" default="0.050"/>

    <group if="$(arg use_moveit)">
      <include file="$(find open_manipulator_controller)/launch/open_manipulator_moveit.launch">
        <arg name="robot_name"      value="$(arg use_robot_name)"/>
        <arg name="sample_duration" value="$(arg moveit_sample_duration)"/>
      </include>
    </group>

    <node name="$(arg use_robot_name)" pkg="open_manipulator_controller" type="open_manipulator_controller" output="screen" args="$(arg dynamixel_usb_port) $(arg dynamixel_baud_rate)">
        <param name="using_platform"       value="$(arg use_platform)"/>
        <param name="using_moveit"         value="$(arg use_moveit)"/>
        <param name="planning_group_name"  value="$(arg planning_group_name)"/>
        <param name="control_period"       value="$(arg control_period)"/>
        <param name="moveit_sample_duration"  value="$(arg moveit_sample_duration)"/>
    </node>

  </launch>

Parameter Description

The following patameters are used to set the controls.

use_robot_name

dynamixel_usb_port

dynamixel_baud_rate

control_period

use_platform

use_moveit, planning_group_name and moveit_sample_duration

Launch Controller

After setting the parameters, launch the OpenMANIPULATOR-X controller to start [ROS] Operation.

Open a terminal and then run roscore along with the following command.

$ roscore

Open a new terminal and launch the controller package.

$ roslaunch open_manipulator_controller open_manipulator_controller.launch

WARNING :
Please check each joint position before running OpenMANIPULATOR-X. It might stop operation because of joint position out of range.
The following feature shows you the ideal pose of OpenMANIPULATOR-X. Please adjust each joints along with the following picture when DYNAMIXEL torque isn’t enabled.

Follwing message will be shown in the Terminal after the process done successfully.

SUMMARY
========

PARAMETERS
 * /open_manipulator/control_period: 0.01
 * /open_manipulator/moveit_sample_duration: 0.05
 * /open_manipulator/planning_group_name: arm
 * /open_manipulator/using_moveit: False
 * /open_manipulator/using_platform: True
 * /rosdistro: kinetic
 * /rosversion: 1.12.14

NODES
  /
    open_manipulator (open_manipulator_controller/open_manipulator_controller)

ROS_MASTER_URI=http://localhost:11311

process[open_manipulator-1]: started with pid [23452]
Joint Dynamixel ID : 11, Model Name : XM430-W350
Joint Dynamixel ID : 12, Model Name : XM430-W350
Joint Dynamixel ID : 13, Model Name : XM430-W350
Joint Dynamixel ID : 14, Model Name : XM430-W350
Gripper Dynamixel ID : 15, Model Name :XM430-W350
[ INFO] [1544509070.096942788]: Succeeded to init /open_manipulator

TIP:

  • If you can’t load DYNAMIXEL, please check your DYNAMIXEL settings using the following command from DYNAMIXEL Workbench packages.
    rosrun dynamixel_workbench_controllers find_dynamixel /dev/ttyUSB0
    Even if you can’t find any DYNAMIXEL, please check firmware to use ROBOTIS software (R+ Manager 2.0 or DYNAMIXEL Wizard 2.0)
  • If you would like to change DYNAMIXEL ID, please check open_manipulator.cpp in the open_manipulator_lib folder. The default ID is 11, 12, 13, 14 for joints and 15 for the gripper

NOTE: OpenMANIPULATOR-X controller is compatible with Protocol 2.0. Protocol 1.0 does not support SyncRead instructions to access to multiple DYNAMIXEL’s’s simultaneously. Protocol 2.0 supports MX 2.0, X and Pro series, but it does not support AX, RX and EX.

Check Setting

Manipulator Description

NOTE:

  • The below instruction has been tested on Ubuntu 16.04 and ROS Kinetic Kame.
  • Make sure ROS dependencies are installed before performing these instructions. - Install ROS Packages.
  • Make sure to launch the OpenMANIPULATOR-X controller before use of the instruction

Publish a topic message to check the OpenMANIPULATOR-X setting.

$ rostopic pub /open_manipulator/option std_msgs/String "print_open_manipulator_setting"

<Manipulator Description> will be printed on Terminal. Launch the open_manipulator_controller. It is shown that present states of the OpenMANIPULATOR-X.
This parameter is descripted on open_manipulator.cpp in open_manipulator_libs package.
~/catkin_ws/src/open_manipulator/open_manipulator_libs/src/open_manipulator.cpp

    ----------<Manipulator Description>----------
    <Degree of freedom>
    4.000
    <Size of Components>
    5.000

    <Configuration of world>
    [Name]
    -World Name : world
    -Child Name : joint1
    [Static Pose]
    -Position :
    (0.000, 0.000, 0.000)
    -Orientation :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    [Dynamic Pose]
    -Linear Velocity :
    (0.000, 0.000, 0.000)
    -Linear acceleration :
    (0.000, 0.000, 0.000)
    -Angular Velocity :
    (0.000, 0.000, 0.000)
    -Angular acceleration :
    (0.000, 0.000, 0.000)

    <Configuration of gripper>
    [Component Type]
      Tool
    [Name]
    -Parent Name : joint4
    [Actuator]
    -Actuator Name : tool_dxl
    -ID :  15
    -Joint Axis :
    (0.000, 0.000, 0.000)
    -Coefficient :  -0.015
    -Limit :
        Maximum : 0.010, Minimum : -0.010
    [Actuator Value]
    -Value :  0.008
    -Velocity :  0.000
    -Acceleration :  0.000
    -Effort :  0.000
    [Constant]
    -Relative Position from parent component :
    (0.130, 0.000, 0.000)
    -Relative Orientation from parent component :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Mass :  0.000
    -Inertia Tensor :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Center of Mass :
    (0.000, 0.000, 0.000)
    [Variable]
    -Position :
    (0.138, -0.005, 0.015)
    -Orientation :
    (-0.006, 0.043, 0.999
    0.000, 0.999, -0.043
    -1.000, 0.000, -0.006)
    -Linear Velocity :
    (0.000, 0.000, 0.000)
    -Linear acceleration :
    (0.000, 0.000, 0.000)
    -Angular Velocity :
    (0.000, 0.000, 0.000)
    -Angular acceleration :
    (0.000, 0.000, 0.000)

    <Configuration of joint1>
    [Component Type]
      Active Joint
    [Name]
    -Parent Name : world
    -Child Name 1 : joint2
    [Actuator]
    -Actuator Name : joint_dxl
    -ID :  11
    -Joint Axis :
    (0.000, 0.000, 1.000)
    -Coefficient :  1.000
    -Limit :
        Maximum : 3.142, Minimum : -3.142
    [Actuator Value]
    -Value :  -0.043
    -Velocity :  0.000
    -Acceleration :  0.000
    -Effort :  0.000
    [Constant]
    -Relative Position from parent component :
    (0.012, 0.000, 0.017)
    -Relative Orientation from parent component :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Mass :  0.000
    -Inertia Tensor :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Center of Mass :
    (0.000, 0.000, 0.000)
    [Variable]
    -Position :
    (0.012, 0.000, 0.017)
    -Orientation :
    (0.999, 0.043, 0.000
    -0.043, 0.999, 0.000
    0.000, 0.000, 1.000)
    -Linear Velocity :
    (0.000, 0.000, 0.000)
    -Linear acceleration :
    (0.000, 0.000, 0.000)
    -Angular Velocity :
    (0.000, 0.000, 0.000)
    -Angular acceleration :
    (0.000, 0.000, 0.000)

    <Configuration of joint2>
    [Component Type]
      Active Joint
    [Name]
    -Parent Name : joint1
    -Child Name 1 : joint3
    [Actuator]
    -Actuator Name : joint_dxl
    -ID :  12
    -Joint Axis :
    (0.000, 1.000, 0.000)
    -Coefficient :  1.000
    -Limit :
        Maximum : 1.571, Minimum : -2.050
    [Actuator Value]
    -Value :  -0.052
    -Velocity :  0.000
    -Acceleration :  0.000
    -Effort :  0.000
    [Constant]
    -Relative Position from parent component :
    (0.000, 0.000, 0.058)
    -Relative Orientation from parent component :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Mass :  0.000
    -Inertia Tensor :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Center of Mass :
    (0.000, 0.000, 0.000)
    [Variable]
    -Position :
    (0.012, 0.000, 0.075)
    -Orientation :
    (0.998, 0.043, -0.052
    -0.043, 0.999, 0.002
    0.052, 0.000, 0.999)
    -Linear Velocity :
    (0.000, 0.000, 0.000)
    -Linear acceleration :
    (0.000, 0.000, 0.000)
    -Angular Velocity :
    (0.000, 0.000, 0.000)
    -Angular acceleration :
    (0.000, 0.000, 0.000)

    <Configuration of joint3>
    [Component Type]
      Active Joint
    [Name]
    -Parent Name : joint2
    -Child Name 1 : joint4
    [Actuator]
    -Actuator Name : joint_dxl
    -ID :  13
    -Joint Axis :
    (0.000, 1.000, 0.000)
    -Coefficient :  1.000
    -Limit :
        Maximum : 1.530, Minimum : -1.571
    [Actuator Value]
    -Value :  0.546
    -Velocity :  0.000
    -Acceleration :  0.000
    -Effort :  0.000
    [Constant]
    -Relative Position from parent component :
    (0.024, 0.000, 0.128)
    -Relative Orientation from parent component :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Mass :  0.000
    -Inertia Tensor :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Center of Mass :
    (0.000, 0.000, 0.000)
    [Variable]
    -Position :
    (0.029, -0.001, 0.204)
    -Orientation :
    (0.880, 0.043, 0.474
    -0.038, 0.999, -0.020
    -0.474, 0.000, 0.880)
    -Linear Velocity :
    (0.000, 0.000, 0.000)
    -Linear acceleration :
    (0.000, 0.000, 0.000)
    -Angular Velocity :
    (0.000, 0.000, 0.000)
    -Angular acceleration :
    (0.000, 0.000, 0.000)

    <Configuration of joint4>
    [Component Type]
      Active Joint
    [Name]
    -Parent Name : joint3
    -Child Name 1 : gripper
    [Actuator]
    -Actuator Name : joint_dxl
    -ID :  14
    -Joint Axis :
    (0.000, 1.000, 0.000)
    -Coefficient :  1.000
    -Limit :
        Maximum : 2.000, Minimum : -1.800
    [Actuator Value]
    -Value :  1.083
    -Velocity :  0.000
    -Acceleration :  0.000
    -Effort :  -2.690
    [Constant]
    -Relative Position from parent component :
    (0.124, 0.000, 0.000)
    -Relative Orientation from parent component :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Mass :  0.000
    -Inertia Tensor :
    (1.000, 0.000, 0.000
    0.000, 1.000, 0.000
    0.000, 0.000, 1.000)
    -Center of Mass :
    (0.000, 0.000, 0.000)
    [Variable]
    -Position :
    (0.138, -0.005, 0.145)
    -Orientation :
    (-0.006, 0.043, 0.999
    0.000, 0.999, -0.043
    -1.000, 0.000, -0.006)
    -Linear Velocity :
    (0.000, 0.000, 0.000)
    -Linear acceleration :
    (0.000, 0.000, 0.000)
    -Angular Velocity :
    (0.000, 0.000, 0.000)
    -Angular acceleration :
    (0.000, 0.000, 0.000)
    ---------------------------------------------

RViz

NOTE:

  • The test is done on ROS Kinetic Kame installed in Ubuntu 16.04.
  • Make sure ROS dependencies are installed before performing these instructions - Install ROS Packages

Load OpenMANIPULATOR-X on RViz.

$ roslaunch open_manipulator_description open_manipulator_rviz.launch

NOTE:

  • If you launched the OpenMANIPULATOR-X controller before launching the open_manipulator_controller file, the robot model on RViz would be synchronized with the actual robot.
  • If you would like to check only model of OpenMANIPULATOR-X without controling the actual OpenMANIPULATOR, you can launch the RViz without the OpenMANIPULATOR-X controller. You can change each joint by GUI, if the user launch only RViz by executing the following command : $ roslaunch open_manipulator_description open_manipulator_rviz.launch use_gui:=true

Message List

NOTE:

  • The test is done on ROS Kinetic Kame installed in Ubuntu 16.04.
  • Make sure ROS dependencies are installed before performing these instructions - Install ROS Packages
  • Make sure to launch the OpenMANIPULATOR-X controller before use of the instruction

OpenMANIPULATOR-X Controller provides topic and service messages to control manipulator and check the states of manipulator.

Topic

Topic Monitor

In order to check the topics of OpenMANIPULATOR-X controller, you can use rqt provided by ROS. Rqt is a Qt-based framework for GUI development for ROS. Rqt allows users to easily see topic status by displaying all topics on a topic list. You can see topic name, type, bandwidth, Hz and value on rqt.

Run rqt.

$ rqt

TIP: If rqt is not displayed, select the plugin -> Topic Monitor -> OpenMANIPULATOR.

Topics without a check mark will not be monitored. To monitor topics, click the checkbox next.

If you would like to see more details about topic message, click the button next to each checkbox.

Published Topic List

Published Topic List : A list of topics that the open_manipulator_controller publishes.

NOTE: These topics are messages for checking the status of the robot regardless of the robot’s motion.

/open_manipulator/joint_states(sensor_msgs/JointState) is a message indicating the states of joints of OpenMANIPULATOR-X. “name” indicates joint component names. “effort” shows currents of the joint DYNAMIXEL. “position” and “velocity” indicates angles and angular velocities of joints.

/open_manipulator/gripper/kinematics_pose(open_manipulator_msgs/KinematicsPose) is a message indicating pose (position and orientation) in task space. “position” indicates the x, y and z values of the center of the end-effector (tool). “Orientation” indicates the direction of the end-effector (tool) as quaternion.

/open_manipulator/states(open_manipulator_msgs/OpenManipulatorState) is a message indicating the status of OpenMANIPULATOR. “open_manipulator_actuator_state” indicates whether actuators (DYNAMIXEL) are enabled (“ACTUATOR_ENABLE”) or disabled (“ACTUATOR_DISABLE”). “open_manipulator_moving_state” indicates whether OpenMANIPULATOR-X is moving along the trajectory (“IS_MOVING”) or stopped (“STOPPED”).

/open_manipulator/*joint_name*_position/command(std_msgs/Float64) are the messages to publish goal position of each joint to gazebo simulation node. *joint_name* shows the name of each joint. The messages will only be published if you run the controller package with the use_platform parameter set to false.

/rviz/moveit/update_start_state(std_msgs/Empty) is a message to update start state of moveit! trajectory. This message will only be published if you run the controller package with the use_moveit parameter set to true.

Subscribed Topic List

Subscribed Topic List: A list of topics that the open_manipulator_controller subscribes.

NOTE: These topics are messages for checking the status of the robot regardless of the robot’s motion.

/open_manipulator/option(std_msgs/String) is used to set OpenMANIPULATOR-X options. “print_open_manipulator_setting” : is to request the open_manipulator_controller to display “Manipulator Description”.

/open_manipulator/option(moveit_msgs/DisplayTrajectory) is used to subscribe a planned joint trajectory published from moveit!

/move_group/goal(moveit_msgs/MoveGroupActionGoal) is used to subscribe a planning option data published from moveit!

/move_group/execute_trajectory/goal(moveit_msgs/ExecuteTrajectoryActionGoal) is used to subscribe states of trajectory execution published from moveit!

In addition, you can monitor topics through rqt whenever you have a topic added in your controller.

Service

Service Server List

NOTE: These services are messages to operate OpenMANIPULATOR-X or to change the status of DYNAMIXEL of OpenMANIPULATOR.

Service Server List : A list of service servers that open_manipulator_controller has.