00001 """autogenerated by genpy from calibration_msgs/LaserMeasurement.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 geometry_msgs.msg
00008 import calibration_msgs.msg
00009 import sensor_msgs.msg
00010 import genpy
00011 import std_msgs.msg
00012
00013 class LaserMeasurement(genpy.Message):
00014 _md5sum = "7fa7e818b1234a443aa5d8e315175d17"
00015 _type = "calibration_msgs/LaserMeasurement"
00016 _has_header = True
00017 _full_text = """Header header
00018 string laser_id
00019 sensor_msgs/JointState[] joint_points
00020
00021 # True -> The extra debugging fields are populated
00022 bool verbose
00023
00024 # Extra, partially processed data. Only needed for debugging
00025 calibration_msgs/DenseLaserSnapshot snapshot
00026 sensor_msgs/Image laser_image
00027 calibration_msgs/CalibrationPattern image_features
00028 calibration_msgs/JointStateCalibrationPattern joint_features
00029
00030 ================================================================================
00031 MSG: std_msgs/Header
00032 # Standard metadata for higher-level stamped data types.
00033 # This is generally used to communicate timestamped data
00034 # in a particular coordinate frame.
00035 #
00036 # sequence ID: consecutively increasing ID
00037 uint32 seq
00038 #Two-integer timestamp that is expressed as:
00039 # * stamp.secs: seconds (stamp_secs) since epoch
00040 # * stamp.nsecs: nanoseconds since stamp_secs
00041 # time-handling sugar is provided by the client library
00042 time stamp
00043 #Frame this data is associated with
00044 # 0: no frame
00045 # 1: global frame
00046 string frame_id
00047
00048 ================================================================================
00049 MSG: sensor_msgs/JointState
00050 # This is a message that holds data to describe the state of a set of torque controlled joints.
00051 #
00052 # The state of each joint (revolute or prismatic) is defined by:
00053 # * the position of the joint (rad or m),
00054 # * the velocity of the joint (rad/s or m/s) and
00055 # * the effort that is applied in the joint (Nm or N).
00056 #
00057 # Each joint is uniquely identified by its name
00058 # The header specifies the time at which the joint states were recorded. All the joint states
00059 # in one message have to be recorded at the same time.
00060 #
00061 # This message consists of a multiple arrays, one for each part of the joint state.
00062 # The goal is to make each of the fields optional. When e.g. your joints have no
00063 # effort associated with them, you can leave the effort array empty.
00064 #
00065 # All arrays in this message should have the same size, or be empty.
00066 # This is the only way to uniquely associate the joint name with the correct
00067 # states.
00068
00069
00070 Header header
00071
00072 string[] name
00073 float64[] position
00074 float64[] velocity
00075 float64[] effort
00076
00077 ================================================================================
00078 MSG: calibration_msgs/DenseLaserSnapshot
00079 # Provides all the state & sensor information for
00080 # a single sweep of laser attached to some mechanism.
00081 # Most likely, this will be used with PR2's tilting laser mechanism
00082 Header header
00083
00084 # Store the laser intrinsics. This is very similar to the
00085 # intrinsics commonly stored in
00086 float32 angle_min # start angle of the scan [rad]
00087 float32 angle_max # end angle of the scan [rad]
00088 float32 angle_increment # angular distance between measurements [rad]
00089 float32 time_increment # time between measurements [seconds]
00090 float32 range_min # minimum range value [m]
00091 float32 range_max # maximum range value [m]
00092
00093 # Define the size of the binary data
00094 uint32 readings_per_scan # (Width)
00095 uint32 num_scans # (Height)
00096
00097 # 2D Arrays storing laser data.
00098 # We can think of each type data as being a single channel image.
00099 # Each row of the image has data from a single scan, and scans are
00100 # concatenated to form the entire 'image'.
00101 float32[] ranges # (Image data)
00102 float32[] intensities # (Image data)
00103
00104 # Store the start time of each scan
00105 time[] scan_start
00106
00107 ================================================================================
00108 MSG: sensor_msgs/Image
00109 # This message contains an uncompressed image
00110 # (0, 0) is at top-left corner of image
00111 #
00112
00113 Header header # Header timestamp should be acquisition time of image
00114 # Header frame_id should be optical frame of camera
00115 # origin of frame should be optical center of cameara
00116 # +x should point to the right in the image
00117 # +y should point down in the image
00118 # +z should point into to plane of the image
00119 # If the frame_id here and the frame_id of the CameraInfo
00120 # message associated with the image conflict
00121 # the behavior is undefined
00122
00123 uint32 height # image height, that is, number of rows
00124 uint32 width # image width, that is, number of columns
00125
00126 # The legal values for encoding are in file src/image_encodings.cpp
00127 # If you want to standardize a new string format, join
00128 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00129
00130 string encoding # Encoding of pixels -- channel meaning, ordering, size
00131 # taken from the list of strings in src/image_encodings.cpp
00132
00133 uint8 is_bigendian # is this data bigendian?
00134 uint32 step # Full row length in bytes
00135 uint8[] data # actual matrix data, size is (step * rows)
00136
00137 ================================================================================
00138 MSG: calibration_msgs/CalibrationPattern
00139 Header header
00140 geometry_msgs/Point[] object_points
00141 geometry_msgs/Point[] image_points
00142 uint8 success
00143
00144 ================================================================================
00145 MSG: geometry_msgs/Point
00146 # This contains the position of a point in free space
00147 float64 x
00148 float64 y
00149 float64 z
00150
00151 ================================================================================
00152 MSG: calibration_msgs/JointStateCalibrationPattern
00153 Header header
00154 geometry_msgs/Point[] object_points
00155 sensor_msgs/JointState[] joint_points
00156
00157
00158 """
00159 __slots__ = ['header','laser_id','joint_points','verbose','snapshot','laser_image','image_features','joint_features']
00160 _slot_types = ['std_msgs/Header','string','sensor_msgs/JointState[]','bool','calibration_msgs/DenseLaserSnapshot','sensor_msgs/Image','calibration_msgs/CalibrationPattern','calibration_msgs/JointStateCalibrationPattern']
00161
00162 def __init__(self, *args, **kwds):
00163 """
00164 Constructor. Any message fields that are implicitly/explicitly
00165 set to None will be assigned a default value. The recommend
00166 use is keyword arguments as this is more robust to future message
00167 changes. You cannot mix in-order arguments and keyword arguments.
00168
00169 The available fields are:
00170 header,laser_id,joint_points,verbose,snapshot,laser_image,image_features,joint_features
00171
00172 :param args: complete set of field values, in .msg order
00173 :param kwds: use keyword arguments corresponding to message field names
00174 to set specific fields.
00175 """
00176 if args or kwds:
00177 super(LaserMeasurement, self).__init__(*args, **kwds)
00178
00179 if self.header is None:
00180 self.header = std_msgs.msg.Header()
00181 if self.laser_id is None:
00182 self.laser_id = ''
00183 if self.joint_points is None:
00184 self.joint_points = []
00185 if self.verbose is None:
00186 self.verbose = False
00187 if self.snapshot is None:
00188 self.snapshot = calibration_msgs.msg.DenseLaserSnapshot()
00189 if self.laser_image is None:
00190 self.laser_image = sensor_msgs.msg.Image()
00191 if self.image_features is None:
00192 self.image_features = calibration_msgs.msg.CalibrationPattern()
00193 if self.joint_features is None:
00194 self.joint_features = calibration_msgs.msg.JointStateCalibrationPattern()
00195 else:
00196 self.header = std_msgs.msg.Header()
00197 self.laser_id = ''
00198 self.joint_points = []
00199 self.verbose = False
00200 self.snapshot = calibration_msgs.msg.DenseLaserSnapshot()
00201 self.laser_image = sensor_msgs.msg.Image()
00202 self.image_features = calibration_msgs.msg.CalibrationPattern()
00203 self.joint_features = calibration_msgs.msg.JointStateCalibrationPattern()
00204
00205 def _get_types(self):
00206 """
00207 internal API method
00208 """
00209 return self._slot_types
00210
00211 def serialize(self, buff):
00212 """
00213 serialize message into buffer
00214 :param buff: buffer, ``StringIO``
00215 """
00216 try:
00217 _x = self
00218 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00219 _x = self.header.frame_id
00220 length = len(_x)
00221 if python3 or type(_x) == unicode:
00222 _x = _x.encode('utf-8')
00223 length = len(_x)
00224 buff.write(struct.pack('<I%ss'%length, length, _x))
00225 _x = self.laser_id
00226 length = len(_x)
00227 if python3 or type(_x) == unicode:
00228 _x = _x.encode('utf-8')
00229 length = len(_x)
00230 buff.write(struct.pack('<I%ss'%length, length, _x))
00231 length = len(self.joint_points)
00232 buff.write(_struct_I.pack(length))
00233 for val1 in self.joint_points:
00234 _v1 = val1.header
00235 buff.write(_struct_I.pack(_v1.seq))
00236 _v2 = _v1.stamp
00237 _x = _v2
00238 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00239 _x = _v1.frame_id
00240 length = len(_x)
00241 if python3 or type(_x) == unicode:
00242 _x = _x.encode('utf-8')
00243 length = len(_x)
00244 buff.write(struct.pack('<I%ss'%length, length, _x))
00245 length = len(val1.name)
00246 buff.write(_struct_I.pack(length))
00247 for val2 in val1.name:
00248 length = len(val2)
00249 if python3 or type(val2) == unicode:
00250 val2 = val2.encode('utf-8')
00251 length = len(val2)
00252 buff.write(struct.pack('<I%ss'%length, length, val2))
00253 length = len(val1.position)
00254 buff.write(_struct_I.pack(length))
00255 pattern = '<%sd'%length
00256 buff.write(struct.pack(pattern, *val1.position))
00257 length = len(val1.velocity)
00258 buff.write(_struct_I.pack(length))
00259 pattern = '<%sd'%length
00260 buff.write(struct.pack(pattern, *val1.velocity))
00261 length = len(val1.effort)
00262 buff.write(_struct_I.pack(length))
00263 pattern = '<%sd'%length
00264 buff.write(struct.pack(pattern, *val1.effort))
00265 _x = self
00266 buff.write(_struct_B3I.pack(_x.verbose, _x.snapshot.header.seq, _x.snapshot.header.stamp.secs, _x.snapshot.header.stamp.nsecs))
00267 _x = self.snapshot.header.frame_id
00268 length = len(_x)
00269 if python3 or type(_x) == unicode:
00270 _x = _x.encode('utf-8')
00271 length = len(_x)
00272 buff.write(struct.pack('<I%ss'%length, length, _x))
00273 _x = self
00274 buff.write(_struct_6f2I.pack(_x.snapshot.angle_min, _x.snapshot.angle_max, _x.snapshot.angle_increment, _x.snapshot.time_increment, _x.snapshot.range_min, _x.snapshot.range_max, _x.snapshot.readings_per_scan, _x.snapshot.num_scans))
00275 length = len(self.snapshot.ranges)
00276 buff.write(_struct_I.pack(length))
00277 pattern = '<%sf'%length
00278 buff.write(struct.pack(pattern, *self.snapshot.ranges))
00279 length = len(self.snapshot.intensities)
00280 buff.write(_struct_I.pack(length))
00281 pattern = '<%sf'%length
00282 buff.write(struct.pack(pattern, *self.snapshot.intensities))
00283 length = len(self.snapshot.scan_start)
00284 buff.write(_struct_I.pack(length))
00285 for val1 in self.snapshot.scan_start:
00286 _x = val1
00287 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00288 _x = self
00289 buff.write(_struct_3I.pack(_x.laser_image.header.seq, _x.laser_image.header.stamp.secs, _x.laser_image.header.stamp.nsecs))
00290 _x = self.laser_image.header.frame_id
00291 length = len(_x)
00292 if python3 or type(_x) == unicode:
00293 _x = _x.encode('utf-8')
00294 length = len(_x)
00295 buff.write(struct.pack('<I%ss'%length, length, _x))
00296 _x = self
00297 buff.write(_struct_2I.pack(_x.laser_image.height, _x.laser_image.width))
00298 _x = self.laser_image.encoding
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 _x = self
00305 buff.write(_struct_BI.pack(_x.laser_image.is_bigendian, _x.laser_image.step))
00306 _x = self.laser_image.data
00307 length = len(_x)
00308
00309 if type(_x) in [list, tuple]:
00310 buff.write(struct.pack('<I%sB'%length, length, *_x))
00311 else:
00312 buff.write(struct.pack('<I%ss'%length, length, _x))
00313 _x = self
00314 buff.write(_struct_3I.pack(_x.image_features.header.seq, _x.image_features.header.stamp.secs, _x.image_features.header.stamp.nsecs))
00315 _x = self.image_features.header.frame_id
00316 length = len(_x)
00317 if python3 or type(_x) == unicode:
00318 _x = _x.encode('utf-8')
00319 length = len(_x)
00320 buff.write(struct.pack('<I%ss'%length, length, _x))
00321 length = len(self.image_features.object_points)
00322 buff.write(_struct_I.pack(length))
00323 for val1 in self.image_features.object_points:
00324 _x = val1
00325 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00326 length = len(self.image_features.image_points)
00327 buff.write(_struct_I.pack(length))
00328 for val1 in self.image_features.image_points:
00329 _x = val1
00330 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00331 _x = self
00332 buff.write(_struct_B3I.pack(_x.image_features.success, _x.joint_features.header.seq, _x.joint_features.header.stamp.secs, _x.joint_features.header.stamp.nsecs))
00333 _x = self.joint_features.header.frame_id
00334 length = len(_x)
00335 if python3 or type(_x) == unicode:
00336 _x = _x.encode('utf-8')
00337 length = len(_x)
00338 buff.write(struct.pack('<I%ss'%length, length, _x))
00339 length = len(self.joint_features.object_points)
00340 buff.write(_struct_I.pack(length))
00341 for val1 in self.joint_features.object_points:
00342 _x = val1
00343 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00344 length = len(self.joint_features.joint_points)
00345 buff.write(_struct_I.pack(length))
00346 for val1 in self.joint_features.joint_points:
00347 _v3 = val1.header
00348 buff.write(_struct_I.pack(_v3.seq))
00349 _v4 = _v3.stamp
00350 _x = _v4
00351 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00352 _x = _v3.frame_id
00353 length = len(_x)
00354 if python3 or type(_x) == unicode:
00355 _x = _x.encode('utf-8')
00356 length = len(_x)
00357 buff.write(struct.pack('<I%ss'%length, length, _x))
00358 length = len(val1.name)
00359 buff.write(_struct_I.pack(length))
00360 for val2 in val1.name:
00361 length = len(val2)
00362 if python3 or type(val2) == unicode:
00363 val2 = val2.encode('utf-8')
00364 length = len(val2)
00365 buff.write(struct.pack('<I%ss'%length, length, val2))
00366 length = len(val1.position)
00367 buff.write(_struct_I.pack(length))
00368 pattern = '<%sd'%length
00369 buff.write(struct.pack(pattern, *val1.position))
00370 length = len(val1.velocity)
00371 buff.write(_struct_I.pack(length))
00372 pattern = '<%sd'%length
00373 buff.write(struct.pack(pattern, *val1.velocity))
00374 length = len(val1.effort)
00375 buff.write(_struct_I.pack(length))
00376 pattern = '<%sd'%length
00377 buff.write(struct.pack(pattern, *val1.effort))
00378 except struct.error as se: self._check_types(se)
00379 except TypeError as te: self._check_types(te)
00380
00381 def deserialize(self, str):
00382 """
00383 unpack serialized message in str into this message instance
00384 :param str: byte array of serialized message, ``str``
00385 """
00386 try:
00387 if self.header is None:
00388 self.header = std_msgs.msg.Header()
00389 if self.joint_points is None:
00390 self.joint_points = None
00391 if self.snapshot is None:
00392 self.snapshot = calibration_msgs.msg.DenseLaserSnapshot()
00393 if self.laser_image is None:
00394 self.laser_image = sensor_msgs.msg.Image()
00395 if self.image_features is None:
00396 self.image_features = calibration_msgs.msg.CalibrationPattern()
00397 if self.joint_features is None:
00398 self.joint_features = calibration_msgs.msg.JointStateCalibrationPattern()
00399 end = 0
00400 _x = self
00401 start = end
00402 end += 12
00403 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00404 start = end
00405 end += 4
00406 (length,) = _struct_I.unpack(str[start:end])
00407 start = end
00408 end += length
00409 if python3:
00410 self.header.frame_id = str[start:end].decode('utf-8')
00411 else:
00412 self.header.frame_id = str[start:end]
00413 start = end
00414 end += 4
00415 (length,) = _struct_I.unpack(str[start:end])
00416 start = end
00417 end += length
00418 if python3:
00419 self.laser_id = str[start:end].decode('utf-8')
00420 else:
00421 self.laser_id = str[start:end]
00422 start = end
00423 end += 4
00424 (length,) = _struct_I.unpack(str[start:end])
00425 self.joint_points = []
00426 for i in range(0, length):
00427 val1 = sensor_msgs.msg.JointState()
00428 _v5 = val1.header
00429 start = end
00430 end += 4
00431 (_v5.seq,) = _struct_I.unpack(str[start:end])
00432 _v6 = _v5.stamp
00433 _x = _v6
00434 start = end
00435 end += 8
00436 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00437 start = end
00438 end += 4
00439 (length,) = _struct_I.unpack(str[start:end])
00440 start = end
00441 end += length
00442 if python3:
00443 _v5.frame_id = str[start:end].decode('utf-8')
00444 else:
00445 _v5.frame_id = str[start:end]
00446 start = end
00447 end += 4
00448 (length,) = _struct_I.unpack(str[start:end])
00449 val1.name = []
00450 for i in range(0, length):
00451 start = end
00452 end += 4
00453 (length,) = _struct_I.unpack(str[start:end])
00454 start = end
00455 end += length
00456 if python3:
00457 val2 = str[start:end].decode('utf-8')
00458 else:
00459 val2 = str[start:end]
00460 val1.name.append(val2)
00461 start = end
00462 end += 4
00463 (length,) = _struct_I.unpack(str[start:end])
00464 pattern = '<%sd'%length
00465 start = end
00466 end += struct.calcsize(pattern)
00467 val1.position = struct.unpack(pattern, str[start:end])
00468 start = end
00469 end += 4
00470 (length,) = _struct_I.unpack(str[start:end])
00471 pattern = '<%sd'%length
00472 start = end
00473 end += struct.calcsize(pattern)
00474 val1.velocity = struct.unpack(pattern, str[start:end])
00475 start = end
00476 end += 4
00477 (length,) = _struct_I.unpack(str[start:end])
00478 pattern = '<%sd'%length
00479 start = end
00480 end += struct.calcsize(pattern)
00481 val1.effort = struct.unpack(pattern, str[start:end])
00482 self.joint_points.append(val1)
00483 _x = self
00484 start = end
00485 end += 13
00486 (_x.verbose, _x.snapshot.header.seq, _x.snapshot.header.stamp.secs, _x.snapshot.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00487 self.verbose = bool(self.verbose)
00488 start = end
00489 end += 4
00490 (length,) = _struct_I.unpack(str[start:end])
00491 start = end
00492 end += length
00493 if python3:
00494 self.snapshot.header.frame_id = str[start:end].decode('utf-8')
00495 else:
00496 self.snapshot.header.frame_id = str[start:end]
00497 _x = self
00498 start = end
00499 end += 32
00500 (_x.snapshot.angle_min, _x.snapshot.angle_max, _x.snapshot.angle_increment, _x.snapshot.time_increment, _x.snapshot.range_min, _x.snapshot.range_max, _x.snapshot.readings_per_scan, _x.snapshot.num_scans,) = _struct_6f2I.unpack(str[start:end])
00501 start = end
00502 end += 4
00503 (length,) = _struct_I.unpack(str[start:end])
00504 pattern = '<%sf'%length
00505 start = end
00506 end += struct.calcsize(pattern)
00507 self.snapshot.ranges = struct.unpack(pattern, str[start:end])
00508 start = end
00509 end += 4
00510 (length,) = _struct_I.unpack(str[start:end])
00511 pattern = '<%sf'%length
00512 start = end
00513 end += struct.calcsize(pattern)
00514 self.snapshot.intensities = struct.unpack(pattern, str[start:end])
00515 start = end
00516 end += 4
00517 (length,) = _struct_I.unpack(str[start:end])
00518 self.snapshot.scan_start = []
00519 for i in range(0, length):
00520 val1 = genpy.Time()
00521 _x = val1
00522 start = end
00523 end += 8
00524 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00525 self.snapshot.scan_start.append(val1)
00526 _x = self
00527 start = end
00528 end += 12
00529 (_x.laser_image.header.seq, _x.laser_image.header.stamp.secs, _x.laser_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00530 start = end
00531 end += 4
00532 (length,) = _struct_I.unpack(str[start:end])
00533 start = end
00534 end += length
00535 if python3:
00536 self.laser_image.header.frame_id = str[start:end].decode('utf-8')
00537 else:
00538 self.laser_image.header.frame_id = str[start:end]
00539 _x = self
00540 start = end
00541 end += 8
00542 (_x.laser_image.height, _x.laser_image.width,) = _struct_2I.unpack(str[start:end])
00543 start = end
00544 end += 4
00545 (length,) = _struct_I.unpack(str[start:end])
00546 start = end
00547 end += length
00548 if python3:
00549 self.laser_image.encoding = str[start:end].decode('utf-8')
00550 else:
00551 self.laser_image.encoding = str[start:end]
00552 _x = self
00553 start = end
00554 end += 5
00555 (_x.laser_image.is_bigendian, _x.laser_image.step,) = _struct_BI.unpack(str[start:end])
00556 start = end
00557 end += 4
00558 (length,) = _struct_I.unpack(str[start:end])
00559 start = end
00560 end += length
00561 if python3:
00562 self.laser_image.data = str[start:end].decode('utf-8')
00563 else:
00564 self.laser_image.data = str[start:end]
00565 _x = self
00566 start = end
00567 end += 12
00568 (_x.image_features.header.seq, _x.image_features.header.stamp.secs, _x.image_features.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00569 start = end
00570 end += 4
00571 (length,) = _struct_I.unpack(str[start:end])
00572 start = end
00573 end += length
00574 if python3:
00575 self.image_features.header.frame_id = str[start:end].decode('utf-8')
00576 else:
00577 self.image_features.header.frame_id = str[start:end]
00578 start = end
00579 end += 4
00580 (length,) = _struct_I.unpack(str[start:end])
00581 self.image_features.object_points = []
00582 for i in range(0, length):
00583 val1 = geometry_msgs.msg.Point()
00584 _x = val1
00585 start = end
00586 end += 24
00587 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00588 self.image_features.object_points.append(val1)
00589 start = end
00590 end += 4
00591 (length,) = _struct_I.unpack(str[start:end])
00592 self.image_features.image_points = []
00593 for i in range(0, length):
00594 val1 = geometry_msgs.msg.Point()
00595 _x = val1
00596 start = end
00597 end += 24
00598 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00599 self.image_features.image_points.append(val1)
00600 _x = self
00601 start = end
00602 end += 13
00603 (_x.image_features.success, _x.joint_features.header.seq, _x.joint_features.header.stamp.secs, _x.joint_features.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00604 start = end
00605 end += 4
00606 (length,) = _struct_I.unpack(str[start:end])
00607 start = end
00608 end += length
00609 if python3:
00610 self.joint_features.header.frame_id = str[start:end].decode('utf-8')
00611 else:
00612 self.joint_features.header.frame_id = str[start:end]
00613 start = end
00614 end += 4
00615 (length,) = _struct_I.unpack(str[start:end])
00616 self.joint_features.object_points = []
00617 for i in range(0, length):
00618 val1 = geometry_msgs.msg.Point()
00619 _x = val1
00620 start = end
00621 end += 24
00622 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00623 self.joint_features.object_points.append(val1)
00624 start = end
00625 end += 4
00626 (length,) = _struct_I.unpack(str[start:end])
00627 self.joint_features.joint_points = []
00628 for i in range(0, length):
00629 val1 = sensor_msgs.msg.JointState()
00630 _v7 = val1.header
00631 start = end
00632 end += 4
00633 (_v7.seq,) = _struct_I.unpack(str[start:end])
00634 _v8 = _v7.stamp
00635 _x = _v8
00636 start = end
00637 end += 8
00638 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00639 start = end
00640 end += 4
00641 (length,) = _struct_I.unpack(str[start:end])
00642 start = end
00643 end += length
00644 if python3:
00645 _v7.frame_id = str[start:end].decode('utf-8')
00646 else:
00647 _v7.frame_id = str[start:end]
00648 start = end
00649 end += 4
00650 (length,) = _struct_I.unpack(str[start:end])
00651 val1.name = []
00652 for i in range(0, length):
00653 start = end
00654 end += 4
00655 (length,) = _struct_I.unpack(str[start:end])
00656 start = end
00657 end += length
00658 if python3:
00659 val2 = str[start:end].decode('utf-8')
00660 else:
00661 val2 = str[start:end]
00662 val1.name.append(val2)
00663 start = end
00664 end += 4
00665 (length,) = _struct_I.unpack(str[start:end])
00666 pattern = '<%sd'%length
00667 start = end
00668 end += struct.calcsize(pattern)
00669 val1.position = struct.unpack(pattern, str[start:end])
00670 start = end
00671 end += 4
00672 (length,) = _struct_I.unpack(str[start:end])
00673 pattern = '<%sd'%length
00674 start = end
00675 end += struct.calcsize(pattern)
00676 val1.velocity = struct.unpack(pattern, str[start:end])
00677 start = end
00678 end += 4
00679 (length,) = _struct_I.unpack(str[start:end])
00680 pattern = '<%sd'%length
00681 start = end
00682 end += struct.calcsize(pattern)
00683 val1.effort = struct.unpack(pattern, str[start:end])
00684 self.joint_features.joint_points.append(val1)
00685 return self
00686 except struct.error as e:
00687 raise genpy.DeserializationError(e)
00688
00689
00690 def serialize_numpy(self, buff, numpy):
00691 """
00692 serialize message with numpy array types into buffer
00693 :param buff: buffer, ``StringIO``
00694 :param numpy: numpy python module
00695 """
00696 try:
00697 _x = self
00698 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00699 _x = self.header.frame_id
00700 length = len(_x)
00701 if python3 or type(_x) == unicode:
00702 _x = _x.encode('utf-8')
00703 length = len(_x)
00704 buff.write(struct.pack('<I%ss'%length, length, _x))
00705 _x = self.laser_id
00706 length = len(_x)
00707 if python3 or type(_x) == unicode:
00708 _x = _x.encode('utf-8')
00709 length = len(_x)
00710 buff.write(struct.pack('<I%ss'%length, length, _x))
00711 length = len(self.joint_points)
00712 buff.write(_struct_I.pack(length))
00713 for val1 in self.joint_points:
00714 _v9 = val1.header
00715 buff.write(_struct_I.pack(_v9.seq))
00716 _v10 = _v9.stamp
00717 _x = _v10
00718 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00719 _x = _v9.frame_id
00720 length = len(_x)
00721 if python3 or type(_x) == unicode:
00722 _x = _x.encode('utf-8')
00723 length = len(_x)
00724 buff.write(struct.pack('<I%ss'%length, length, _x))
00725 length = len(val1.name)
00726 buff.write(_struct_I.pack(length))
00727 for val2 in val1.name:
00728 length = len(val2)
00729 if python3 or type(val2) == unicode:
00730 val2 = val2.encode('utf-8')
00731 length = len(val2)
00732 buff.write(struct.pack('<I%ss'%length, length, val2))
00733 length = len(val1.position)
00734 buff.write(_struct_I.pack(length))
00735 pattern = '<%sd'%length
00736 buff.write(val1.position.tostring())
00737 length = len(val1.velocity)
00738 buff.write(_struct_I.pack(length))
00739 pattern = '<%sd'%length
00740 buff.write(val1.velocity.tostring())
00741 length = len(val1.effort)
00742 buff.write(_struct_I.pack(length))
00743 pattern = '<%sd'%length
00744 buff.write(val1.effort.tostring())
00745 _x = self
00746 buff.write(_struct_B3I.pack(_x.verbose, _x.snapshot.header.seq, _x.snapshot.header.stamp.secs, _x.snapshot.header.stamp.nsecs))
00747 _x = self.snapshot.header.frame_id
00748 length = len(_x)
00749 if python3 or type(_x) == unicode:
00750 _x = _x.encode('utf-8')
00751 length = len(_x)
00752 buff.write(struct.pack('<I%ss'%length, length, _x))
00753 _x = self
00754 buff.write(_struct_6f2I.pack(_x.snapshot.angle_min, _x.snapshot.angle_max, _x.snapshot.angle_increment, _x.snapshot.time_increment, _x.snapshot.range_min, _x.snapshot.range_max, _x.snapshot.readings_per_scan, _x.snapshot.num_scans))
00755 length = len(self.snapshot.ranges)
00756 buff.write(_struct_I.pack(length))
00757 pattern = '<%sf'%length
00758 buff.write(self.snapshot.ranges.tostring())
00759 length = len(self.snapshot.intensities)
00760 buff.write(_struct_I.pack(length))
00761 pattern = '<%sf'%length
00762 buff.write(self.snapshot.intensities.tostring())
00763 length = len(self.snapshot.scan_start)
00764 buff.write(_struct_I.pack(length))
00765 for val1 in self.snapshot.scan_start:
00766 _x = val1
00767 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00768 _x = self
00769 buff.write(_struct_3I.pack(_x.laser_image.header.seq, _x.laser_image.header.stamp.secs, _x.laser_image.header.stamp.nsecs))
00770 _x = self.laser_image.header.frame_id
00771 length = len(_x)
00772 if python3 or type(_x) == unicode:
00773 _x = _x.encode('utf-8')
00774 length = len(_x)
00775 buff.write(struct.pack('<I%ss'%length, length, _x))
00776 _x = self
00777 buff.write(_struct_2I.pack(_x.laser_image.height, _x.laser_image.width))
00778 _x = self.laser_image.encoding
00779 length = len(_x)
00780 if python3 or type(_x) == unicode:
00781 _x = _x.encode('utf-8')
00782 length = len(_x)
00783 buff.write(struct.pack('<I%ss'%length, length, _x))
00784 _x = self
00785 buff.write(_struct_BI.pack(_x.laser_image.is_bigendian, _x.laser_image.step))
00786 _x = self.laser_image.data
00787 length = len(_x)
00788
00789 if type(_x) in [list, tuple]:
00790 buff.write(struct.pack('<I%sB'%length, length, *_x))
00791 else:
00792 buff.write(struct.pack('<I%ss'%length, length, _x))
00793 _x = self
00794 buff.write(_struct_3I.pack(_x.image_features.header.seq, _x.image_features.header.stamp.secs, _x.image_features.header.stamp.nsecs))
00795 _x = self.image_features.header.frame_id
00796 length = len(_x)
00797 if python3 or type(_x) == unicode:
00798 _x = _x.encode('utf-8')
00799 length = len(_x)
00800 buff.write(struct.pack('<I%ss'%length, length, _x))
00801 length = len(self.image_features.object_points)
00802 buff.write(_struct_I.pack(length))
00803 for val1 in self.image_features.object_points:
00804 _x = val1
00805 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00806 length = len(self.image_features.image_points)
00807 buff.write(_struct_I.pack(length))
00808 for val1 in self.image_features.image_points:
00809 _x = val1
00810 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00811 _x = self
00812 buff.write(_struct_B3I.pack(_x.image_features.success, _x.joint_features.header.seq, _x.joint_features.header.stamp.secs, _x.joint_features.header.stamp.nsecs))
00813 _x = self.joint_features.header.frame_id
00814 length = len(_x)
00815 if python3 or type(_x) == unicode:
00816 _x = _x.encode('utf-8')
00817 length = len(_x)
00818 buff.write(struct.pack('<I%ss'%length, length, _x))
00819 length = len(self.joint_features.object_points)
00820 buff.write(_struct_I.pack(length))
00821 for val1 in self.joint_features.object_points:
00822 _x = val1
00823 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00824 length = len(self.joint_features.joint_points)
00825 buff.write(_struct_I.pack(length))
00826 for val1 in self.joint_features.joint_points:
00827 _v11 = val1.header
00828 buff.write(_struct_I.pack(_v11.seq))
00829 _v12 = _v11.stamp
00830 _x = _v12
00831 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00832 _x = _v11.frame_id
00833 length = len(_x)
00834 if python3 or type(_x) == unicode:
00835 _x = _x.encode('utf-8')
00836 length = len(_x)
00837 buff.write(struct.pack('<I%ss'%length, length, _x))
00838 length = len(val1.name)
00839 buff.write(_struct_I.pack(length))
00840 for val2 in val1.name:
00841 length = len(val2)
00842 if python3 or type(val2) == unicode:
00843 val2 = val2.encode('utf-8')
00844 length = len(val2)
00845 buff.write(struct.pack('<I%ss'%length, length, val2))
00846 length = len(val1.position)
00847 buff.write(_struct_I.pack(length))
00848 pattern = '<%sd'%length
00849 buff.write(val1.position.tostring())
00850 length = len(val1.velocity)
00851 buff.write(_struct_I.pack(length))
00852 pattern = '<%sd'%length
00853 buff.write(val1.velocity.tostring())
00854 length = len(val1.effort)
00855 buff.write(_struct_I.pack(length))
00856 pattern = '<%sd'%length
00857 buff.write(val1.effort.tostring())
00858 except struct.error as se: self._check_types(se)
00859 except TypeError as te: self._check_types(te)
00860
00861 def deserialize_numpy(self, str, numpy):
00862 """
00863 unpack serialized message in str into this message instance using numpy for array types
00864 :param str: byte array of serialized message, ``str``
00865 :param numpy: numpy python module
00866 """
00867 try:
00868 if self.header is None:
00869 self.header = std_msgs.msg.Header()
00870 if self.joint_points is None:
00871 self.joint_points = None
00872 if self.snapshot is None:
00873 self.snapshot = calibration_msgs.msg.DenseLaserSnapshot()
00874 if self.laser_image is None:
00875 self.laser_image = sensor_msgs.msg.Image()
00876 if self.image_features is None:
00877 self.image_features = calibration_msgs.msg.CalibrationPattern()
00878 if self.joint_features is None:
00879 self.joint_features = calibration_msgs.msg.JointStateCalibrationPattern()
00880 end = 0
00881 _x = self
00882 start = end
00883 end += 12
00884 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00885 start = end
00886 end += 4
00887 (length,) = _struct_I.unpack(str[start:end])
00888 start = end
00889 end += length
00890 if python3:
00891 self.header.frame_id = str[start:end].decode('utf-8')
00892 else:
00893 self.header.frame_id = str[start:end]
00894 start = end
00895 end += 4
00896 (length,) = _struct_I.unpack(str[start:end])
00897 start = end
00898 end += length
00899 if python3:
00900 self.laser_id = str[start:end].decode('utf-8')
00901 else:
00902 self.laser_id = str[start:end]
00903 start = end
00904 end += 4
00905 (length,) = _struct_I.unpack(str[start:end])
00906 self.joint_points = []
00907 for i in range(0, length):
00908 val1 = sensor_msgs.msg.JointState()
00909 _v13 = val1.header
00910 start = end
00911 end += 4
00912 (_v13.seq,) = _struct_I.unpack(str[start:end])
00913 _v14 = _v13.stamp
00914 _x = _v14
00915 start = end
00916 end += 8
00917 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00918 start = end
00919 end += 4
00920 (length,) = _struct_I.unpack(str[start:end])
00921 start = end
00922 end += length
00923 if python3:
00924 _v13.frame_id = str[start:end].decode('utf-8')
00925 else:
00926 _v13.frame_id = str[start:end]
00927 start = end
00928 end += 4
00929 (length,) = _struct_I.unpack(str[start:end])
00930 val1.name = []
00931 for i in range(0, length):
00932 start = end
00933 end += 4
00934 (length,) = _struct_I.unpack(str[start:end])
00935 start = end
00936 end += length
00937 if python3:
00938 val2 = str[start:end].decode('utf-8')
00939 else:
00940 val2 = str[start:end]
00941 val1.name.append(val2)
00942 start = end
00943 end += 4
00944 (length,) = _struct_I.unpack(str[start:end])
00945 pattern = '<%sd'%length
00946 start = end
00947 end += struct.calcsize(pattern)
00948 val1.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00949 start = end
00950 end += 4
00951 (length,) = _struct_I.unpack(str[start:end])
00952 pattern = '<%sd'%length
00953 start = end
00954 end += struct.calcsize(pattern)
00955 val1.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00956 start = end
00957 end += 4
00958 (length,) = _struct_I.unpack(str[start:end])
00959 pattern = '<%sd'%length
00960 start = end
00961 end += struct.calcsize(pattern)
00962 val1.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00963 self.joint_points.append(val1)
00964 _x = self
00965 start = end
00966 end += 13
00967 (_x.verbose, _x.snapshot.header.seq, _x.snapshot.header.stamp.secs, _x.snapshot.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00968 self.verbose = bool(self.verbose)
00969 start = end
00970 end += 4
00971 (length,) = _struct_I.unpack(str[start:end])
00972 start = end
00973 end += length
00974 if python3:
00975 self.snapshot.header.frame_id = str[start:end].decode('utf-8')
00976 else:
00977 self.snapshot.header.frame_id = str[start:end]
00978 _x = self
00979 start = end
00980 end += 32
00981 (_x.snapshot.angle_min, _x.snapshot.angle_max, _x.snapshot.angle_increment, _x.snapshot.time_increment, _x.snapshot.range_min, _x.snapshot.range_max, _x.snapshot.readings_per_scan, _x.snapshot.num_scans,) = _struct_6f2I.unpack(str[start:end])
00982 start = end
00983 end += 4
00984 (length,) = _struct_I.unpack(str[start:end])
00985 pattern = '<%sf'%length
00986 start = end
00987 end += struct.calcsize(pattern)
00988 self.snapshot.ranges = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00989 start = end
00990 end += 4
00991 (length,) = _struct_I.unpack(str[start:end])
00992 pattern = '<%sf'%length
00993 start = end
00994 end += struct.calcsize(pattern)
00995 self.snapshot.intensities = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00996 start = end
00997 end += 4
00998 (length,) = _struct_I.unpack(str[start:end])
00999 self.snapshot.scan_start = []
01000 for i in range(0, length):
01001 val1 = genpy.Time()
01002 _x = val1
01003 start = end
01004 end += 8
01005 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01006 self.snapshot.scan_start.append(val1)
01007 _x = self
01008 start = end
01009 end += 12
01010 (_x.laser_image.header.seq, _x.laser_image.header.stamp.secs, _x.laser_image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01011 start = end
01012 end += 4
01013 (length,) = _struct_I.unpack(str[start:end])
01014 start = end
01015 end += length
01016 if python3:
01017 self.laser_image.header.frame_id = str[start:end].decode('utf-8')
01018 else:
01019 self.laser_image.header.frame_id = str[start:end]
01020 _x = self
01021 start = end
01022 end += 8
01023 (_x.laser_image.height, _x.laser_image.width,) = _struct_2I.unpack(str[start:end])
01024 start = end
01025 end += 4
01026 (length,) = _struct_I.unpack(str[start:end])
01027 start = end
01028 end += length
01029 if python3:
01030 self.laser_image.encoding = str[start:end].decode('utf-8')
01031 else:
01032 self.laser_image.encoding = str[start:end]
01033 _x = self
01034 start = end
01035 end += 5
01036 (_x.laser_image.is_bigendian, _x.laser_image.step,) = _struct_BI.unpack(str[start:end])
01037 start = end
01038 end += 4
01039 (length,) = _struct_I.unpack(str[start:end])
01040 start = end
01041 end += length
01042 if python3:
01043 self.laser_image.data = str[start:end].decode('utf-8')
01044 else:
01045 self.laser_image.data = str[start:end]
01046 _x = self
01047 start = end
01048 end += 12
01049 (_x.image_features.header.seq, _x.image_features.header.stamp.secs, _x.image_features.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01050 start = end
01051 end += 4
01052 (length,) = _struct_I.unpack(str[start:end])
01053 start = end
01054 end += length
01055 if python3:
01056 self.image_features.header.frame_id = str[start:end].decode('utf-8')
01057 else:
01058 self.image_features.header.frame_id = str[start:end]
01059 start = end
01060 end += 4
01061 (length,) = _struct_I.unpack(str[start:end])
01062 self.image_features.object_points = []
01063 for i in range(0, length):
01064 val1 = geometry_msgs.msg.Point()
01065 _x = val1
01066 start = end
01067 end += 24
01068 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01069 self.image_features.object_points.append(val1)
01070 start = end
01071 end += 4
01072 (length,) = _struct_I.unpack(str[start:end])
01073 self.image_features.image_points = []
01074 for i in range(0, length):
01075 val1 = geometry_msgs.msg.Point()
01076 _x = val1
01077 start = end
01078 end += 24
01079 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01080 self.image_features.image_points.append(val1)
01081 _x = self
01082 start = end
01083 end += 13
01084 (_x.image_features.success, _x.joint_features.header.seq, _x.joint_features.header.stamp.secs, _x.joint_features.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
01085 start = end
01086 end += 4
01087 (length,) = _struct_I.unpack(str[start:end])
01088 start = end
01089 end += length
01090 if python3:
01091 self.joint_features.header.frame_id = str[start:end].decode('utf-8')
01092 else:
01093 self.joint_features.header.frame_id = str[start:end]
01094 start = end
01095 end += 4
01096 (length,) = _struct_I.unpack(str[start:end])
01097 self.joint_features.object_points = []
01098 for i in range(0, length):
01099 val1 = geometry_msgs.msg.Point()
01100 _x = val1
01101 start = end
01102 end += 24
01103 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01104 self.joint_features.object_points.append(val1)
01105 start = end
01106 end += 4
01107 (length,) = _struct_I.unpack(str[start:end])
01108 self.joint_features.joint_points = []
01109 for i in range(0, length):
01110 val1 = sensor_msgs.msg.JointState()
01111 _v15 = val1.header
01112 start = end
01113 end += 4
01114 (_v15.seq,) = _struct_I.unpack(str[start:end])
01115 _v16 = _v15.stamp
01116 _x = _v16
01117 start = end
01118 end += 8
01119 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01120 start = end
01121 end += 4
01122 (length,) = _struct_I.unpack(str[start:end])
01123 start = end
01124 end += length
01125 if python3:
01126 _v15.frame_id = str[start:end].decode('utf-8')
01127 else:
01128 _v15.frame_id = str[start:end]
01129 start = end
01130 end += 4
01131 (length,) = _struct_I.unpack(str[start:end])
01132 val1.name = []
01133 for i in range(0, length):
01134 start = end
01135 end += 4
01136 (length,) = _struct_I.unpack(str[start:end])
01137 start = end
01138 end += length
01139 if python3:
01140 val2 = str[start:end].decode('utf-8')
01141 else:
01142 val2 = str[start:end]
01143 val1.name.append(val2)
01144 start = end
01145 end += 4
01146 (length,) = _struct_I.unpack(str[start:end])
01147 pattern = '<%sd'%length
01148 start = end
01149 end += struct.calcsize(pattern)
01150 val1.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01151 start = end
01152 end += 4
01153 (length,) = _struct_I.unpack(str[start:end])
01154 pattern = '<%sd'%length
01155 start = end
01156 end += struct.calcsize(pattern)
01157 val1.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01158 start = end
01159 end += 4
01160 (length,) = _struct_I.unpack(str[start:end])
01161 pattern = '<%sd'%length
01162 start = end
01163 end += struct.calcsize(pattern)
01164 val1.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01165 self.joint_features.joint_points.append(val1)
01166 return self
01167 except struct.error as e:
01168 raise genpy.DeserializationError(e)
01169
01170 _struct_I = genpy.struct_I
01171 _struct_BI = struct.Struct("<BI")
01172 _struct_3I = struct.Struct("<3I")
01173 _struct_B3I = struct.Struct("<B3I")
01174 _struct_6f2I = struct.Struct("<6f2I")
01175 _struct_2I = struct.Struct("<2I")
01176 _struct_3d = struct.Struct("<3d")