00001 """autogenerated by genmsg_py from CollisionObject.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import arm_navigation_msgs.msg
00006 import geometry_msgs.msg
00007 import std_msgs.msg
00008
00009 class CollisionObject(roslib.message.Message):
00010 _md5sum = "7b972910c23ece1b873b3de0cf92ba97"
00011 _type = "arm_navigation_msgs/CollisionObject"
00012 _has_header = True
00013 _full_text = """# a header, used for interpreting the poses
00014 Header header
00015
00016 # the id of the object
00017 string id
00018
00019 # The padding used for filtering points near the object.
00020 # This does not affect collision checking for the object.
00021 # Set to negative to get zero padding.
00022 float32 padding
00023
00024 #This contains what is to be done with the object
00025 CollisionObjectOperation operation
00026
00027 #the shapes associated with the object
00028 arm_navigation_msgs/Shape[] shapes
00029
00030 #the poses associated with the shapes - will be transformed using the header
00031 geometry_msgs/Pose[] poses
00032
00033 ================================================================================
00034 MSG: std_msgs/Header
00035 # Standard metadata for higher-level stamped data types.
00036 # This is generally used to communicate timestamped data
00037 # in a particular coordinate frame.
00038 #
00039 # sequence ID: consecutively increasing ID
00040 uint32 seq
00041 #Two-integer timestamp that is expressed as:
00042 # * stamp.secs: seconds (stamp_secs) since epoch
00043 # * stamp.nsecs: nanoseconds since stamp_secs
00044 # time-handling sugar is provided by the client library
00045 time stamp
00046 #Frame this data is associated with
00047 # 0: no frame
00048 # 1: global frame
00049 string frame_id
00050
00051 ================================================================================
00052 MSG: arm_navigation_msgs/CollisionObjectOperation
00053 #Puts the object into the environment
00054 #or updates the object if already added
00055 byte ADD=0
00056
00057 #Removes the object from the environment entirely
00058 byte REMOVE=1
00059
00060 #Only valid within the context of a CollisionAttachedObject message
00061 #Will be ignored if sent with an CollisionObject message
00062 #Takes an attached object, detaches from the attached link
00063 #But adds back in as regular object
00064 byte DETACH_AND_ADD_AS_OBJECT=2
00065
00066 #Only valid within the context of a CollisionAttachedObject message
00067 #Will be ignored if sent with an CollisionObject message
00068 #Takes current object in the environment and removes it as
00069 #a regular object
00070 byte ATTACH_AND_REMOVE_AS_OBJECT=3
00071
00072 # Byte code for operation
00073 byte operation
00074
00075 ================================================================================
00076 MSG: arm_navigation_msgs/Shape
00077 byte SPHERE=0
00078 byte BOX=1
00079 byte CYLINDER=2
00080 byte MESH=3
00081
00082 byte type
00083
00084
00085 #### define sphere, box, cylinder ####
00086 # the origin of each shape is considered at the shape's center
00087
00088 # for sphere
00089 # radius := dimensions[0]
00090
00091 # for cylinder
00092 # radius := dimensions[0]
00093 # length := dimensions[1]
00094 # the length is along the Z axis
00095
00096 # for box
00097 # size_x := dimensions[0]
00098 # size_y := dimensions[1]
00099 # size_z := dimensions[2]
00100 float64[] dimensions
00101
00102
00103 #### define mesh ####
00104
00105 # list of triangles; triangle k is defined by tre vertices located
00106 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00107 int32[] triangles
00108 geometry_msgs/Point[] vertices
00109
00110 ================================================================================
00111 MSG: geometry_msgs/Point
00112 # This contains the position of a point in free space
00113 float64 x
00114 float64 y
00115 float64 z
00116
00117 ================================================================================
00118 MSG: geometry_msgs/Pose
00119 # A representation of pose in free space, composed of postion and orientation.
00120 Point position
00121 Quaternion orientation
00122
00123 ================================================================================
00124 MSG: geometry_msgs/Quaternion
00125 # This represents an orientation in free space in quaternion form.
00126
00127 float64 x
00128 float64 y
00129 float64 z
00130 float64 w
00131
00132 """
00133 __slots__ = ['header','id','padding','operation','shapes','poses']
00134 _slot_types = ['Header','string','float32','arm_navigation_msgs/CollisionObjectOperation','arm_navigation_msgs/Shape[]','geometry_msgs/Pose[]']
00135
00136 def __init__(self, *args, **kwds):
00137 """
00138 Constructor. Any message fields that are implicitly/explicitly
00139 set to None will be assigned a default value. The recommend
00140 use is keyword arguments as this is more robust to future message
00141 changes. You cannot mix in-order arguments and keyword arguments.
00142
00143 The available fields are:
00144 header,id,padding,operation,shapes,poses
00145
00146 @param args: complete set of field values, in .msg order
00147 @param kwds: use keyword arguments corresponding to message field names
00148 to set specific fields.
00149 """
00150 if args or kwds:
00151 super(CollisionObject, self).__init__(*args, **kwds)
00152
00153 if self.header is None:
00154 self.header = std_msgs.msg._Header.Header()
00155 if self.id is None:
00156 self.id = ''
00157 if self.padding is None:
00158 self.padding = 0.
00159 if self.operation is None:
00160 self.operation = arm_navigation_msgs.msg.CollisionObjectOperation()
00161 if self.shapes is None:
00162 self.shapes = []
00163 if self.poses is None:
00164 self.poses = []
00165 else:
00166 self.header = std_msgs.msg._Header.Header()
00167 self.id = ''
00168 self.padding = 0.
00169 self.operation = arm_navigation_msgs.msg.CollisionObjectOperation()
00170 self.shapes = []
00171 self.poses = []
00172
00173 def _get_types(self):
00174 """
00175 internal API method
00176 """
00177 return self._slot_types
00178
00179 def serialize(self, buff):
00180 """
00181 serialize message into buffer
00182 @param buff: buffer
00183 @type buff: StringIO
00184 """
00185 try:
00186 _x = self
00187 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00188 _x = self.header.frame_id
00189 length = len(_x)
00190 buff.write(struct.pack('<I%ss'%length, length, _x))
00191 _x = self.id
00192 length = len(_x)
00193 buff.write(struct.pack('<I%ss'%length, length, _x))
00194 _x = self
00195 buff.write(_struct_fb.pack(_x.padding, _x.operation.operation))
00196 length = len(self.shapes)
00197 buff.write(_struct_I.pack(length))
00198 for val1 in self.shapes:
00199 buff.write(_struct_b.pack(val1.type))
00200 length = len(val1.dimensions)
00201 buff.write(_struct_I.pack(length))
00202 pattern = '<%sd'%length
00203 buff.write(struct.pack(pattern, *val1.dimensions))
00204 length = len(val1.triangles)
00205 buff.write(_struct_I.pack(length))
00206 pattern = '<%si'%length
00207 buff.write(struct.pack(pattern, *val1.triangles))
00208 length = len(val1.vertices)
00209 buff.write(_struct_I.pack(length))
00210 for val2 in val1.vertices:
00211 _x = val2
00212 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00213 length = len(self.poses)
00214 buff.write(_struct_I.pack(length))
00215 for val1 in self.poses:
00216 _v1 = val1.position
00217 _x = _v1
00218 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00219 _v2 = val1.orientation
00220 _x = _v2
00221 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00222 except struct.error as se: self._check_types(se)
00223 except TypeError as te: self._check_types(te)
00224
00225 def deserialize(self, str):
00226 """
00227 unpack serialized message in str into this message instance
00228 @param str: byte array of serialized message
00229 @type str: str
00230 """
00231 try:
00232 if self.header is None:
00233 self.header = std_msgs.msg._Header.Header()
00234 if self.operation is None:
00235 self.operation = arm_navigation_msgs.msg.CollisionObjectOperation()
00236 end = 0
00237 _x = self
00238 start = end
00239 end += 12
00240 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00241 start = end
00242 end += 4
00243 (length,) = _struct_I.unpack(str[start:end])
00244 start = end
00245 end += length
00246 self.header.frame_id = str[start:end]
00247 start = end
00248 end += 4
00249 (length,) = _struct_I.unpack(str[start:end])
00250 start = end
00251 end += length
00252 self.id = str[start:end]
00253 _x = self
00254 start = end
00255 end += 5
00256 (_x.padding, _x.operation.operation,) = _struct_fb.unpack(str[start:end])
00257 start = end
00258 end += 4
00259 (length,) = _struct_I.unpack(str[start:end])
00260 self.shapes = []
00261 for i in range(0, length):
00262 val1 = arm_navigation_msgs.msg.Shape()
00263 start = end
00264 end += 1
00265 (val1.type,) = _struct_b.unpack(str[start:end])
00266 start = end
00267 end += 4
00268 (length,) = _struct_I.unpack(str[start:end])
00269 pattern = '<%sd'%length
00270 start = end
00271 end += struct.calcsize(pattern)
00272 val1.dimensions = struct.unpack(pattern, str[start:end])
00273 start = end
00274 end += 4
00275 (length,) = _struct_I.unpack(str[start:end])
00276 pattern = '<%si'%length
00277 start = end
00278 end += struct.calcsize(pattern)
00279 val1.triangles = struct.unpack(pattern, str[start:end])
00280 start = end
00281 end += 4
00282 (length,) = _struct_I.unpack(str[start:end])
00283 val1.vertices = []
00284 for i in range(0, length):
00285 val2 = geometry_msgs.msg.Point()
00286 _x = val2
00287 start = end
00288 end += 24
00289 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00290 val1.vertices.append(val2)
00291 self.shapes.append(val1)
00292 start = end
00293 end += 4
00294 (length,) = _struct_I.unpack(str[start:end])
00295 self.poses = []
00296 for i in range(0, length):
00297 val1 = geometry_msgs.msg.Pose()
00298 _v3 = val1.position
00299 _x = _v3
00300 start = end
00301 end += 24
00302 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00303 _v4 = val1.orientation
00304 _x = _v4
00305 start = end
00306 end += 32
00307 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00308 self.poses.append(val1)
00309 return self
00310 except struct.error as e:
00311 raise roslib.message.DeserializationError(e)
00312
00313
00314 def serialize_numpy(self, buff, numpy):
00315 """
00316 serialize message with numpy array types into buffer
00317 @param buff: buffer
00318 @type buff: StringIO
00319 @param numpy: numpy python module
00320 @type numpy module
00321 """
00322 try:
00323 _x = self
00324 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00325 _x = self.header.frame_id
00326 length = len(_x)
00327 buff.write(struct.pack('<I%ss'%length, length, _x))
00328 _x = self.id
00329 length = len(_x)
00330 buff.write(struct.pack('<I%ss'%length, length, _x))
00331 _x = self
00332 buff.write(_struct_fb.pack(_x.padding, _x.operation.operation))
00333 length = len(self.shapes)
00334 buff.write(_struct_I.pack(length))
00335 for val1 in self.shapes:
00336 buff.write(_struct_b.pack(val1.type))
00337 length = len(val1.dimensions)
00338 buff.write(_struct_I.pack(length))
00339 pattern = '<%sd'%length
00340 buff.write(val1.dimensions.tostring())
00341 length = len(val1.triangles)
00342 buff.write(_struct_I.pack(length))
00343 pattern = '<%si'%length
00344 buff.write(val1.triangles.tostring())
00345 length = len(val1.vertices)
00346 buff.write(_struct_I.pack(length))
00347 for val2 in val1.vertices:
00348 _x = val2
00349 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00350 length = len(self.poses)
00351 buff.write(_struct_I.pack(length))
00352 for val1 in self.poses:
00353 _v5 = val1.position
00354 _x = _v5
00355 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00356 _v6 = val1.orientation
00357 _x = _v6
00358 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00359 except struct.error as se: self._check_types(se)
00360 except TypeError as te: self._check_types(te)
00361
00362 def deserialize_numpy(self, str, numpy):
00363 """
00364 unpack serialized message in str into this message instance using numpy for array types
00365 @param str: byte array of serialized message
00366 @type str: str
00367 @param numpy: numpy python module
00368 @type numpy: module
00369 """
00370 try:
00371 if self.header is None:
00372 self.header = std_msgs.msg._Header.Header()
00373 if self.operation is None:
00374 self.operation = arm_navigation_msgs.msg.CollisionObjectOperation()
00375 end = 0
00376 _x = self
00377 start = end
00378 end += 12
00379 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00380 start = end
00381 end += 4
00382 (length,) = _struct_I.unpack(str[start:end])
00383 start = end
00384 end += length
00385 self.header.frame_id = str[start:end]
00386 start = end
00387 end += 4
00388 (length,) = _struct_I.unpack(str[start:end])
00389 start = end
00390 end += length
00391 self.id = str[start:end]
00392 _x = self
00393 start = end
00394 end += 5
00395 (_x.padding, _x.operation.operation,) = _struct_fb.unpack(str[start:end])
00396 start = end
00397 end += 4
00398 (length,) = _struct_I.unpack(str[start:end])
00399 self.shapes = []
00400 for i in range(0, length):
00401 val1 = arm_navigation_msgs.msg.Shape()
00402 start = end
00403 end += 1
00404 (val1.type,) = _struct_b.unpack(str[start:end])
00405 start = end
00406 end += 4
00407 (length,) = _struct_I.unpack(str[start:end])
00408 pattern = '<%sd'%length
00409 start = end
00410 end += struct.calcsize(pattern)
00411 val1.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00412 start = end
00413 end += 4
00414 (length,) = _struct_I.unpack(str[start:end])
00415 pattern = '<%si'%length
00416 start = end
00417 end += struct.calcsize(pattern)
00418 val1.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00419 start = end
00420 end += 4
00421 (length,) = _struct_I.unpack(str[start:end])
00422 val1.vertices = []
00423 for i in range(0, length):
00424 val2 = geometry_msgs.msg.Point()
00425 _x = val2
00426 start = end
00427 end += 24
00428 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00429 val1.vertices.append(val2)
00430 self.shapes.append(val1)
00431 start = end
00432 end += 4
00433 (length,) = _struct_I.unpack(str[start:end])
00434 self.poses = []
00435 for i in range(0, length):
00436 val1 = geometry_msgs.msg.Pose()
00437 _v7 = val1.position
00438 _x = _v7
00439 start = end
00440 end += 24
00441 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00442 _v8 = val1.orientation
00443 _x = _v8
00444 start = end
00445 end += 32
00446 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00447 self.poses.append(val1)
00448 return self
00449 except struct.error as e:
00450 raise roslib.message.DeserializationError(e)
00451
00452 _struct_I = roslib.message.struct_I
00453 _struct_4d = struct.Struct("<4d")
00454 _struct_3I = struct.Struct("<3I")
00455 _struct_b = struct.Struct("<b")
00456 _struct_fb = struct.Struct("<fb")
00457 _struct_3d = struct.Struct("<3d")