00001 """autogenerated by genmsg_py from SimulateScanRequest.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006
00007 class SimulateScanRequest(roslib.message.Message):
00008 _md5sum = "1a813aa3e885cadba26d83919a706a44"
00009 _type = "graspit_interface_msgs/SimulateScanRequest"
00010 _has_header = False
00011 _full_text = """
00012
00013
00014
00015
00016
00017
00018
00019 geometry_msgs/Pose scanner_pose
00020
00021 bool request_ray_directions
00022
00023
00024 ================================================================================
00025 MSG: geometry_msgs/Pose
00026 # A representation of pose in free space, composed of postion and orientation.
00027 Point position
00028 Quaternion orientation
00029
00030 ================================================================================
00031 MSG: geometry_msgs/Point
00032 # This contains the position of a point in free space
00033 float64 x
00034 float64 y
00035 float64 z
00036
00037 ================================================================================
00038 MSG: geometry_msgs/Quaternion
00039 # This represents an orientation in free space in quaternion form.
00040
00041 float64 x
00042 float64 y
00043 float64 z
00044 float64 w
00045
00046 """
00047 __slots__ = ['scanner_pose','request_ray_directions']
00048 _slot_types = ['geometry_msgs/Pose','bool']
00049
00050 def __init__(self, *args, **kwds):
00051 """
00052 Constructor. Any message fields that are implicitly/explicitly
00053 set to None will be assigned a default value. The recommend
00054 use is keyword arguments as this is more robust to future message
00055 changes. You cannot mix in-order arguments and keyword arguments.
00056
00057 The available fields are:
00058 scanner_pose,request_ray_directions
00059
00060 @param args: complete set of field values, in .msg order
00061 @param kwds: use keyword arguments corresponding to message field names
00062 to set specific fields.
00063 """
00064 if args or kwds:
00065 super(SimulateScanRequest, self).__init__(*args, **kwds)
00066
00067 if self.scanner_pose is None:
00068 self.scanner_pose = geometry_msgs.msg.Pose()
00069 if self.request_ray_directions is None:
00070 self.request_ray_directions = False
00071 else:
00072 self.scanner_pose = geometry_msgs.msg.Pose()
00073 self.request_ray_directions = False
00074
00075 def _get_types(self):
00076 """
00077 internal API method
00078 """
00079 return self._slot_types
00080
00081 def serialize(self, buff):
00082 """
00083 serialize message into buffer
00084 @param buff: buffer
00085 @type buff: StringIO
00086 """
00087 try:
00088 _x = self
00089 buff.write(_struct_7dB.pack(_x.scanner_pose.position.x, _x.scanner_pose.position.y, _x.scanner_pose.position.z, _x.scanner_pose.orientation.x, _x.scanner_pose.orientation.y, _x.scanner_pose.orientation.z, _x.scanner_pose.orientation.w, _x.request_ray_directions))
00090 except struct.error as se: self._check_types(se)
00091 except TypeError as te: self._check_types(te)
00092
00093 def deserialize(self, str):
00094 """
00095 unpack serialized message in str into this message instance
00096 @param str: byte array of serialized message
00097 @type str: str
00098 """
00099 try:
00100 if self.scanner_pose is None:
00101 self.scanner_pose = geometry_msgs.msg.Pose()
00102 end = 0
00103 _x = self
00104 start = end
00105 end += 57
00106 (_x.scanner_pose.position.x, _x.scanner_pose.position.y, _x.scanner_pose.position.z, _x.scanner_pose.orientation.x, _x.scanner_pose.orientation.y, _x.scanner_pose.orientation.z, _x.scanner_pose.orientation.w, _x.request_ray_directions,) = _struct_7dB.unpack(str[start:end])
00107 self.request_ray_directions = bool(self.request_ray_directions)
00108 return self
00109 except struct.error as e:
00110 raise roslib.message.DeserializationError(e)
00111
00112
00113 def serialize_numpy(self, buff, numpy):
00114 """
00115 serialize message with numpy array types into buffer
00116 @param buff: buffer
00117 @type buff: StringIO
00118 @param numpy: numpy python module
00119 @type numpy module
00120 """
00121 try:
00122 _x = self
00123 buff.write(_struct_7dB.pack(_x.scanner_pose.position.x, _x.scanner_pose.position.y, _x.scanner_pose.position.z, _x.scanner_pose.orientation.x, _x.scanner_pose.orientation.y, _x.scanner_pose.orientation.z, _x.scanner_pose.orientation.w, _x.request_ray_directions))
00124 except struct.error as se: self._check_types(se)
00125 except TypeError as te: self._check_types(te)
00126
00127 def deserialize_numpy(self, str, numpy):
00128 """
00129 unpack serialized message in str into this message instance using numpy for array types
00130 @param str: byte array of serialized message
00131 @type str: str
00132 @param numpy: numpy python module
00133 @type numpy: module
00134 """
00135 try:
00136 if self.scanner_pose is None:
00137 self.scanner_pose = geometry_msgs.msg.Pose()
00138 end = 0
00139 _x = self
00140 start = end
00141 end += 57
00142 (_x.scanner_pose.position.x, _x.scanner_pose.position.y, _x.scanner_pose.position.z, _x.scanner_pose.orientation.x, _x.scanner_pose.orientation.y, _x.scanner_pose.orientation.z, _x.scanner_pose.orientation.w, _x.request_ray_directions,) = _struct_7dB.unpack(str[start:end])
00143 self.request_ray_directions = bool(self.request_ray_directions)
00144 return self
00145 except struct.error as e:
00146 raise roslib.message.DeserializationError(e)
00147
00148 _struct_I = roslib.message.struct_I
00149 _struct_7dB = struct.Struct("<7dB")
00150 """autogenerated by genmsg_py from SimulateScanResponse.msg. Do not edit."""
00151 import roslib.message
00152 import struct
00153
00154 import geometry_msgs.msg
00155 import std_msgs.msg
00156 import sensor_msgs.msg
00157
00158 class SimulateScanResponse(roslib.message.Message):
00159 _md5sum = "1feb66b2a9b2dd4ab7c14f6ef5754e41"
00160 _type = "graspit_interface_msgs/SimulateScanResponse"
00161 _has_header = False
00162 _full_text = """
00163
00164 sensor_msgs/PointCloud2 scan
00165
00166 geometry_msgs/Point32[] missing_ray_directions
00167
00168
00169 ================================================================================
00170 MSG: sensor_msgs/PointCloud2
00171 # This message holds a collection of N-dimensional points, which may
00172 # contain additional information such as normals, intensity, etc. The
00173 # point data is stored as a binary blob, its layout described by the
00174 # contents of the "fields" array.
00175
00176 # The point cloud data may be organized 2d (image-like) or 1d
00177 # (unordered). Point clouds organized as 2d images may be produced by
00178 # camera depth sensors such as stereo or time-of-flight.
00179
00180 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00181 # points).
00182 Header header
00183
00184 # 2D structure of the point cloud. If the cloud is unordered, height is
00185 # 1 and width is the length of the point cloud.
00186 uint32 height
00187 uint32 width
00188
00189 # Describes the channels and their layout in the binary data blob.
00190 PointField[] fields
00191
00192 bool is_bigendian # Is this data bigendian?
00193 uint32 point_step # Length of a point in bytes
00194 uint32 row_step # Length of a row in bytes
00195 uint8[] data # Actual point data, size is (row_step*height)
00196
00197 bool is_dense # True if there are no invalid points
00198
00199 ================================================================================
00200 MSG: std_msgs/Header
00201 # Standard metadata for higher-level stamped data types.
00202 # This is generally used to communicate timestamped data
00203 # in a particular coordinate frame.
00204 #
00205 # sequence ID: consecutively increasing ID
00206 uint32 seq
00207 #Two-integer timestamp that is expressed as:
00208 # * stamp.secs: seconds (stamp_secs) since epoch
00209 # * stamp.nsecs: nanoseconds since stamp_secs
00210 # time-handling sugar is provided by the client library
00211 time stamp
00212 #Frame this data is associated with
00213 # 0: no frame
00214 # 1: global frame
00215 string frame_id
00216
00217 ================================================================================
00218 MSG: sensor_msgs/PointField
00219 # This message holds the description of one point entry in the
00220 # PointCloud2 message format.
00221 uint8 INT8 = 1
00222 uint8 UINT8 = 2
00223 uint8 INT16 = 3
00224 uint8 UINT16 = 4
00225 uint8 INT32 = 5
00226 uint8 UINT32 = 6
00227 uint8 FLOAT32 = 7
00228 uint8 FLOAT64 = 8
00229
00230 string name # Name of field
00231 uint32 offset # Offset from start of point struct
00232 uint8 datatype # Datatype enumeration, see above
00233 uint32 count # How many elements in the field
00234
00235 ================================================================================
00236 MSG: geometry_msgs/Point32
00237 # This contains the position of a point in free space(with 32 bits of precision).
00238 # It is recommeded to use Point wherever possible instead of Point32.
00239 #
00240 # This recommendation is to promote interoperability.
00241 #
00242 # This message is designed to take up less space when sending
00243 # lots of points at once, as in the case of a PointCloud.
00244
00245 float32 x
00246 float32 y
00247 float32 z
00248 """
00249 __slots__ = ['scan','missing_ray_directions']
00250 _slot_types = ['sensor_msgs/PointCloud2','geometry_msgs/Point32[]']
00251
00252 def __init__(self, *args, **kwds):
00253 """
00254 Constructor. Any message fields that are implicitly/explicitly
00255 set to None will be assigned a default value. The recommend
00256 use is keyword arguments as this is more robust to future message
00257 changes. You cannot mix in-order arguments and keyword arguments.
00258
00259 The available fields are:
00260 scan,missing_ray_directions
00261
00262 @param args: complete set of field values, in .msg order
00263 @param kwds: use keyword arguments corresponding to message field names
00264 to set specific fields.
00265 """
00266 if args or kwds:
00267 super(SimulateScanResponse, self).__init__(*args, **kwds)
00268
00269 if self.scan is None:
00270 self.scan = sensor_msgs.msg.PointCloud2()
00271 if self.missing_ray_directions is None:
00272 self.missing_ray_directions = []
00273 else:
00274 self.scan = sensor_msgs.msg.PointCloud2()
00275 self.missing_ray_directions = []
00276
00277 def _get_types(self):
00278 """
00279 internal API method
00280 """
00281 return self._slot_types
00282
00283 def serialize(self, buff):
00284 """
00285 serialize message into buffer
00286 @param buff: buffer
00287 @type buff: StringIO
00288 """
00289 try:
00290 _x = self
00291 buff.write(_struct_3I.pack(_x.scan.header.seq, _x.scan.header.stamp.secs, _x.scan.header.stamp.nsecs))
00292 _x = self.scan.header.frame_id
00293 length = len(_x)
00294 buff.write(struct.pack('<I%ss'%length, length, _x))
00295 _x = self
00296 buff.write(_struct_2I.pack(_x.scan.height, _x.scan.width))
00297 length = len(self.scan.fields)
00298 buff.write(_struct_I.pack(length))
00299 for val1 in self.scan.fields:
00300 _x = val1.name
00301 length = len(_x)
00302 buff.write(struct.pack('<I%ss'%length, length, _x))
00303 _x = val1
00304 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00305 _x = self
00306 buff.write(_struct_B2I.pack(_x.scan.is_bigendian, _x.scan.point_step, _x.scan.row_step))
00307 _x = self.scan.data
00308 length = len(_x)
00309
00310 if type(_x) in [list, tuple]:
00311 buff.write(struct.pack('<I%sB'%length, length, *_x))
00312 else:
00313 buff.write(struct.pack('<I%ss'%length, length, _x))
00314 buff.write(_struct_B.pack(self.scan.is_dense))
00315 length = len(self.missing_ray_directions)
00316 buff.write(_struct_I.pack(length))
00317 for val1 in self.missing_ray_directions:
00318 _x = val1
00319 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00320 except struct.error as se: self._check_types(se)
00321 except TypeError as te: self._check_types(te)
00322
00323 def deserialize(self, str):
00324 """
00325 unpack serialized message in str into this message instance
00326 @param str: byte array of serialized message
00327 @type str: str
00328 """
00329 try:
00330 if self.scan is None:
00331 self.scan = sensor_msgs.msg.PointCloud2()
00332 end = 0
00333 _x = self
00334 start = end
00335 end += 12
00336 (_x.scan.header.seq, _x.scan.header.stamp.secs, _x.scan.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00337 start = end
00338 end += 4
00339 (length,) = _struct_I.unpack(str[start:end])
00340 start = end
00341 end += length
00342 self.scan.header.frame_id = str[start:end]
00343 _x = self
00344 start = end
00345 end += 8
00346 (_x.scan.height, _x.scan.width,) = _struct_2I.unpack(str[start:end])
00347 start = end
00348 end += 4
00349 (length,) = _struct_I.unpack(str[start:end])
00350 self.scan.fields = []
00351 for i in range(0, length):
00352 val1 = sensor_msgs.msg.PointField()
00353 start = end
00354 end += 4
00355 (length,) = _struct_I.unpack(str[start:end])
00356 start = end
00357 end += length
00358 val1.name = str[start:end]
00359 _x = val1
00360 start = end
00361 end += 9
00362 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00363 self.scan.fields.append(val1)
00364 _x = self
00365 start = end
00366 end += 9
00367 (_x.scan.is_bigendian, _x.scan.point_step, _x.scan.row_step,) = _struct_B2I.unpack(str[start:end])
00368 self.scan.is_bigendian = bool(self.scan.is_bigendian)
00369 start = end
00370 end += 4
00371 (length,) = _struct_I.unpack(str[start:end])
00372 start = end
00373 end += length
00374 self.scan.data = str[start:end]
00375 start = end
00376 end += 1
00377 (self.scan.is_dense,) = _struct_B.unpack(str[start:end])
00378 self.scan.is_dense = bool(self.scan.is_dense)
00379 start = end
00380 end += 4
00381 (length,) = _struct_I.unpack(str[start:end])
00382 self.missing_ray_directions = []
00383 for i in range(0, length):
00384 val1 = geometry_msgs.msg.Point32()
00385 _x = val1
00386 start = end
00387 end += 12
00388 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00389 self.missing_ray_directions.append(val1)
00390 return self
00391 except struct.error as e:
00392 raise roslib.message.DeserializationError(e)
00393
00394
00395 def serialize_numpy(self, buff, numpy):
00396 """
00397 serialize message with numpy array types into buffer
00398 @param buff: buffer
00399 @type buff: StringIO
00400 @param numpy: numpy python module
00401 @type numpy module
00402 """
00403 try:
00404 _x = self
00405 buff.write(_struct_3I.pack(_x.scan.header.seq, _x.scan.header.stamp.secs, _x.scan.header.stamp.nsecs))
00406 _x = self.scan.header.frame_id
00407 length = len(_x)
00408 buff.write(struct.pack('<I%ss'%length, length, _x))
00409 _x = self
00410 buff.write(_struct_2I.pack(_x.scan.height, _x.scan.width))
00411 length = len(self.scan.fields)
00412 buff.write(_struct_I.pack(length))
00413 for val1 in self.scan.fields:
00414 _x = val1.name
00415 length = len(_x)
00416 buff.write(struct.pack('<I%ss'%length, length, _x))
00417 _x = val1
00418 buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00419 _x = self
00420 buff.write(_struct_B2I.pack(_x.scan.is_bigendian, _x.scan.point_step, _x.scan.row_step))
00421 _x = self.scan.data
00422 length = len(_x)
00423
00424 if type(_x) in [list, tuple]:
00425 buff.write(struct.pack('<I%sB'%length, length, *_x))
00426 else:
00427 buff.write(struct.pack('<I%ss'%length, length, _x))
00428 buff.write(_struct_B.pack(self.scan.is_dense))
00429 length = len(self.missing_ray_directions)
00430 buff.write(_struct_I.pack(length))
00431 for val1 in self.missing_ray_directions:
00432 _x = val1
00433 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00434 except struct.error as se: self._check_types(se)
00435 except TypeError as te: self._check_types(te)
00436
00437 def deserialize_numpy(self, str, numpy):
00438 """
00439 unpack serialized message in str into this message instance using numpy for array types
00440 @param str: byte array of serialized message
00441 @type str: str
00442 @param numpy: numpy python module
00443 @type numpy: module
00444 """
00445 try:
00446 if self.scan is None:
00447 self.scan = sensor_msgs.msg.PointCloud2()
00448 end = 0
00449 _x = self
00450 start = end
00451 end += 12
00452 (_x.scan.header.seq, _x.scan.header.stamp.secs, _x.scan.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00453 start = end
00454 end += 4
00455 (length,) = _struct_I.unpack(str[start:end])
00456 start = end
00457 end += length
00458 self.scan.header.frame_id = str[start:end]
00459 _x = self
00460 start = end
00461 end += 8
00462 (_x.scan.height, _x.scan.width,) = _struct_2I.unpack(str[start:end])
00463 start = end
00464 end += 4
00465 (length,) = _struct_I.unpack(str[start:end])
00466 self.scan.fields = []
00467 for i in range(0, length):
00468 val1 = sensor_msgs.msg.PointField()
00469 start = end
00470 end += 4
00471 (length,) = _struct_I.unpack(str[start:end])
00472 start = end
00473 end += length
00474 val1.name = str[start:end]
00475 _x = val1
00476 start = end
00477 end += 9
00478 (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00479 self.scan.fields.append(val1)
00480 _x = self
00481 start = end
00482 end += 9
00483 (_x.scan.is_bigendian, _x.scan.point_step, _x.scan.row_step,) = _struct_B2I.unpack(str[start:end])
00484 self.scan.is_bigendian = bool(self.scan.is_bigendian)
00485 start = end
00486 end += 4
00487 (length,) = _struct_I.unpack(str[start:end])
00488 start = end
00489 end += length
00490 self.scan.data = str[start:end]
00491 start = end
00492 end += 1
00493 (self.scan.is_dense,) = _struct_B.unpack(str[start:end])
00494 self.scan.is_dense = bool(self.scan.is_dense)
00495 start = end
00496 end += 4
00497 (length,) = _struct_I.unpack(str[start:end])
00498 self.missing_ray_directions = []
00499 for i in range(0, length):
00500 val1 = geometry_msgs.msg.Point32()
00501 _x = val1
00502 start = end
00503 end += 12
00504 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00505 self.missing_ray_directions.append(val1)
00506 return self
00507 except struct.error as e:
00508 raise roslib.message.DeserializationError(e)
00509
00510 _struct_I = roslib.message.struct_I
00511 _struct_IBI = struct.Struct("<IBI")
00512 _struct_B = struct.Struct("<B")
00513 _struct_3f = struct.Struct("<3f")
00514 _struct_3I = struct.Struct("<3I")
00515 _struct_B2I = struct.Struct("<B2I")
00516 _struct_2I = struct.Struct("<2I")
00517 class SimulateScan(roslib.message.ServiceDefinition):
00518 _type = 'graspit_interface_msgs/SimulateScan'
00519 _md5sum = '94771e8a60b9bcb2e1caf023bef79cb6'
00520 _request_class = SimulateScanRequest
00521 _response_class = SimulateScanResponse