REP: I0001 Title: Industrial Robot Controller Motion/Status Interface (Version 2) Author: Shaun Edwards Status: Draft Type: Standards Track Created: 19-August-2013
- Abstract
- Motivation
- Definitions
- Requirements
- Design Assumptions
- Simple Message Structures
- Communications Method
- Motion Interface
- State Interface
- Backwards Compatibility
- Todo's
- References
- Copyright
This REP specifies the second version of the ROS-Industrial robot controller client/server motion/state/status interface [1]. It is relevant to anybody using ROS-I standard libraries to communicate with an industrial robot controller. Note: This spec does not specify the ROS API [2], which is specified separately. However, it does make some assumptions about the interface which are not explicitly defined by the API but are assumed by higher level packages like MoveIt [3].
- The following definitions are used throughout:
- joint, axis - A single controllable item. Typically revolute(rotational) or linear motion.
- group, motion group, arm - A group of joints or axes. At the controller level these are non-overlapping (i.e. a joint can be in one and only one group.
- synchronous motion - coordinated motion (at the real time level) of a group of joints
- asynchronous motion - independent control of joints or groups.
The first version of the motion/status interface (loosely documented in code and wikis) worked well for single arm manipulators. Multi-arm (asynchronous or synchronous) was not supported in a generic manor that could be used across all platforms [4]. Some attempts were made to support multiple arms using the existing interface, but these often required multi-arm joint states which could exceed the max number of joints and did not allow for mixed multi-arm/single-arm motion. The intent of this REP is to define a new set of simple messages[#simp_msg]_ for multi-arm control. These messages will replace existing motion control message (they will be deprecated). The approach taken in the REP is one that creates a new set of clients for robot motion. The underlying simple message libraries will remain unchanged (except for the addition of new messages).
- The industrial robot controller motion interface shall meet the following requirements:
- A single node shall act as the point of control (motion). All trajectory topics shall be routed through this node to the controller. This not only simplifies implementation (a controller communicates with a single client) but single point control is key tenant of safety and predictable systems.
- It shall allow for synchronous and asynchronous control of single and multiple arms (i.e. a unified driver that allows for different types of control to be achieved dynamically without reconfiguration)
- All incoming joint trajectories should be fully populated with at least position, velocity, acceleration, and timing information [5]. (NOTE: Certain controllers may not require all data, but this will be different between controllers).
- Effort/force control shall be supported by the messaging structure but not required for robot motion control. Most industrial platforms do not offer this capability. This requirement allows for some level of future proofing and expansion in the future.
- Joint groups shall be statically defined at the controller level. ROS trajectories must define motion for all the joints in a group (NOTE: Some controllers have additional axes that aren't used by all robots. In these cases the axes are ignored by the controller. However, the motion node should be smart enough to reorder or shift joint values based on configuration data).
- Joint trajectories shall be executed one at a time. Receipt of a new trajectory before the current trajectory is finished shall either result in a motion stop, followed by the execution of the new trajectory.
- A single node shall publish joint/robot state information, utilizing a single common connection to the controller.
- Joint states shall be sent from the controller to that robot state node in a single dynamic message that encompasses all groups.
- Group status shall be sent from the controller to that robot state node in a single dynamic message that encompasses all groups.
- The controller joint group structure shall be statically defined at node start up (i.e. in a yaml file read on node construction). Motion groups are predefined (statically) by most controllers.
- The following assumptions are inherent in the client/server design:
- All joints (regardless of group) shall be uniquely named.
The simple message package [6] provides libraries for communicating with industrial robot controllers. This includes connection handling libraries and message packing/unpacking capabilities. The default robot connection is TCP/IP, although any method of transferring byte data is easily supported. While not required, traditional message structures have been statically defined (i.e. fixed arrays). This is because robot controllers cannot dynamically allocate memory. If dynamic messages are used, controller side servers should utilize fixed size data that comply with some physical limitation (i.e. the controller can only handle ten axes in a single group) and then handle the error cases when the simple message exceeds that amount. By creating dynamic simple messages for motion and status, multiple arm control and monitoring can be achieved.
The dynamic joint point is meant to mimic the ROS JointTrajectory message structure [5]. A one-to-one mapping of the joints included in the ROS message to the simple message shall be created. By encapsulating the entire trajectory in a single message, synchronized motion is possible.:
length: true message/data length header: standard msg_type, comms_type, reply_code fields sequence: num_groups: # of motion groups included in this message group[]: # length of this array must match num_groups id: control-group ID for use on-controller num_joints: # of joints in this motion group valid_fields: #bit field for following items # length of the following items must match num_joints, order set by controller. Invalid fields (see bit field above) are not included, resulting in a shorter message. positions[] velocities[] accelerations[] effort[] time_from_start
The dynamic joint state is meant to mimic both the ROS JointState and FollowJointTrajectoryFeedback message. The JointState message specifies the current kinematic/dynamic state of the robot. The feedback message specifies the current control state of the system (this may or may not be available on all systems).:
length: true message/data length header: standard msg_type, comms_type, reply_code fields sequence: num_groups: # of motion groups included in this message group[]: # length of this array must match num_groups id: control-group ID for use on-controller num_joints: # of joints in this motion group valid_fields: #bit field for following items # length of the following items must match num_joints, order set by controller. Invalid fields (see bit field above) are not included, resulting in a shorter message. positions[] velocities[] accelerations[] effort[] position_desired[] position_errors[] velocity_desired[] velocity_errors[] effort_desired[] effort_error[]
The dynamic group status is meant to mimic both the ROS-I RobotStatus message. See the RobotStatus message[#rbt_stat]_ for field descriptions.:
length: true message/data length header: standard msg_type, comms_type, reply_code fields num_groups: # of motion groups included in this message group[]: # length of this array must match num_groups id: control-group ID for use on-controller mode: e_stopped: drives_powered: motion_possible: in_motion: in_error:
The communications method between the ROS PC and robot controller will not change with this REP. It will continue to be via TCP sockets. This REP covers two existing socket connections: motion on one socket, and state and status on a separate socket.
In the first version of the motion interface, some robots allowed motion streaming (i.e. point by point) and others required motion downloading (i.e. entire trajectory). This distinction was invisible to the user, as the ROS interface receives entire trajectories in a single message. Motion download interfaces were created because it was thought that they would provide better (smoother and faster) motion, this hasn't been found to be true. Dense trajectories resulted in the same slow, disjointed motion as motion streaming interfaces. For the purposes of this second version, only streaming interfaces will be considered. This simplifies the problem of switching between synchronous and asynchronous motion.
- The motion interface can be expressed as four variations:
- Single Arm - Only a single arm group is defined, no synchronization required.
- Multi-Arm (Sync) - Multiple arms are defined. A single joint trajectory containing all joints is received and sent to the controller in a single simple message. The controller receives the message and performs synchronized motion.
- Multi-Arm (Async) - Multiple arms are defined. Multiple joint trajectories for each arm/motion group are received and sent to the controller in independent messages. The controller receives the messages and performs asynchronous motion. NOTE: Although this may look like synchronized motion there isn't a real time guarantee that the waypoints across multiple groups are reached at the same time.
- Multi-Arm (Sync & Async) - Combination of the two above operating modes.
In order to support the various methods of control, the motion node must be somewhat dynamic/statically reconfigurable[see current parameters]. The node must be able to support subscriptions to multiple topics (all of the same type) as well as conversion from ROS group organizations to controller organization. This mapping would look similar to the MoveIt controller manager[#ctrl_mgr]_. The yaml file will contain a list of structures that defines the joint trajectory topics as well as the mapping to the controller.:
topic_list: - name: <topic name> ns: <topic namespace> group: <controller group#> joints: - <joint_1> - <joint_2> - <joint_N> - name: <topic name> ns: ...
The robot state interface encapsulates all the data coming FROM the robot controller, including joint position, velocity (if available), effort(if available), position error and general robot status information [7]. The implementation of the state interface is simpler than the motion interface because it can be generalized to the multi-arm case, where a single arm is just a specific example.
- The state interface is split into a joint state and robot status interface (although they will utilize the same socket connection, see Communications Method). The split allows joint state feedback to be sent at a higher rate than status information (which should change slowly).
- Joint State - A single controller message is split into N JointState messages.
- Robot Status - A single controller message that contains status information for each arm.
Similar to the motion interface, the state interface will require configuration. The state interface will have to parse messages coming from the robot and convert the date into the desired ROS topics. The level of configuration available on the robot controller will vary, so the messages coming from the controller may be more or less dynamic. The state node, based on configuration, will identify the pertinent information from the robot controller and convert to ROS topics. Additional information will be ignored.
The yaml file will contain a list of structures that defines the joint trajectory/status topics as well as the mapping to the controller. Note, this configuration is very similar to the motion node, with the exception that the state node performs a one-to-one mapping from controller groups to topics. The motion node, in addition to this, can perform a one(topic) to many (groups) mapping.:
topic_list: - state group: <controller group#> - joint - name: <topic name> ns: <topic namespace> joints: - <joint_1> - <joint_2> - <joint_N> - status - name: <topic name> - ns: <topic namespace> ...
This REP creates a new industrial robot client package that will not be backwards compaptible with the previous version. This means that all servers will have to be rewritten to support this new client. Because this REP does not change the ROS API (except for multi-arm considerations), the previous client/server versions can continue to be used as is. Transition to the client/servers described by this REP can be a gradual process as the capabilities enabled by this new design are required.
If incompatible client/server combinations are ever used, there is little risk of undesirable behavior. Because the simple message base protocol is not changed by this REP, the client/server should recognize the new message types as undefined and return an error reply code.
- The following items still need to be addressed:
- Topics and Services - The ROS API defines topics and services for receiving trajectories. This should also be supported by the new nodes.
- Controller/PC handshaking - Currently most robot/PC communications involves a handshake (either I received and processed the last message or the last message resulted in an error). This results in robust communications and execution, but doubles the amount of latency in the system. I think this is the appropriate design, but it may be up for discussion.
- What to do about force/effort control. It is not currently supported by many controllers, but may be in the future.
- What is the failure mechanism when an incomplete trajectory point is sent? impossible trajectory point (too fast, too much acceleration)?
- Support for joint trajectory splicing should be added (implementation should be simpler now that trajectories are streamed point by point).
[1] | ROS-Industrial robot client ( http://wiki.ros.org/industrial_robot_client ). |
[2] | Industrial robot driver spec (ROS API) ( http://wiki.ros.org/Industrial/Industrial_Robot_Driver_Spec ). |
[3] | MoveIt motion planning library ( http://moveit.ros.org ). |
[4] | Google group discussion: Support for Dual-arm robots (https://groups.google.com/forum/#!topic/swri-ros-pkg-dev/LHrfVgEA4hs). |
[5] | (1, 2) Joint trajectory message definition ( http://wiki.ros.org/trajectory_msgs ). |
[6] | ROS-Industrial simple message package ( http://wiki.ros.org/simple_message ). |
[7] | Industrial robot status message ( http://wiki.ros.org/industrial_msgs ). |
[8] | MoveIt simple controller manager ( http://moveit.ros.org/wiki/Executing_Trajectories_with_MoveIt!#Simple_MoveIt.21_Controller_Manager_Plugin ). |
This document has been placed in the public domain.