[Documentation] [TitleIndex] [WordIndex

(!) 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.

Using the Motoman FS/DX/YRC ROS Interface

Description: This tutorial walks through the steps of using the DX/FS/YRC interface

Keywords: Motoman, DX100, DX200, FS100, YRC1000, Industrial, motoman_driver

Tutorial Level: BEGINNER

Preparation

Robot Controller

Prior to executing ROS motion:

  1. Make sure the robot controller is ready:
    • Installation and setup of MotoROS driver must be complete
    • Pendant key switch must be in Remote mode

    • The E-stop latch must be released
  2. Make sure the ROS trajectory node has been enabled by invoking the robot_enable service

When a new ROS motion command is received, the robot will check for the required conditions. If the controller is not ready to execute motion, an error message will be printed, and the motion command will be rejected. Make sure to re-enable the robot by calling robot_enable again before re-sending the motion commands.

If desired, the robot_disable service can be used to disable the trajaectory node and prevent further execution of incoming trajectories (this stops the job when MotoROS (the MotoPlus application) is in the IDLE state).

Motion Filtering

The motoman driver interface is fairly low-level, and attempts to execute the commanded motion with minimal additional robot-side filtering. Although the ROS trajectory_msgs/JointTrajectory message allows for creation of trajectories without providing data for all fields, the following trajectory elements are required by the motoman driver interface:

NOTE: acceleration is ignored, and is calculated from other fields

Since the commanded motion is executed without additional filtering, user applications must supply well-filtered trajectories to achieve smooth motion on the robot hardware. If simplistic trajectories are provided to the controller that do not use smooth and consistent position, velocity, and timing data, the robot motion may appear jerky or "noisy". Smooth motion is definitely achievable on the controller, but requires the users to properly pre-filter the trajectories using available ROS tools.

Usage

The motoman driver integrates with the standard ROS-I joint_trajectory_action server using the same messages as other ROS-I nodes: joint_states and joint_path_command.

To bring up all required interface nodes, run (all on one line):

roslaunch motoman_driver robot_interface_streaming_YYYYY.launch robot_ip:=XXX.XXX.XXX.XXX

YYYY is the controller model in lower case. For example, to launch DX200:

roslaunch motoman_driver robot_interface_streaming_dx200.launch robot_ip:=XXX.XXX.XXX.XXX

If everything comes up correctly (no errors), you can observe the reported joint positions using:

rostopic echo joint_states

Joint Naming

Most motoman robots use joint names that differ from the ROS-I "standard" joint names ([joint_1, joint_2, ..., joint_N]). To define the correct joint names for your particular robot, use the following procedure:

  1. Start ROS core:
    • roscore
  2. In a new terminal, create a parameter using one of the following methods
    1. Load the robot URDF into the robot_description parameter:

      rosparam load <path to URDF> robot_description

      will automatically use joint names ordered from Base->Tip

    2. Set the controller_joint_names parameter:

      rosparam set controller_joint_names "[joint_s, joint_l, ..., joint_t]"

      explicitly set the order and names of joints expected by the controller

  3. Restart the robot_interface launch file.

Start Position

The motoman driver requires the first point in the trajectory to match the current robot position. Errors in this position will propagate through the motion trajectory, and will result in deviations from the commanded motion trajectory. As a result, both the ROS and MotoPlus code verify this start condition with an extremely fine tolerance (1e-6 radians, 10 encoder pulse counts). Motion trajectories that do not meet this requirement will be rejected.

move_to_joint.py tool
For ease-of-use, a simple command line tool is provided that will move the robot into the desired start position. This tool generates a basic 2-point trajectory from the current robot position to the specified target position using a slow (10 sec duration) move. The tool will either accept a list of joint positions or a bag-file containing a joint_path_command as input:

rosrun motoman_driver move_to_joint.py "[J1, J2, J3, ...]"

rosrun motoman_driver move_to_joint.py trajectory.bag

rosrun motoman_driver move_to_joint.py "[J1, J2, J3, ...]" 5.0
  - 2nd parameter [optional] is the move duration (in sec).  Default is 10 sec.

By default, this tool uses standard motoman joint names:

You can specify the joint names directly using the ~joint_names parameter:

Behind the Scenes

The motoman driver requires additional messaging and handshaking beyond the standard ROS-I simple_message protocol. This section describes the messaging sequence used by the motion_streaming_interface node to send trajectory data to the controller:

  1. JointTrajectory message is received

  2. MotomanMotionCtrl::CheckReady message is sent to the controller

    • if not ready, MotomanMotionCtrl::StartTrajectoryMode message is sent to the controller

      • Controller checks start state and enables robot drives

  3. Loop over all points in the trajectory
    1. JointTrajectoryFull message sent to controller

    2. if controller buffer is full, it will respond BUSY

    3. resend JointTrajectoryFull message until OK response received

  4. MotomanMotionCtrl::StopTrajectoryMode message is sent when node is closed


2019-07-20 12:55