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 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 object 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