moveit_msgs/CollisionObject Message

File: moveit_msgs/CollisionObject.msg

Raw Message Definition

# a header, used for interpreting the poses
Header header

# the id of the object (name used in MoveIt)
string id

# The object type in a database of known objects
object_recognition_msgs/ObjectType type

# the the collision geometries associated with the object;
# their poses are with respect to the specified header

# solid geometric primitives
shape_msgs/SolidPrimitive[] primitives
geometry_msgs/Pose[] primitive_poses

# meshes
shape_msgs/Mesh[] meshes
geometry_msgs/Pose[] mesh_poses

# bounding planes (equation is specified, but the plane can be oriented using an additional pose)
shape_msgs/Plane[] planes
geometry_msgs/Pose[] plane_poses

# Adds the object to the planning scene. If the object previously existed, it is replaced.
byte ADD=0

# Removes the object from the environment entirely (everything that matches the specified id)
byte REMOVE=1

# Append to an object that already exists in the planning scene. If the does not exist, it is added.
byte APPEND=2

# If an object already exists in the scene, new poses can be sent (the geometry arrays must be left empty)
# if solely moving the object is desired
byte MOVE=3

# Operation to be performed
byte operation

Compact Message Definition

byte ADD=0
byte REMOVE=1
byte APPEND=2
byte MOVE=3
std_msgs/Header header
string id
object_recognition_msgs/ObjectType type
shape_msgs/SolidPrimitive[] primitives
geometry_msgs/Pose[] primitive_poses
shape_msgs/Mesh[] meshes
geometry_msgs/Pose[] mesh_poses
shape_msgs/Plane[] planes
geometry_msgs/Pose[] plane_poses
byte operation