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