Show EOL distros:
The Industrial Robot Driver specification does not apply to this release. Please see a later release version for more details.
Contents
This page provides a detailed description of how different robot platforms comply with the Industrial Robot Driver specification. It is intended for developers and systems integrators needing to evaluate specific functional capabilities. More general compatibility information can be found here.
ROS Interface
Section |
Type |
Name |
Robots |
|
Motoman |
Adept |
|||
param |
robot_ip_address |
N1 |
N2 |
|
pub topic |
feedback_states |
Y3 |
Y3 |
|
pub topic |
joint_states |
Y3 |
Y3 |
|
sub topic |
joint_path_command |
Y4 |
Y4 |
- Uses command-line argument instead.
- Hardcoded in source code.
Simple Message only supports actual position feedback.
Performs fixed-speed motion set on robot controller. Ignores ROS velocities/timestamps.
Robot/Client Behavior
Section |
Condition |
Expected Behavior |
Robots |
|
Motoman |
Adept |
|||
ROS node launched |
auto-connect to robot |
Y |
Y |
|
robot power-on |
ROS comms software auto-runs |
Y |
N |
|
comms loss |
ROS node tries repeated reconnects to robot |
Y |
N |
|
comms loss |
ROS node stops publishing position messages |
Y |
Y |
|
comms loss |
robot stops motion and turns off drive power |
N |
? |
|
comms loss |
robot waits for new connection |
Y |
N |
|
general |
topics/services should not be published/advertised if unsupported |
Y |
Y |
|
trajectory overflow |
trajectory ignored and error logged |
Y |
Y |
|
trajectory received |
robot automatically starts motion |
Y |
Y |
|
trajectory completed |
motion stops, drive power stays on |
Y |
? |
|
trajectory interrupted |
cancel current motion, begin new trajectory |
? |
N |
Contents
This page provides a detailed description of how different robot platforms comply with the Industrial Robot Driver specification. It is intended for developers and systems integrators needing to evaluate specific functional capabilities. More general compatibility information can be found here.
ROS Interface
Section |
Type |
Name |
Robots |
||||||
Simulator |
Industrial |
Motoman |
Adept |
ABB |
Fanuc |
Universal |
|||
param |
robot_ip_address |
N/A |
Y |
N1 |
N2 |
Y |
Y |
N1 |
|
pub topic |
feedback_states |
Y5 |
Y3 |
Y3 |
Y3 |
Y3 |
Y3 |
N |
|
pub topic |
joint_states |
Y5 |
Y3 |
Y3 |
Y3 |
Y3 |
Y3 |
Y6 |
|
pub topic |
robot_status |
N |
Y |
Y7 |
N |
N |
N |
N |
|
sub topic |
joint_path_command |
Y8 |
Y |
Y4 |
Y4 |
Y9 |
Y4 |
N10 |
|
service |
stop_motion |
N |
Y |
N |
N |
Y |
Y |
N |
|
service |
joint_path_command |
N |
Y |
N |
N |
Y |
Y |
N |
- Uses command-line argument instead.
- Hardcoded in source code.
Simple Message only supports actual position feedback.
Performs fixed-speed motion set on robot controller. Ignores ROS velocities/timestamps.
Actual position feedback only.
Actual position/velocity feedback only.
- Only responds with motion state.
- Assumes stepwise motion, from point-to-point, using time_from_start. Does not interpolate between trajectory points using velocities or accel.
- Velocities calculated from time_from_start, assuming continuous motion. Ignores trajectory velocity/accel values.
Provides control_msgs/FollowJointTrajectoryAction directly.
Robot/Client Behavior
Section |
Condition |
Expected Behavior |
Robots |
||||||
Simulator |
Industrial |
Motoman |
Adept |
ABB |
Fanuc |
Universal |
|||
ROS node launched |
auto-connect to robot |
N/A |
Y |
Y |
Y |
Y |
Y |
Y |
|
robot power-on |
ROS comms software auto-runs |
N/A |
N/A |
Y |
N |
Y |
N |
Y1 |
|
comms loss |
ROS node tries repeated reconnects to robot |
N/A |
Y |
Y |
N |
Y? |
Y |
? |
|
comms loss |
ROS node stops publishing position messages |
N/A |
Y |
Y |
Y |
Y |
Y |
? |
|
comms loss |
ROS node publishes "disconnected" state messages |
N/A |
N |
N |
N |
N |
N |
N |
|
comms loss |
robot stops motion and turns off drive power |
N/A |
N/A |
N |
? |
N? |
N8 |
? |
|
comms loss |
robot waits for new connection |
N/A |
N/A |
Y |
N |
Y |
Y9 |
Y |
|
general |
topics/services should not be published/advertised if unsupported |
Y |
N6 |
Y |
Y |
Y |
Y |
Y |
|
trajectory overflow |
trajectory ignored and error logged |
N/A |
N/A |
Y |
Y |
N2 |
N/A3 |
N/A3 |
|
trajectory received |
robot automatically starts motion |
Y |
N/A |
Y |
Y |
Y |
Y |
Y |
|
trajectory completed |
motion stops, drive power stays on |
Y |
N/A |
Y |
? |
Y |
Y |
Y |
|
trajectory interrupted |
cancel current motion, begin new trajectory |
N4 |
Y7 |
? |
N |
Y |
Y |
? |
|
trajectory overlap |
points with out-of-order (or in-the-past) time_from_start should be ignored |
N5 |
N5 |
N5 |
N5 |
N5 |
N5 |
? |
- Required software downloaded "on-the-fly" to robot by UR5 ROS node.
- Error logged. Trajectory truncated at max-size and executed anyway (not ignored).
- Trajectory streamed to robot. No overflow possible.
- Simulator is single-threaded. Will block new trajectories (buffered in ROS) until previous trajectory is completed, then execute new trajectories in the order received.
- Moves through all trajectory points, in the order received.
- Topic publishers are always created. No topic messages are published if robot doesn't provide required simple_message broadcast.
- Streaming trajectory only. Reaction is robot-specific for robots using downloaded trajectories.
- Motion is stopped, drives remain powered.
Socket time-outs may interfere, see ros-industrial/fanuc/issues/19.
Contents
This page provides a detailed description of how different robot platforms comply with the Industrial Robot Driver specification. It is intended for developers and systems integrators needing to evaluate specific functional capabilities. More general compatibility information can be found here.
ROS Interface
Section |
Type |
Name |
Robots |
||||||
Simulator |
Industrial |
Motoman |
Adept |
ABB |
Fanuc |
Universal |
|||
param |
robot_ip_address |
N/A |
Y |
N1 |
N2 |
Y |
Y |
N1 |
|
pub topic |
feedback_states |
Y5 |
Y3 |
Y3 |
Y3 |
Y3 |
Y3 |
N |
|
pub topic |
joint_states |
Y5 |
Y3 |
Y3 |
Y3 |
Y3 |
Y3 |
Y6 |
|
pub topic |
robot_status |
Y |
Y |
Y7 |
N |
N |
Y |
N |
|
sub topic |
joint_path_command |
Y8 |
Y |
Y4 |
Y4 |
Y9 |
Y4 |
N10 |
|
service |
stop_motion |
N |
Y |
N |
N |
Y |
Y |
N |
|
service |
joint_path_command |
N |
Y |
N |
N |
Y |
Y |
N |
- Uses command-line argument instead.
- Hardcoded in source code.
Simple Message only supports actual position feedback.
Performs fixed-speed motion set on robot controller. Ignores ROS velocities/timestamps.
Actual position feedback only.
Actual position/velocity feedback only.
- Only responds with motion state.
- Assumes stepwise motion, from point-to-point, using time_from_start. Does not interpolate between trajectory points using velocities or accel.
- Velocities calculated from time_from_start, assuming continuous motion. Ignores trajectory velocity/accel values.
Provides control_msgs/FollowJointTrajectoryAction directly.
Robot/Client Behavior
Section |
Condition |
Expected Behavior |
Robots |
||||||
Simulator |
Industrial |
Motoman |
Adept |
ABB |
Fanuc |
Universal |
|||
ROS node launched |
auto-connect to robot |
N/A |
Y |
Y |
Y |
Y |
Y |
Y |
|
robot power-on |
ROS comms software auto-runs |
N/A |
N/A |
Y |
N |
Y |
N |
Y1 |
|
comms loss |
ROS node tries repeated reconnects to robot |
N/A |
Y |
Y |
N |
Y? |
Y |
? |
|
comms loss |
ROS node stops publishing position messages |
N/A |
Y |
Y |
Y |
Y |
Y |
? |
|
comms loss |
ROS node publishes "disconnected" state messages |
N/A |
N |
N |
N |
N |
N |
N |
|
comms loss |
robot stops motion and turns off drive power |
N/A |
N/A |
N |
? |
N? |
N8 |
? |
|
comms loss |
robot waits for new connection |
N/A |
N/A |
Y |
N |
Y |
Y9 |
Y |
|
general |
topics/services should not be published/advertised if unsupported |
Y |
N6 |
Y |
Y |
Y |
Y |
Y |
|
trajectory overflow |
trajectory ignored and error logged |
N/A |
N/A |
Y |
Y |
N2 |
N/A3 |
N/A3 |
|
trajectory received |
robot automatically starts motion |
Y |
N/A |
Y |
Y |
Y |
Y |
Y |
|
trajectory completed |
motion stops, drive power stays on |
Y |
N/A |
Y |
? |
Y |
Y |
Y |
|
trajectory interrupted |
cancel current motion, begin new trajectory |
N4 |
Y7 |
? |
N |
Y |
Y |
? |
|
trajectory overlap |
points with out-of-order (or in-the-past) time_from_start should be ignored |
N5 |
N5 |
N5 |
N5 |
N5 |
N5 |
? |
- Required software downloaded on-the-fly to robot by the Universal Robot ROS driver node.
- Error logged. Trajectory truncated at max-size and executed anyway (not ignored).
- Trajectory streamed to robot. No overflow possible.
- Simulator is single-threaded. Will block new trajectories (buffered in ROS) until previous trajectory is completed, then execute new trajectories in the order received.
- Moves through all trajectory points, in the order received.
- Topic publishers are always created. No topic messages are published if robot doesn't provide required simple_message broadcast.
- Streaming trajectory only. Reaction is robot-specific for robots using downloaded trajectories.
- Motion is stopped, drives remain powered.
Socket time-outs may interfere, see ros-industrial/fanuc/issues/19.
There is no Indigo specific version of the Hardware Compatibility page of ROS-Industrial yet. Please refer to the Hydro page.
There is no Jade specific version of the Hardware Compatibility page of ROS-Industrial yet. Please refer to the Hydro page.