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

This information is for the ROS 1 interface. If you are looking for ROS 2 support, please visit Yaskawa-Global/motoros2.

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 continuity and filtering

Motion planning tools like MoveIt or Tesseract will typically generate sufficiently smooth trajectories for use with motoman_driver.

When using other means of trajectory generation, please make sure to read the following paragraphs, and ensure trajectories submitted to the driver for execution fulfil these requirements.

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:

  • names (for each joint)

  • position (for each joint)

  • velocity (for each joint)

  • time_from_start

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-Industrial joint_trajectory_action server using the same messages and actions as other ROS-Industrial nodes: sensor_msgs/JointState and control_msgs/FollowJointTrajectory.

Robots with support packages

If there is a dedicated robot support package available (ie: motoman_S_support, where S is the name of the robot series) for the robot to be used with motoman_driver, use the following command to start it:

roslaunch motoman_S_support robot_interface_streaming_M.launch controller:=CCCCC robot_ip:=XXX.XXX.XXX.XXX

Where S is the robot series (ie: HC10 or GP180) and M is the variant (ie: HC10DT or GP180-120), and CCCCC is the controller model in lower case (ie: yrc1000 for a YRC1000).

As an example: to launch the driver for the HC10DT, the following command should be used:

roslaunch motoman_hc10_support robot_interface_streaming_hc10dt.launch controller:=yrc1000 robot_ip:=XXX.XXX.XXX.XXX

Refer to Working With ROS-Industrial Robot Support Packages for more information on robot support packages.

Robots without support packages

Consider creating a robot support package before trying to use motoman_driver. It will be more convenient, and more in-line with the use of other robot drivers.

New robot support packages can be created by duplicating the structure of an existing package, and updating it for the new robot model and variant.

We strongly recommended using robot support packages over using motoman_driver directly.

Refer to Working With ROS-Industrial Robot Support Packages for more information on robot support packages, and post a message on the Discussion forum in case you need help.

If no existing robot support package is available, the driver can be started directly.

To bring up all required interface nodes, the following command may be used:

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

CCCCC is the controller model in lower case. For example, to launch motoman_driver for a DX200:

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

Note the dx200 in the robot_interface_streaming_...launch filename.

Verifying the driver has started

In all cases, to verify everything has come up correctly (no errors), inspect the current sensor_msgs/JointState by running:

rostopic echo -c /joint_states

You should see the data update when the robot is jogged.

To check the command interface:

rostopic list | grep 'joint_trajectory_action'

This should result in several lines being printed, showing the command interface is online.

In case of errors or warnings while starting the driver or while trying to use it, please refer to motoman_driver/Troubleshooting.

Commanding motion

Using the topic interface directly (ie: /joint_path_command) is not recommended.

Please use the action interface, as it provides a much better user experience, and allows motoman_driver to perform additional checks on incoming trajectories and provide much more informative error messages.

The motion command interface can only be used with an appropriate actionlib client.

MoveIt uses such a client to execute trajectories it has planned, and MoveIt configuration packages, if provided, are already configured to use that action client interface to motoman_driver.

When using other motion planners, or when generating trajectories manually, an actionlib client script or node would have to be written. Refer to the actionlib/Tutorials for a generic introduction to actionlib.

An example action client for motoman_driver specifically may be found here (via ros-industrial/motoman#229).

Please refer to the Motion continuity and filtering section above for requirements on trajectories generated manually.

Joint Naming

Most Motoman robot support packages use joint names that differ from the ROS-Industrial standard joint names (ie: [joint_1, joint_2, ..., joint_N]). The provided robot support packages already configure the necessary parameters to take this alternative naming into account.

In case there is no robot support package available, and one cannot be created either (see the Robots without support packages section above), the following procedure can be used to define the correct joint names for your particular robot:

  1. Start ROS core if one is not already running:
     roscore
  2. In a new terminal, set the required 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. (Re)start the controller specific robot_interface_streaming_...launch file.

Start Position

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 by the driver.

Note: delays can be present in ROS applications, and relying on "the most recent JointState message" may not be sufficient.

Make sure to check the /robot_status topic (carrying industrial_msgs/RobotStatus messages) and inspect the in_motion field to determine when the robot has come to a full stop.

Behind the Scenes

This section provides additional information on the implementation of motoman_driver.

Everything described here is already taken care of by the various nodes provided by motoman_driver, and is not something regular users need to take into account.

The motoman driver requires additional messaging and handshaking beyond the standard ROS-Industrial 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

Troubleshooting

In case of errors or warnings while starting the driver or while trying to use it, please refer to motoman_driver/Troubleshooting.

If the information on that page is insufficient, or you require additional help, please post a message on the Discussion forum.

Wiki: motoman_driver/Tutorials/Usage (last edited 2023-05-26 18:30:48 by GvdHoorn)