-
Notifications
You must be signed in to change notification settings - Fork 21
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Update REP-I0001 with implementation-related changes/clarifications #13
base: master
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -31,7 +31,7 @@ Abstract | |
This REP specifies the second version of the ROS-Industrial robot controller client/server motion/state/status interface [#rbt_clnt]_. 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 [#ros_api]_, 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 [#moveit]_. | ||
|
||
Definitions | ||
========= | ||
=========== | ||
|
||
The following definitions are used throughout: | ||
* joint, axis - A single controllable item. Typically revolute(rotational) or linear motion. | ||
|
@@ -42,11 +42,11 @@ The following definitions are used throughout: | |
Motivation | ||
========== | ||
|
||
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 [#discuss]_. 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 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 manner that could be used across all platforms [#discuss]_. 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). | ||
|
||
|
||
Requirements | ||
========= | ||
============ | ||
|
||
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. | ||
|
@@ -61,18 +61,18 @@ The industrial robot controller motion interface shall meet the following requir | |
* 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. | ||
|
||
Design Assumptions | ||
========= | ||
================== | ||
The following assumptions are inherent in the client/server design: | ||
* All joints (regardless of group) shall be uniquely named. | ||
|
||
* All joints (within a common namespace) shall be uniquely named. | ||
|
||
Simple Message Structures | ||
========= | ||
========================= | ||
The simple message package [#simp_msg]_ 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. | ||
|
||
In addition to dynamic array-sizing, several of the new messages also allow for populating only a subset of the supported message fields. This allows for the messages to support a wide range of potential data, while also allowing robot controllers and ROS control algorithms to only support a small subset of those capabilities. The new messages contain a ``valid_fields`` item, that signals which of the potential data fields are being used. The messages are packed, to minimize bandwidth, so that only the specified fields are acutally transmitted in the message datastream. The ordering of data fields is still maintained, even when some fields are skipped. | ||
|
||
Dynamic Joint Point | ||
--------- | ||
------------------- | ||
The dynamic joint point is meant to mimic the ROS JointTrajectory message structure [#traj_msg]_. 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.:: | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Isn't synchronised motion only dependent on the trajectory point containing info for all groups that are to be part of the motion? A |
||
|
||
length: true message/data length | ||
|
@@ -92,7 +92,7 @@ The dynamic joint point is meant to mimic the ROS JointTrajectory message struct | |
|
||
|
||
Dynamic Joint State | ||
--------- | ||
------------------- | ||
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 | ||
|
@@ -109,43 +109,46 @@ The dynamic joint state is meant to mimic both the ROS JointState and FollowJoin | |
accelerations[] | ||
effort[] | ||
position_desired[] | ||
position_errors[] | ||
position_error[] | ||
velocity_desired[] | ||
velocity_errors[] | ||
velocity_error[] | ||
accel_desired[] | ||
accel_error[] | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why revert to singular only here? To get this more in-line with the JointState msg, I'd make all field names singular (ie: There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This message maps to both the JointState and FollowJointTrajectoryFeedback, which eventually encapsulates data using a JointTrajectoryPoint. These messages use different conventions, so there is no "best choice". In the end, I updated For what it's worth, the There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Hm, I think I'd vote for consistency. Let's see whether there are any more opinions. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Additional note for the There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. For brevity in typing. {shrug}. In reality, these field names don't officially appear anywhere. There are some related constants, comments, and methods in the ROS/Karel code, but they don't adhere strictly to these names either. |
||
effort_desired[] | ||
effort_error[] | ||
|
||
|
||
Dynamic Group Status | ||
--------- | ||
The dynamic group status is meant to mimic both the ROS-I RobotStatus message. See the RobotStatus message[#rbt_stat]_ for field descriptions.:: | ||
-------------------- | ||
The dynamic group status is meant to mimic both the ROS-I RobotStatus message. See the RobotStatus message [#rbt_stat]_ for field descriptions.:: | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. "meant to mimic both the ROS-I RobotStatus message": is something missing here? Mimic both RobotStatus and what other message? |
||
|
||
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: | ||
e_stopped: | ||
error_code: | ||
in_error: | ||
in_motion: | ||
mode: | ||
motion_possible: | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Just asking: do we want to order this like Obviously we don't have to keep this in the same order, as we are not bound by backward compatibility issues. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Hm. The linked header and the actual order used in the RobotStatus::load(..) and RobotStatus::unload(..) implementations would seem not to match with each other. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It looks to me as though everything is consistent, after this update to the REP. Your comments link to rev 12a74a1, but it looks like commit 4405b0d updated the header comments to match the field ordering in load/unload. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Hm, yes, you're right. I even fixed that order myself (ros-industrial/industrial_core@4405b0dc). Sorry for the noise. |
||
|
||
|
||
Communications Method | ||
========= | ||
===================== | ||
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. | ||
|
||
Motion Interface | ||
========= | ||
================ | ||
|
||
Motion Downloading Vs Streaming | ||
--------- | ||
------------------------------- | ||
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. | ||
|
||
Motion Variants | ||
--------- | ||
--------------- | ||
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. | ||
|
@@ -155,56 +158,80 @@ The motion interface can be expressed as four variations: | |
.. image:: rep-I0001/motion_interface.png | ||
|
||
Node Configuration | ||
--------- | ||
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.:: | ||
------------------ | ||
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]_. | ||
|
||
topic_list: | ||
- name: <topic name> | ||
As in previous interfaces, the node will be configured using a ROS parameter specifying ROS-to-controller mapping. This parameter will contain a list of structures that define both the topic namespaces as well as the mapping to the controller.:: | ||
|
||
controller_joint_map: | ||
- group: <controller group#> | ||
ns: <topic namespace> | ||
group: <controller group#> | ||
joints: | ||
- <joint_1> | ||
- <joint_2> | ||
- <joint_N> | ||
- name: <topic name> | ||
- group: <controller group #> | ||
ns: ... | ||
|
||
This structure allows users to configure the robot interface to receive motion commands in several different ways: | ||
|
||
#. Single Topic | ||
all groups use same namespace (e.g. ``ns: ""``) | ||
#. Separate Topics | ||
use group-specific namespaces | ||
#. Mixed Mode | ||
joint map may contain multiple entries for the same group, in different namespaces. This allows using separate topics for different planning/control methods (for example, in dual-arm robots: left, right, both). | ||
|
||
The interface node will always listen for motion commands on the same topic as the current interface (``joint_path_command``), inside the specified namespace for each group. | ||
|
||
State Interface | ||
========= | ||
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 [#rbt_stat]_. 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 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 [#rbt_stat]_. | ||
|
||
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. | ||
|
||
As in the motion interface, users can specify which namespace to use for each robot group. Unlike the motion interface, multiple groups that share a namespace are *always* combined into a single message (regardless of sync vs. async motion). Separate namespaces can be used to receive separate messages for each motion group. | ||
|
||
For ``JointState`` and ``JointTrajectoryFeedback`` messages, aggregation of multiple robot groups is easily supported through the explicit joint-name list in the message. For ``RobotStatus`` messages, the status of multiple groups is aggregated into a single message using simple logic and the ``TriState`` message type: If all groups share the same status value, use that value, otherwise use ``TriState::Unknown``. Some fields (such as ``in_motion``) may use modified logic (if "any" group in motion...). | ||
|
||
.. image:: rep-I0001/state_interface.png | ||
|
||
|
||
Node Configuration | ||
--------- | ||
------------------ | ||
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> | ||
... | ||
|
||
The state interface uses the same ROS configuration parameter as the motion node. Robot groups may be mapped to the same namespace (aggregate status messages) or different namespaces (per-group messages), or both. As in the motion interface, the same topics are used within each namespace as are used in the current state interface. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Perhaps add some example configurations for each of the cases? The "may be mapped to X, Y or both" can be confusing. |
||
|
||
The normal use-case will be to map a each motion group to a single namespace (either independent or shared with other groups). However, it is possible to map a single group to multiple topics, as shown below: | ||
|
||
:: | ||
|
||
controller_joint_map | ||
- group: 1 | ||
ns: "north" | ||
joints: ['j1', ..., 'j6'] | ||
|
||
- group: 2 | ||
ns: "south" | ||
joints: ['j1', ..., 'j6'] | ||
|
||
- group: 1 | ||
ns: "combined" | ||
joints: ['north_j1', ..., 'north_j6'] | ||
|
||
- group: 2 | ||
ns: "combined" | ||
joints: ['south_j1', ..., 'south_j6'] | ||
|
||
Which will result in the following topics: | ||
- ``/north/joint_states``: ``[j1 ... j6]`` | ||
- ``/south/joint_states``: ``[j1 ... j6]`` | ||
- ``/combined/joint_states``: ``[north_j1 ... south_j6]`` | ||
|
||
Backwards Compatibility | ||
========= | ||
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. | ||
======================= | ||
This REP creates a new industrial robot client package that may not be backwards compaptible with the previous version. The new Dynamic simple_message types will be used for all data communications with the robot, even in single-arm configurations. This means that all robot servers will have to be rewritten to support the new dynamic message types. This REP attempts to minimize the impact to ROS-side API, so most ROS clients will be unaffected. The new industrial robot client package should continue to support the existing ``controller_joint_names`` definition, for backwards compatibility. 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. | ||
|
||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Missing space between messages and
[#simp_msg]_
(in "new set of simple messages[#simp_msg]_ for multi-arm control").