Show EOL distros:
Package Summary
industrial robot client contains generic clients for connecting to industrial robot controllers with servers that adhere to the simple message protocol.
- Author: Jeremy Zoss
- License: BSD
- Source: svn https://swri-ros-pkg.googlecode.com/svn/branches/groovy/industrial_core
Package Summary
industrial robot client contains generic clients for connecting to industrial robot controllers with servers that adhere to the simple message protocol.
- Maintainer status: maintained
- Maintainer: Shaun Edwards <sedwards AT swri DOT org>
- Author: Jeremy Zoss
- License: BSD
- Source: git https://github.com/ros-industrial/industrial_core.git (branch: hydro)
Package Summary
industrial robot client contains generic clients for connecting to industrial robot controllers with servers that adhere to the simple message protocol.
- Maintainer status: maintained
- Maintainer: Shaun Edwards <sedwards AT swri DOT org>
- Author: Jeremy Zoss
- License: BSD
- Source: git https://github.com/ros-industrial/industrial_core.git (branch: indigo)
Package Summary
industrial robot client contains generic clients for connecting to industrial robot controllers with servers that adhere to the simple message protocol.
- Maintainer status: maintained
- Maintainer: Shaun Edwards <sedwards AT swri DOT org>
- Author: Jeremy Zoss
- License: BSD
- Source: git https://github.com/ros-industrial/industrial_core.git (branch: jade)
Package Summary
industrial robot client contains generic clients for connecting to industrial robot controllers with servers that adhere to the simple message protocol.
- Maintainer status: maintained
- Maintainer: Shaun Edwards <shaun.edwards AT gmail DOT com>
- Author: Jeremy Zoss
- License: BSD
- Source: git https://github.com/ros-industrial/industrial_core.git (branch: kinetic)
Package Summary
industrial robot client contains generic clients for connecting to industrial robot controllers with servers that adhere to the simple message protocol.
- Maintainer status: maintained
- Maintainer: G.A. vd. Hoorn (TU Delft Robotics Institute) <g.a.vanderhoorn AT tudelft DOT nl>, Levi Armstrong (Southwest Research Institute) <levi.armstrong AT swri DOT org>
- Author: Jeremy Zoss
- License: BSD
- Source: git https://github.com/ros-industrial/industrial_core.git (branch: melodic)
Package Summary
industrial robot client contains generic clients for connecting to industrial robot controllers with servers that adhere to the simple message protocol.
- Maintainer status: maintained
- Maintainer: G.A. vd. Hoorn (TU Delft Robotics Institute) <g.a.vanderhoorn AT tudelft DOT nl>, Levi Armstrong (Southwest Research Institute) <levi.armstrong AT swri DOT org>
- Author: Jeremy Zoss
- License: BSD
- Source: git https://github.com/ros-industrial/industrial_core.git (branch: melodic)
Contents
Overview
The industrial_robot_client package provides a standardized interface for controlling industrial robots, based on the ROS-Industrial Specification. This package includes a C++ reference implementation of the specification, using the simple_message protocol to communicate with a compatible server running on a standalone industrial robot controller.
Primarily, this package provides the industrial_robot_client library. The intent is for robot-specific implementations to reuse code from this library using standard C++ derived-class mechanisms, to avoid much of the copy/paste duplication in current industrial-robot driver implementations. Modification to adapt the library to new robot needs is discussed in more detail below.
This package also provides generic nodes exposing the base industrial_robot_client functionality. If a robot does not require any specific client-side code, then it may be sufficient to run these standard nodes. This page describes this usage in more detail.
Protocol documentation
The Simple Message (SimpleMessage) protocol defines the message structure between the ROS driver layer and the robot controller itself.
Refer to REP-I0006: Message Structures of the ROS-Industrial Simple Message Protocol for a description of the protocol.
Modification for Robot-Specific Needs
Often, differences between manufacturer interfaces and robot designs will require changes to the basic reference implementation provided in the industrial_robot_client library. Joint-coupling, velocity scaling, and communications protocols are all potential reasons for robot-specific control code.
Rather than make a new copy of the entire ROS client codebase, it is recommended that the integrator use a derived-class approach to only re-implement the minimal functionality required. Wherever possible, the new code should call the base class reference-implementation functions to avoid code duplication and maintain consistent operations. It may be helpful to review the library's design to determine which functionality may need replacing. Simple joint reordering and renaming can be handled through existing capabilities, as described here.
Example
The following example shows how to replace the reference velocity calculation (0-100% of max-velocity) with an absolute velocity algorithm.
Create a new derived class, based on JointTrajectoryDownloader (or JointTrajectoryStreamer)
- Override specific functionality. In this case, the velocity calculation.
1 class myRobot_JointTrajectoryDownloader : JointTrajectoryDownloader 2 { 3 4 public: 5 bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity) 6 { 7 if (pt.velocities.empty()) 8 *rbt_velocity = SAFE_SPEED; 9 else 10 *rbt_velocity = std::min(pt.velocities.begin(), pt.velocities.end()); 11 12 return true; 13 } 14 }
- Implement a new node, using an instance of the appropriate derived-class.
Further examples
Further examples of creating robot-specific interfaces may be found in the following code samples:
Nodes
Besides the reusable libraries, this package also provides default implementations of a set of generic nodes. The following is the ROS API of those generic nodes.
robot_state
Connects to a robot state server program on a controller and publishes joint states.Action Feedback
feedback_states (control_msgs/FollowJointTrajectory)- Provide feedback of current vs. desired joint position (and velocity/acceleration).
Published Topics
joint_states (sensor_msgs/JointState)- Joint state for all joints of the connected robot.
- Aggregate controller/robot status (ie: drives enabled, motion possible, etc)
Parameters
robot_ip_address (str, default: none)- IP address of the controller to connect to. If this is not set the node will exit.
- TCP port the robot state server program is listening on.
- The urdf xml robot description.
- (optional) A list containing all joints the driver should assume control over. If this parameter is not found, the driver will try to extract this from the robot_description parameter, but this will result in all joints in the urdf to be included. If the driver should only publish joint states for a subset of the joints in the urdf, the controller_joint_names parameter must be set.
motion_download_interface
Connects to a motion relay server program on the controller and uploads trajectories. Note: this is the download version of the interface, which means the entire trajectory is uploaded to the motion relay server program before motion is started.Subscribed Topics
joint_states (sensor_msgs/JointState)- Joint state for all joints of the connected robot.
- Execute a pre-calculated joint trajectory on the robot.
Services
joint_path_command (industrial_msgs/CmdJointTrajectory)- Execute a new motion trajectory on the robot.
- Stop execution of the current motion at the earliest time possible.
Parameters
robot_ip_address (str, default: none)- IP address of the controller to connect to. If this is not set the node will exit.
- TCP port the motion relay server program is listening on.
- The urdf xml robot description.
- (optional) A list containing all joints the driver should assume control over. If this parameter is not found, the driver will try to extract this from the robot_description parameter, but this will result in all joints in the urdf to be included. If the driver should only control a subset of the joints in the urdf, the controller_joint_names parameter must be set.
motion_streaming_interface
Connects to a motion relay server program on the controller and streams trajectories. Note: this is the streaming version of the interface, which means trajectories are relayed piecewise to the motion relay server program and motion is expected to start immediately (or: as soon as possible).Subscribed Topics
joint_states (sensor_msgs/JointState)- Joint state for all joints of the connected robot.
- Execute a pre-calculated joint trajectory on the robot.
Services
joint_path_command (industrial_msgs/CmdJointTrajectory)- Execute a new motion trajectory on the robot.
- Stop execution of the current motion at the earliest time possible.
Parameters
robot_ip_address (str, default: none)- IP address of the controller to connect to. If this is not set the node will exit.
- TCP port the motion relay server program is listening on.
- The urdf xml robot description.
- (optional) A list containing all joints the driver should assume control over. If this parameter is not found, the driver will try to extract this from the robot_description parameter, but this will result in all joints in the urdf to be included. If the driver should only control a subset of the joints in the urdf, the controller_joint_names parameter must be set.
Contact us/Technical support
For questions about this package or ROS-Industrial in general, please contact the developers by posting a message in the ROS-Industrial category on ROS Discourse.
Reporting bugs
Use GitHub to report bugs or submit feature requests. [View active issues]