Overview

The industrial_payload_manager package provides functionality for managing payloads in planning scenes and RViz visualizations of industrial robot operations by providing the following functionality:

  • Load payloads, payload_targets, and link_markers from URDF files into industrial_payload_manager/Payload messages
  • Dynamically insert, remove, or manipulate pose of payloads
  • Update RViz visualization marker array, attached collision objects in MoveIt! planning scene, and in the future attached collision objects in Tesseract planning scene.

  • industrial_payload_manager/Payload messages include information for payload geometry, Aruco marker locations, gripper targets for payload grasping, and inertial properties of payload
  • industrial_payload_manager/PayloadTarget messages include the desired final locations for payloads after manipulation
  • industrial_payload_manager/LinkMarkers message contains the pose of Aruco markers attached to a robot or workcell link
  • payload_transform_publisher script will publish all relevant transforms to /tf
  • PayloadTransformListener Python class extends the standard TransformListener with the ability to understand industrial_transform_listener/PayloadArray messages and include the relevant transforms in lookup

Source: https://github.com/arminstitute/industrial_payload_manager

Warning: This software is under development. API and message formats and subject to change.

Nodes

industrial_payload_manager

Provides core functionality for managing payloads in RViz and planning scenes

Subscribed Topics

/payload (industrial_payload_manager/PayloadArray)
  • Contains array of Payload, PayloadTarget, and LinkMarkers messages

Published Topics

/payload (industrial_payload_manager/PayloadArray)
  • Publishes updated payload messages if payload is changed by the manager
/attached_collision_object (moveit_msgs/AttachedCollisionObject) /payload_marker_array (visualization_msgs/MarkerArray)
  • MarkerArray messages for RViz to show visual meshes of payloads

Services

/get_payload_array (industrial_payload_manager/GetPayloadArray)
  • Synchronously returns a PayloadArray of active payloads
/update_payload_pose (industrial_payload_manager/UpdatePayloadPose)
  • Updates the pose of a payload and the link the payload is attached

urdf_to_payload

Loads URDF Xacro files to payload messages and publishes to /payload topic. The payloads must be carefully formatted so each Xacro file contains only one Payload, PayloadTarget, or LinkMarkers. The Payload Xacro URDF files may contain visual and collision geometry, Aruco markers, payload targets, and inertial parameters. Each Aruco marker and payload target must be in a sub-link connected by a fixed joint. Only on level of joints is allowed. See the test/load_payloads.launch file for examples of how to use the urdf_to_payload node.

Published Topics

/payload (industrial_payload_manager/PayloadArray)
  • Publishes the payloads loaded from URDF files

payload_trasform_publisher

Publishes payload transforms to /tf topic

Subscribed Topics

/payload (industrial_payload_manager/PayloadArray)
  • The payloads to publish to /tf

Published Topics

/tf (tf/tfMessage)
  • Transforms of relevant frames including all payloads, all Aruco markers, and all payload/gripper targets.

Wiki: industrial_payload_manager (last edited 2018-11-04 21:14:14 by JohnWason)