_RobotMeasurement.py
Go to the documentation of this file.
00001 """autogenerated by genpy from calibration_msgs/RobotMeasurement.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 sensor_msgs.msg
00008 import calibration_msgs.msg
00009 import geometry_msgs.msg
00010 import genpy
00011 import std_msgs.msg
00012 
00013 class RobotMeasurement(genpy.Message):
00014   _md5sum = "fe22486c078efbf7892430dd0b99305c"
00015   _type = "calibration_msgs/RobotMeasurement"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """string sample_id    # Tag to figure out which yaml file this was generated from
00018 
00019 string target_id    # Defines the target that we were sensing.
00020 string chain_id     # Defines where this target was attached
00021 
00022 CameraMeasurement[] M_cam
00023 LaserMeasurement[]  M_laser
00024 ChainMeasurement[]  M_chain
00025 
00026 ================================================================================
00027 MSG: calibration_msgs/CameraMeasurement
00028 Header header
00029 string camera_id
00030 geometry_msgs/Point[] image_points
00031 sensor_msgs/CameraInfo cam_info
00032 
00033 # True -> The extra debugging fields are populated
00034 bool verbose
00035 
00036 # Extra, partially processed data. Only needed for debugging
00037 sensor_msgs/Image image
00038 sensor_msgs/Image image_rect
00039 calibration_msgs/CalibrationPattern features
00040 
00041 ================================================================================
00042 MSG: std_msgs/Header
00043 # Standard metadata for higher-level stamped data types.
00044 # This is generally used to communicate timestamped data 
00045 # in a particular coordinate frame.
00046 # 
00047 # sequence ID: consecutively increasing ID 
00048 uint32 seq
00049 #Two-integer timestamp that is expressed as:
00050 # * stamp.secs: seconds (stamp_secs) since epoch
00051 # * stamp.nsecs: nanoseconds since stamp_secs
00052 # time-handling sugar is provided by the client library
00053 time stamp
00054 #Frame this data is associated with
00055 # 0: no frame
00056 # 1: global frame
00057 string frame_id
00058 
00059 ================================================================================
00060 MSG: geometry_msgs/Point
00061 # This contains the position of a point in free space
00062 float64 x
00063 float64 y
00064 float64 z
00065 
00066 ================================================================================
00067 MSG: sensor_msgs/CameraInfo
00068 # This message defines meta information for a camera. It should be in a
00069 # camera namespace on topic "camera_info" and accompanied by up to five
00070 # image topics named:
00071 #
00072 #   image_raw - raw data from the camera driver, possibly Bayer encoded
00073 #   image            - monochrome, distorted
00074 #   image_color      - color, distorted
00075 #   image_rect       - monochrome, rectified
00076 #   image_rect_color - color, rectified
00077 #
00078 # The image_pipeline contains packages (image_proc, stereo_image_proc)
00079 # for producing the four processed image topics from image_raw and
00080 # camera_info. The meaning of the camera parameters are described in
00081 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
00082 #
00083 # The image_geometry package provides a user-friendly interface to
00084 # common operations using this meta information. If you want to, e.g.,
00085 # project a 3d point into image coordinates, we strongly recommend
00086 # using image_geometry.
00087 #
00088 # If the camera is uncalibrated, the matrices D, K, R, P should be left
00089 # zeroed out. In particular, clients may assume that K[0] == 0.0
00090 # indicates an uncalibrated camera.
00091 
00092 #######################################################################
00093 #                     Image acquisition info                          #
00094 #######################################################################
00095 
00096 # Time of image acquisition, camera coordinate frame ID
00097 Header header    # Header timestamp should be acquisition time of image
00098                  # Header frame_id should be optical frame of camera
00099                  # origin of frame should be optical center of camera
00100                  # +x should point to the right in the image
00101                  # +y should point down in the image
00102                  # +z should point into the plane of the image
00103 
00104 
00105 #######################################################################
00106 #                      Calibration Parameters                         #
00107 #######################################################################
00108 # These are fixed during camera calibration. Their values will be the #
00109 # same in all messages until the camera is recalibrated. Note that    #
00110 # self-calibrating systems may "recalibrate" frequently.              #
00111 #                                                                     #
00112 # The internal parameters can be used to warp a raw (distorted) image #
00113 # to:                                                                 #
00114 #   1. An undistorted image (requires D and K)                        #
00115 #   2. A rectified image (requires D, K, R)                           #
00116 # The projection matrix P projects 3D points into the rectified image.#
00117 #######################################################################
00118 
00119 # The image dimensions with which the camera was calibrated. Normally
00120 # this will be the full camera resolution in pixels.
00121 uint32 height
00122 uint32 width
00123 
00124 # The distortion model used. Supported models are listed in
00125 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
00126 # simple model of radial and tangential distortion - is sufficent.
00127 string distortion_model
00128 
00129 # The distortion parameters, size depending on the distortion model.
00130 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3).
00131 float64[] D
00132 
00133 # Intrinsic camera matrix for the raw (distorted) images.
00134 #     [fx  0 cx]
00135 # K = [ 0 fy cy]
00136 #     [ 0  0  1]
00137 # Projects 3D points in the camera coordinate frame to 2D pixel
00138 # coordinates using the focal lengths (fx, fy) and principal point
00139 # (cx, cy).
00140 float64[9]  K # 3x3 row-major matrix
00141 
00142 # Rectification matrix (stereo cameras only)
00143 # A rotation matrix aligning the camera coordinate system to the ideal
00144 # stereo image plane so that epipolar lines in both stereo images are
00145 # parallel.
00146 float64[9]  R # 3x3 row-major matrix
00147 
00148 # Projection/camera matrix
00149 #     [fx'  0  cx' Tx]
00150 # P = [ 0  fy' cy' Ty]
00151 #     [ 0   0   1   0]
00152 # By convention, this matrix specifies the intrinsic (camera) matrix
00153 #  of the processed (rectified) image. That is, the left 3x3 portion
00154 #  is the normal camera intrinsic matrix for the rectified image.
00155 # It projects 3D points in the camera coordinate frame to 2D pixel
00156 #  coordinates using the focal lengths (fx', fy') and principal point
00157 #  (cx', cy') - these may differ from the values in K.
00158 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
00159 #  also have R = the identity and P[1:3,1:3] = K.
00160 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the
00161 #  position of the optical center of the second camera in the first
00162 #  camera's frame. We assume Tz = 0 so both cameras are in the same
00163 #  stereo image plane. The first camera always has Tx = Ty = 0. For
00164 #  the right (second) camera of a horizontal stereo pair, Ty = 0 and
00165 #  Tx = -fx' * B, where B is the baseline between the cameras.
00166 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto
00167 #  the rectified image is given by:
00168 #  [u v w]' = P * [X Y Z 1]'
00169 #         x = u / w
00170 #         y = v / w
00171 #  This holds for both images of a stereo pair.
00172 float64[12] P # 3x4 row-major matrix
00173 
00174 
00175 #######################################################################
00176 #                      Operational Parameters                         #
00177 #######################################################################
00178 # These define the image region actually captured by the camera       #
00179 # driver. Although they affect the geometry of the output image, they #
00180 # may be changed freely without recalibrating the camera.             #
00181 #######################################################################
00182 
00183 # Binning refers here to any camera setting which combines rectangular
00184 #  neighborhoods of pixels into larger "super-pixels." It reduces the
00185 #  resolution of the output image to
00186 #  (width / binning_x) x (height / binning_y).
00187 # The default values binning_x = binning_y = 0 is considered the same
00188 #  as binning_x = binning_y = 1 (no subsampling).
00189 uint32 binning_x
00190 uint32 binning_y
00191 
00192 # Region of interest (subwindow of full camera resolution), given in
00193 #  full resolution (unbinned) image coordinates. A particular ROI
00194 #  always denotes the same window of pixels on the camera sensor,
00195 #  regardless of binning settings.
00196 # The default setting of roi (all values 0) is considered the same as
00197 #  full resolution (roi.width = width, roi.height = height).
00198 RegionOfInterest roi
00199 
00200 ================================================================================
00201 MSG: sensor_msgs/RegionOfInterest
00202 # This message is used to specify a region of interest within an image.
00203 #
00204 # When used to specify the ROI setting of the camera when the image was
00205 # taken, the height and width fields should either match the height and
00206 # width fields for the associated image; or height = width = 0
00207 # indicates that the full resolution image was captured.
00208 
00209 uint32 x_offset  # Leftmost pixel of the ROI
00210                  # (0 if the ROI includes the left edge of the image)
00211 uint32 y_offset  # Topmost pixel of the ROI
00212                  # (0 if the ROI includes the top edge of the image)
00213 uint32 height    # Height of ROI
00214 uint32 width     # Width of ROI
00215 
00216 # True if a distinct rectified ROI should be calculated from the "raw"
00217 # ROI in this message. Typically this should be False if the full image
00218 # is captured (ROI not used), and True if a subwindow is captured (ROI
00219 # used).
00220 bool do_rectify
00221 
00222 ================================================================================
00223 MSG: sensor_msgs/Image
00224 # This message contains an uncompressed image
00225 # (0, 0) is at top-left corner of image
00226 #
00227 
00228 Header header        # Header timestamp should be acquisition time of image
00229                      # Header frame_id should be optical frame of camera
00230                      # origin of frame should be optical center of cameara
00231                      # +x should point to the right in the image
00232                      # +y should point down in the image
00233                      # +z should point into to plane of the image
00234                      # If the frame_id here and the frame_id of the CameraInfo
00235                      # message associated with the image conflict
00236                      # the behavior is undefined
00237 
00238 uint32 height         # image height, that is, number of rows
00239 uint32 width          # image width, that is, number of columns
00240 
00241 # The legal values for encoding are in file src/image_encodings.cpp
00242 # If you want to standardize a new string format, join
00243 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.
00244 
00245 string encoding       # Encoding of pixels -- channel meaning, ordering, size
00246                       # taken from the list of strings in src/image_encodings.cpp
00247 
00248 uint8 is_bigendian    # is this data bigendian?
00249 uint32 step           # Full row length in bytes
00250 uint8[] data          # actual matrix data, size is (step * rows)
00251 
00252 ================================================================================
00253 MSG: calibration_msgs/CalibrationPattern
00254 Header header
00255 geometry_msgs/Point[] object_points
00256 geometry_msgs/Point[] image_points
00257 uint8 success
00258 
00259 ================================================================================
00260 MSG: calibration_msgs/LaserMeasurement
00261 Header header
00262 string laser_id
00263 sensor_msgs/JointState[] joint_points
00264 
00265 # True -> The extra debugging fields are populated
00266 bool verbose
00267 
00268 # Extra, partially processed data. Only needed for debugging
00269 calibration_msgs/DenseLaserSnapshot snapshot
00270 sensor_msgs/Image laser_image
00271 calibration_msgs/CalibrationPattern image_features
00272 calibration_msgs/JointStateCalibrationPattern joint_features
00273 
00274 ================================================================================
00275 MSG: sensor_msgs/JointState
00276 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00277 #
00278 # The state of each joint (revolute or prismatic) is defined by:
00279 #  * the position of the joint (rad or m),
00280 #  * the velocity of the joint (rad/s or m/s) and 
00281 #  * the effort that is applied in the joint (Nm or N).
00282 #
00283 # Each joint is uniquely identified by its name
00284 # The header specifies the time at which the joint states were recorded. All the joint states
00285 # in one message have to be recorded at the same time.
00286 #
00287 # This message consists of a multiple arrays, one for each part of the joint state. 
00288 # The goal is to make each of the fields optional. When e.g. your joints have no
00289 # effort associated with them, you can leave the effort array empty. 
00290 #
00291 # All arrays in this message should have the same size, or be empty.
00292 # This is the only way to uniquely associate the joint name with the correct
00293 # states.
00294 
00295 
00296 Header header
00297 
00298 string[] name
00299 float64[] position
00300 float64[] velocity
00301 float64[] effort
00302 
00303 ================================================================================
00304 MSG: calibration_msgs/DenseLaserSnapshot
00305 # Provides all the state & sensor information for
00306 # a single sweep of laser attached to some mechanism.
00307 # Most likely, this will be used with PR2's tilting laser mechanism
00308 Header header
00309 
00310 # Store the laser intrinsics. This is very similar to the
00311 # intrinsics commonly stored in 
00312 float32 angle_min        # start angle of the scan [rad]
00313 float32 angle_max        # end angle of the scan [rad]
00314 float32 angle_increment  # angular distance between measurements [rad]
00315 float32 time_increment   # time between measurements [seconds]
00316 float32 range_min        # minimum range value [m]
00317 float32 range_max        # maximum range value [m]
00318 
00319 # Define the size of the binary data
00320 uint32 readings_per_scan    # (Width)
00321 uint32 num_scans            # (Height)
00322 
00323 # 2D Arrays storing laser data.
00324 # We can think of each type data as being a single channel image.
00325 # Each row of the image has data from a single scan, and scans are
00326 # concatenated to form the entire 'image'.
00327 float32[] ranges            # (Image data)
00328 float32[] intensities       # (Image data)
00329 
00330 # Store the start time of each scan
00331 time[] scan_start
00332 
00333 ================================================================================
00334 MSG: calibration_msgs/JointStateCalibrationPattern
00335 Header header
00336 geometry_msgs/Point[]  object_points
00337 sensor_msgs/JointState[] joint_points
00338 
00339 
00340 ================================================================================
00341 MSG: calibration_msgs/ChainMeasurement
00342 Header header
00343 string chain_id
00344 sensor_msgs/JointState chain_state
00345 
00346 """
00347   __slots__ = ['sample_id','target_id','chain_id','M_cam','M_laser','M_chain']
00348   _slot_types = ['string','string','string','calibration_msgs/CameraMeasurement[]','calibration_msgs/LaserMeasurement[]','calibration_msgs/ChainMeasurement[]']
00349 
00350   def __init__(self, *args, **kwds):
00351     """
00352     Constructor. Any message fields that are implicitly/explicitly
00353     set to None will be assigned a default value. The recommend
00354     use is keyword arguments as this is more robust to future message
00355     changes.  You cannot mix in-order arguments and keyword arguments.
00356 
00357     The available fields are:
00358        sample_id,target_id,chain_id,M_cam,M_laser,M_chain
00359 
00360     :param args: complete set of field values, in .msg order
00361     :param kwds: use keyword arguments corresponding to message field names
00362     to set specific fields.
00363     """
00364     if args or kwds:
00365       super(RobotMeasurement, self).__init__(*args, **kwds)
00366       #message fields cannot be None, assign default values for those that are
00367       if self.sample_id is None:
00368         self.sample_id = ''
00369       if self.target_id is None:
00370         self.target_id = ''
00371       if self.chain_id is None:
00372         self.chain_id = ''
00373       if self.M_cam is None:
00374         self.M_cam = []
00375       if self.M_laser is None:
00376         self.M_laser = []
00377       if self.M_chain is None:
00378         self.M_chain = []
00379     else:
00380       self.sample_id = ''
00381       self.target_id = ''
00382       self.chain_id = ''
00383       self.M_cam = []
00384       self.M_laser = []
00385       self.M_chain = []
00386 
00387   def _get_types(self):
00388     """
00389     internal API method
00390     """
00391     return self._slot_types
00392 
00393   def serialize(self, buff):
00394     """
00395     serialize message into buffer
00396     :param buff: buffer, ``StringIO``
00397     """
00398     try:
00399       _x = self.sample_id
00400       length = len(_x)
00401       if python3 or type(_x) == unicode:
00402         _x = _x.encode('utf-8')
00403         length = len(_x)
00404       buff.write(struct.pack('<I%ss'%length, length, _x))
00405       _x = self.target_id
00406       length = len(_x)
00407       if python3 or type(_x) == unicode:
00408         _x = _x.encode('utf-8')
00409         length = len(_x)
00410       buff.write(struct.pack('<I%ss'%length, length, _x))
00411       _x = self.chain_id
00412       length = len(_x)
00413       if python3 or type(_x) == unicode:
00414         _x = _x.encode('utf-8')
00415         length = len(_x)
00416       buff.write(struct.pack('<I%ss'%length, length, _x))
00417       length = len(self.M_cam)
00418       buff.write(_struct_I.pack(length))
00419       for val1 in self.M_cam:
00420         _v1 = val1.header
00421         buff.write(_struct_I.pack(_v1.seq))
00422         _v2 = _v1.stamp
00423         _x = _v2
00424         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00425         _x = _v1.frame_id
00426         length = len(_x)
00427         if python3 or type(_x) == unicode:
00428           _x = _x.encode('utf-8')
00429           length = len(_x)
00430         buff.write(struct.pack('<I%ss'%length, length, _x))
00431         _x = val1.camera_id
00432         length = len(_x)
00433         if python3 or type(_x) == unicode:
00434           _x = _x.encode('utf-8')
00435           length = len(_x)
00436         buff.write(struct.pack('<I%ss'%length, length, _x))
00437         length = len(val1.image_points)
00438         buff.write(_struct_I.pack(length))
00439         for val2 in val1.image_points:
00440           _x = val2
00441           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00442         _v3 = val1.cam_info
00443         _v4 = _v3.header
00444         buff.write(_struct_I.pack(_v4.seq))
00445         _v5 = _v4.stamp
00446         _x = _v5
00447         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00448         _x = _v4.frame_id
00449         length = len(_x)
00450         if python3 or type(_x) == unicode:
00451           _x = _x.encode('utf-8')
00452           length = len(_x)
00453         buff.write(struct.pack('<I%ss'%length, length, _x))
00454         _x = _v3
00455         buff.write(_struct_2I.pack(_x.height, _x.width))
00456         _x = _v3.distortion_model
00457         length = len(_x)
00458         if python3 or type(_x) == unicode:
00459           _x = _x.encode('utf-8')
00460           length = len(_x)
00461         buff.write(struct.pack('<I%ss'%length, length, _x))
00462         length = len(_v3.D)
00463         buff.write(_struct_I.pack(length))
00464         pattern = '<%sd'%length
00465         buff.write(struct.pack(pattern, *_v3.D))
00466         buff.write(_struct_9d.pack(*_v3.K))
00467         buff.write(_struct_9d.pack(*_v3.R))
00468         buff.write(_struct_12d.pack(*_v3.P))
00469         _x = _v3
00470         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
00471         _v6 = _v3.roi
00472         _x = _v6
00473         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
00474         buff.write(_struct_B.pack(val1.verbose))
00475         _v7 = val1.image
00476         _v8 = _v7.header
00477         buff.write(_struct_I.pack(_v8.seq))
00478         _v9 = _v8.stamp
00479         _x = _v9
00480         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00481         _x = _v8.frame_id
00482         length = len(_x)
00483         if python3 or type(_x) == unicode:
00484           _x = _x.encode('utf-8')
00485           length = len(_x)
00486         buff.write(struct.pack('<I%ss'%length, length, _x))
00487         _x = _v7
00488         buff.write(_struct_2I.pack(_x.height, _x.width))
00489         _x = _v7.encoding
00490         length = len(_x)
00491         if python3 or type(_x) == unicode:
00492           _x = _x.encode('utf-8')
00493           length = len(_x)
00494         buff.write(struct.pack('<I%ss'%length, length, _x))
00495         _x = _v7
00496         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00497         _x = _v7.data
00498         length = len(_x)
00499         # - if encoded as a list instead, serialize as bytes instead of string
00500         if type(_x) in [list, tuple]:
00501           buff.write(struct.pack('<I%sB'%length, length, *_x))
00502         else:
00503           buff.write(struct.pack('<I%ss'%length, length, _x))
00504         _v10 = val1.image_rect
00505         _v11 = _v10.header
00506         buff.write(_struct_I.pack(_v11.seq))
00507         _v12 = _v11.stamp
00508         _x = _v12
00509         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00510         _x = _v11.frame_id
00511         length = len(_x)
00512         if python3 or type(_x) == unicode:
00513           _x = _x.encode('utf-8')
00514           length = len(_x)
00515         buff.write(struct.pack('<I%ss'%length, length, _x))
00516         _x = _v10
00517         buff.write(_struct_2I.pack(_x.height, _x.width))
00518         _x = _v10.encoding
00519         length = len(_x)
00520         if python3 or type(_x) == unicode:
00521           _x = _x.encode('utf-8')
00522           length = len(_x)
00523         buff.write(struct.pack('<I%ss'%length, length, _x))
00524         _x = _v10
00525         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00526         _x = _v10.data
00527         length = len(_x)
00528         # - if encoded as a list instead, serialize as bytes instead of string
00529         if type(_x) in [list, tuple]:
00530           buff.write(struct.pack('<I%sB'%length, length, *_x))
00531         else:
00532           buff.write(struct.pack('<I%ss'%length, length, _x))
00533         _v13 = val1.features
00534         _v14 = _v13.header
00535         buff.write(_struct_I.pack(_v14.seq))
00536         _v15 = _v14.stamp
00537         _x = _v15
00538         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00539         _x = _v14.frame_id
00540         length = len(_x)
00541         if python3 or type(_x) == unicode:
00542           _x = _x.encode('utf-8')
00543           length = len(_x)
00544         buff.write(struct.pack('<I%ss'%length, length, _x))
00545         length = len(_v13.object_points)
00546         buff.write(_struct_I.pack(length))
00547         for val3 in _v13.object_points:
00548           _x = val3
00549           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00550         length = len(_v13.image_points)
00551         buff.write(_struct_I.pack(length))
00552         for val3 in _v13.image_points:
00553           _x = val3
00554           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00555         buff.write(_struct_B.pack(_v13.success))
00556       length = len(self.M_laser)
00557       buff.write(_struct_I.pack(length))
00558       for val1 in self.M_laser:
00559         _v16 = val1.header
00560         buff.write(_struct_I.pack(_v16.seq))
00561         _v17 = _v16.stamp
00562         _x = _v17
00563         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00564         _x = _v16.frame_id
00565         length = len(_x)
00566         if python3 or type(_x) == unicode:
00567           _x = _x.encode('utf-8')
00568           length = len(_x)
00569         buff.write(struct.pack('<I%ss'%length, length, _x))
00570         _x = val1.laser_id
00571         length = len(_x)
00572         if python3 or type(_x) == unicode:
00573           _x = _x.encode('utf-8')
00574           length = len(_x)
00575         buff.write(struct.pack('<I%ss'%length, length, _x))
00576         length = len(val1.joint_points)
00577         buff.write(_struct_I.pack(length))
00578         for val2 in val1.joint_points:
00579           _v18 = val2.header
00580           buff.write(_struct_I.pack(_v18.seq))
00581           _v19 = _v18.stamp
00582           _x = _v19
00583           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00584           _x = _v18.frame_id
00585           length = len(_x)
00586           if python3 or type(_x) == unicode:
00587             _x = _x.encode('utf-8')
00588             length = len(_x)
00589           buff.write(struct.pack('<I%ss'%length, length, _x))
00590           length = len(val2.name)
00591           buff.write(_struct_I.pack(length))
00592           for val3 in val2.name:
00593             length = len(val3)
00594             if python3 or type(val3) == unicode:
00595               val3 = val3.encode('utf-8')
00596               length = len(val3)
00597             buff.write(struct.pack('<I%ss'%length, length, val3))
00598           length = len(val2.position)
00599           buff.write(_struct_I.pack(length))
00600           pattern = '<%sd'%length
00601           buff.write(struct.pack(pattern, *val2.position))
00602           length = len(val2.velocity)
00603           buff.write(_struct_I.pack(length))
00604           pattern = '<%sd'%length
00605           buff.write(struct.pack(pattern, *val2.velocity))
00606           length = len(val2.effort)
00607           buff.write(_struct_I.pack(length))
00608           pattern = '<%sd'%length
00609           buff.write(struct.pack(pattern, *val2.effort))
00610         buff.write(_struct_B.pack(val1.verbose))
00611         _v20 = val1.snapshot
00612         _v21 = _v20.header
00613         buff.write(_struct_I.pack(_v21.seq))
00614         _v22 = _v21.stamp
00615         _x = _v22
00616         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00617         _x = _v21.frame_id
00618         length = len(_x)
00619         if python3 or type(_x) == unicode:
00620           _x = _x.encode('utf-8')
00621           length = len(_x)
00622         buff.write(struct.pack('<I%ss'%length, length, _x))
00623         _x = _v20
00624         buff.write(_struct_6f2I.pack(_x.angle_min, _x.angle_max, _x.angle_increment, _x.time_increment, _x.range_min, _x.range_max, _x.readings_per_scan, _x.num_scans))
00625         length = len(_v20.ranges)
00626         buff.write(_struct_I.pack(length))
00627         pattern = '<%sf'%length
00628         buff.write(struct.pack(pattern, *_v20.ranges))
00629         length = len(_v20.intensities)
00630         buff.write(_struct_I.pack(length))
00631         pattern = '<%sf'%length
00632         buff.write(struct.pack(pattern, *_v20.intensities))
00633         length = len(_v20.scan_start)
00634         buff.write(_struct_I.pack(length))
00635         for val3 in _v20.scan_start:
00636           _x = val3
00637           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00638         _v23 = val1.laser_image
00639         _v24 = _v23.header
00640         buff.write(_struct_I.pack(_v24.seq))
00641         _v25 = _v24.stamp
00642         _x = _v25
00643         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00644         _x = _v24.frame_id
00645         length = len(_x)
00646         if python3 or type(_x) == unicode:
00647           _x = _x.encode('utf-8')
00648           length = len(_x)
00649         buff.write(struct.pack('<I%ss'%length, length, _x))
00650         _x = _v23
00651         buff.write(_struct_2I.pack(_x.height, _x.width))
00652         _x = _v23.encoding
00653         length = len(_x)
00654         if python3 or type(_x) == unicode:
00655           _x = _x.encode('utf-8')
00656           length = len(_x)
00657         buff.write(struct.pack('<I%ss'%length, length, _x))
00658         _x = _v23
00659         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
00660         _x = _v23.data
00661         length = len(_x)
00662         # - if encoded as a list instead, serialize as bytes instead of string
00663         if type(_x) in [list, tuple]:
00664           buff.write(struct.pack('<I%sB'%length, length, *_x))
00665         else:
00666           buff.write(struct.pack('<I%ss'%length, length, _x))
00667         _v26 = val1.image_features
00668         _v27 = _v26.header
00669         buff.write(_struct_I.pack(_v27.seq))
00670         _v28 = _v27.stamp
00671         _x = _v28
00672         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00673         _x = _v27.frame_id
00674         length = len(_x)
00675         if python3 or type(_x) == unicode:
00676           _x = _x.encode('utf-8')
00677           length = len(_x)
00678         buff.write(struct.pack('<I%ss'%length, length, _x))
00679         length = len(_v26.object_points)
00680         buff.write(_struct_I.pack(length))
00681         for val3 in _v26.object_points:
00682           _x = val3
00683           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00684         length = len(_v26.image_points)
00685         buff.write(_struct_I.pack(length))
00686         for val3 in _v26.image_points:
00687           _x = val3
00688           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00689         buff.write(_struct_B.pack(_v26.success))
00690         _v29 = val1.joint_features
00691         _v30 = _v29.header
00692         buff.write(_struct_I.pack(_v30.seq))
00693         _v31 = _v30.stamp
00694         _x = _v31
00695         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00696         _x = _v30.frame_id
00697         length = len(_x)
00698         if python3 or type(_x) == unicode:
00699           _x = _x.encode('utf-8')
00700           length = len(_x)
00701         buff.write(struct.pack('<I%ss'%length, length, _x))
00702         length = len(_v29.object_points)
00703         buff.write(_struct_I.pack(length))
00704         for val3 in _v29.object_points:
00705           _x = val3
00706           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00707         length = len(_v29.joint_points)
00708         buff.write(_struct_I.pack(length))
00709         for val3 in _v29.joint_points:
00710           _v32 = val3.header
00711           buff.write(_struct_I.pack(_v32.seq))
00712           _v33 = _v32.stamp
00713           _x = _v33
00714           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00715           _x = _v32.frame_id
00716           length = len(_x)
00717           if python3 or type(_x) == unicode:
00718             _x = _x.encode('utf-8')
00719             length = len(_x)
00720           buff.write(struct.pack('<I%ss'%length, length, _x))
00721           length = len(val3.name)
00722           buff.write(_struct_I.pack(length))
00723           for val4 in val3.name:
00724             length = len(val4)
00725             if python3 or type(val4) == unicode:
00726               val4 = val4.encode('utf-8')
00727               length = len(val4)
00728             buff.write(struct.pack('<I%ss'%length, length, val4))
00729           length = len(val3.position)
00730           buff.write(_struct_I.pack(length))
00731           pattern = '<%sd'%length
00732           buff.write(struct.pack(pattern, *val3.position))
00733           length = len(val3.velocity)
00734           buff.write(_struct_I.pack(length))
00735           pattern = '<%sd'%length
00736           buff.write(struct.pack(pattern, *val3.velocity))
00737           length = len(val3.effort)
00738           buff.write(_struct_I.pack(length))
00739           pattern = '<%sd'%length
00740           buff.write(struct.pack(pattern, *val3.effort))
00741       length = len(self.M_chain)
00742       buff.write(_struct_I.pack(length))
00743       for val1 in self.M_chain:
00744         _v34 = val1.header
00745         buff.write(_struct_I.pack(_v34.seq))
00746         _v35 = _v34.stamp
00747         _x = _v35
00748         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00749         _x = _v34.frame_id
00750         length = len(_x)
00751         if python3 or type(_x) == unicode:
00752           _x = _x.encode('utf-8')
00753           length = len(_x)
00754         buff.write(struct.pack('<I%ss'%length, length, _x))
00755         _x = val1.chain_id
00756         length = len(_x)
00757         if python3 or type(_x) == unicode:
00758           _x = _x.encode('utf-8')
00759           length = len(_x)
00760         buff.write(struct.pack('<I%ss'%length, length, _x))
00761         _v36 = val1.chain_state
00762         _v37 = _v36.header
00763         buff.write(_struct_I.pack(_v37.seq))
00764         _v38 = _v37.stamp
00765         _x = _v38
00766         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00767         _x = _v37.frame_id
00768         length = len(_x)
00769         if python3 or type(_x) == unicode:
00770           _x = _x.encode('utf-8')
00771           length = len(_x)
00772         buff.write(struct.pack('<I%ss'%length, length, _x))
00773         length = len(_v36.name)
00774         buff.write(_struct_I.pack(length))
00775         for val3 in _v36.name:
00776           length = len(val3)
00777           if python3 or type(val3) == unicode:
00778             val3 = val3.encode('utf-8')
00779             length = len(val3)
00780           buff.write(struct.pack('<I%ss'%length, length, val3))
00781         length = len(_v36.position)
00782         buff.write(_struct_I.pack(length))
00783         pattern = '<%sd'%length
00784         buff.write(struct.pack(pattern, *_v36.position))
00785         length = len(_v36.velocity)
00786         buff.write(_struct_I.pack(length))
00787         pattern = '<%sd'%length
00788         buff.write(struct.pack(pattern, *_v36.velocity))
00789         length = len(_v36.effort)
00790         buff.write(_struct_I.pack(length))
00791         pattern = '<%sd'%length
00792         buff.write(struct.pack(pattern, *_v36.effort))
00793     except struct.error as se: self._check_types(se)
00794     except TypeError as te: self._check_types(te)
00795 
00796   def deserialize(self, str):
00797     """
00798     unpack serialized message in str into this message instance
00799     :param str: byte array of serialized message, ``str``
00800     """
00801     try:
00802       if self.M_cam is None:
00803         self.M_cam = None
00804       if self.M_laser is None:
00805         self.M_laser = None
00806       if self.M_chain is None:
00807         self.M_chain = None
00808       end = 0
00809       start = end
00810       end += 4
00811       (length,) = _struct_I.unpack(str[start:end])
00812       start = end
00813       end += length
00814       if python3:
00815         self.sample_id = str[start:end].decode('utf-8')
00816       else:
00817         self.sample_id = str[start:end]
00818       start = end
00819       end += 4
00820       (length,) = _struct_I.unpack(str[start:end])
00821       start = end
00822       end += length
00823       if python3:
00824         self.target_id = str[start:end].decode('utf-8')
00825       else:
00826         self.target_id = str[start:end]
00827       start = end
00828       end += 4
00829       (length,) = _struct_I.unpack(str[start:end])
00830       start = end
00831       end += length
00832       if python3:
00833         self.chain_id = str[start:end].decode('utf-8')
00834       else:
00835         self.chain_id = str[start:end]
00836       start = end
00837       end += 4
00838       (length,) = _struct_I.unpack(str[start:end])
00839       self.M_cam = []
00840       for i in range(0, length):
00841         val1 = calibration_msgs.msg.CameraMeasurement()
00842         _v39 = val1.header
00843         start = end
00844         end += 4
00845         (_v39.seq,) = _struct_I.unpack(str[start:end])
00846         _v40 = _v39.stamp
00847         _x = _v40
00848         start = end
00849         end += 8
00850         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00851         start = end
00852         end += 4
00853         (length,) = _struct_I.unpack(str[start:end])
00854         start = end
00855         end += length
00856         if python3:
00857           _v39.frame_id = str[start:end].decode('utf-8')
00858         else:
00859           _v39.frame_id = str[start:end]
00860         start = end
00861         end += 4
00862         (length,) = _struct_I.unpack(str[start:end])
00863         start = end
00864         end += length
00865         if python3:
00866           val1.camera_id = str[start:end].decode('utf-8')
00867         else:
00868           val1.camera_id = str[start:end]
00869         start = end
00870         end += 4
00871         (length,) = _struct_I.unpack(str[start:end])
00872         val1.image_points = []
00873         for i in range(0, length):
00874           val2 = geometry_msgs.msg.Point()
00875           _x = val2
00876           start = end
00877           end += 24
00878           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00879           val1.image_points.append(val2)
00880         _v41 = val1.cam_info
00881         _v42 = _v41.header
00882         start = end
00883         end += 4
00884         (_v42.seq,) = _struct_I.unpack(str[start:end])
00885         _v43 = _v42.stamp
00886         _x = _v43
00887         start = end
00888         end += 8
00889         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00890         start = end
00891         end += 4
00892         (length,) = _struct_I.unpack(str[start:end])
00893         start = end
00894         end += length
00895         if python3:
00896           _v42.frame_id = str[start:end].decode('utf-8')
00897         else:
00898           _v42.frame_id = str[start:end]
00899         _x = _v41
00900         start = end
00901         end += 8
00902         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00903         start = end
00904         end += 4
00905         (length,) = _struct_I.unpack(str[start:end])
00906         start = end
00907         end += length
00908         if python3:
00909           _v41.distortion_model = str[start:end].decode('utf-8')
00910         else:
00911           _v41.distortion_model = str[start:end]
00912         start = end
00913         end += 4
00914         (length,) = _struct_I.unpack(str[start:end])
00915         pattern = '<%sd'%length
00916         start = end
00917         end += struct.calcsize(pattern)
00918         _v41.D = struct.unpack(pattern, str[start:end])
00919         start = end
00920         end += 72
00921         _v41.K = _struct_9d.unpack(str[start:end])
00922         start = end
00923         end += 72
00924         _v41.R = _struct_9d.unpack(str[start:end])
00925         start = end
00926         end += 96
00927         _v41.P = _struct_12d.unpack(str[start:end])
00928         _x = _v41
00929         start = end
00930         end += 8
00931         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
00932         _v44 = _v41.roi
00933         _x = _v44
00934         start = end
00935         end += 17
00936         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
00937         _v44.do_rectify = bool(_v44.do_rectify)
00938         start = end
00939         end += 1
00940         (val1.verbose,) = _struct_B.unpack(str[start:end])
00941         val1.verbose = bool(val1.verbose)
00942         _v45 = val1.image
00943         _v46 = _v45.header
00944         start = end
00945         end += 4
00946         (_v46.seq,) = _struct_I.unpack(str[start:end])
00947         _v47 = _v46.stamp
00948         _x = _v47
00949         start = end
00950         end += 8
00951         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00952         start = end
00953         end += 4
00954         (length,) = _struct_I.unpack(str[start:end])
00955         start = end
00956         end += length
00957         if python3:
00958           _v46.frame_id = str[start:end].decode('utf-8')
00959         else:
00960           _v46.frame_id = str[start:end]
00961         _x = _v45
00962         start = end
00963         end += 8
00964         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
00965         start = end
00966         end += 4
00967         (length,) = _struct_I.unpack(str[start:end])
00968         start = end
00969         end += length
00970         if python3:
00971           _v45.encoding = str[start:end].decode('utf-8')
00972         else:
00973           _v45.encoding = str[start:end]
00974         _x = _v45
00975         start = end
00976         end += 5
00977         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
00978         start = end
00979         end += 4
00980         (length,) = _struct_I.unpack(str[start:end])
00981         start = end
00982         end += length
00983         if python3:
00984           _v45.data = str[start:end].decode('utf-8')
00985         else:
00986           _v45.data = str[start:end]
00987         _v48 = val1.image_rect
00988         _v49 = _v48.header
00989         start = end
00990         end += 4
00991         (_v49.seq,) = _struct_I.unpack(str[start:end])
00992         _v50 = _v49.stamp
00993         _x = _v50
00994         start = end
00995         end += 8
00996         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00997         start = end
00998         end += 4
00999         (length,) = _struct_I.unpack(str[start:end])
01000         start = end
01001         end += length
01002         if python3:
01003           _v49.frame_id = str[start:end].decode('utf-8')
01004         else:
01005           _v49.frame_id = str[start:end]
01006         _x = _v48
01007         start = end
01008         end += 8
01009         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01010         start = end
01011         end += 4
01012         (length,) = _struct_I.unpack(str[start:end])
01013         start = end
01014         end += length
01015         if python3:
01016           _v48.encoding = str[start:end].decode('utf-8')
01017         else:
01018           _v48.encoding = str[start:end]
01019         _x = _v48
01020         start = end
01021         end += 5
01022         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
01023         start = end
01024         end += 4
01025         (length,) = _struct_I.unpack(str[start:end])
01026         start = end
01027         end += length
01028         if python3:
01029           _v48.data = str[start:end].decode('utf-8')
01030         else:
01031           _v48.data = str[start:end]
01032         _v51 = val1.features
01033         _v52 = _v51.header
01034         start = end
01035         end += 4
01036         (_v52.seq,) = _struct_I.unpack(str[start:end])
01037         _v53 = _v52.stamp
01038         _x = _v53
01039         start = end
01040         end += 8
01041         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01042         start = end
01043         end += 4
01044         (length,) = _struct_I.unpack(str[start:end])
01045         start = end
01046         end += length
01047         if python3:
01048           _v52.frame_id = str[start:end].decode('utf-8')
01049         else:
01050           _v52.frame_id = str[start:end]
01051         start = end
01052         end += 4
01053         (length,) = _struct_I.unpack(str[start:end])
01054         _v51.object_points = []
01055         for i in range(0, length):
01056           val3 = geometry_msgs.msg.Point()
01057           _x = val3
01058           start = end
01059           end += 24
01060           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01061           _v51.object_points.append(val3)
01062         start = end
01063         end += 4
01064         (length,) = _struct_I.unpack(str[start:end])
01065         _v51.image_points = []
01066         for i in range(0, length):
01067           val3 = geometry_msgs.msg.Point()
01068           _x = val3
01069           start = end
01070           end += 24
01071           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01072           _v51.image_points.append(val3)
01073         start = end
01074         end += 1
01075         (_v51.success,) = _struct_B.unpack(str[start:end])
01076         self.M_cam.append(val1)
01077       start = end
01078       end += 4
01079       (length,) = _struct_I.unpack(str[start:end])
01080       self.M_laser = []
01081       for i in range(0, length):
01082         val1 = calibration_msgs.msg.LaserMeasurement()
01083         _v54 = val1.header
01084         start = end
01085         end += 4
01086         (_v54.seq,) = _struct_I.unpack(str[start:end])
01087         _v55 = _v54.stamp
01088         _x = _v55
01089         start = end
01090         end += 8
01091         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01092         start = end
01093         end += 4
01094         (length,) = _struct_I.unpack(str[start:end])
01095         start = end
01096         end += length
01097         if python3:
01098           _v54.frame_id = str[start:end].decode('utf-8')
01099         else:
01100           _v54.frame_id = str[start:end]
01101         start = end
01102         end += 4
01103         (length,) = _struct_I.unpack(str[start:end])
01104         start = end
01105         end += length
01106         if python3:
01107           val1.laser_id = str[start:end].decode('utf-8')
01108         else:
01109           val1.laser_id = str[start:end]
01110         start = end
01111         end += 4
01112         (length,) = _struct_I.unpack(str[start:end])
01113         val1.joint_points = []
01114         for i in range(0, length):
01115           val2 = sensor_msgs.msg.JointState()
01116           _v56 = val2.header
01117           start = end
01118           end += 4
01119           (_v56.seq,) = _struct_I.unpack(str[start:end])
01120           _v57 = _v56.stamp
01121           _x = _v57
01122           start = end
01123           end += 8
01124           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01125           start = end
01126           end += 4
01127           (length,) = _struct_I.unpack(str[start:end])
01128           start = end
01129           end += length
01130           if python3:
01131             _v56.frame_id = str[start:end].decode('utf-8')
01132           else:
01133             _v56.frame_id = str[start:end]
01134           start = end
01135           end += 4
01136           (length,) = _struct_I.unpack(str[start:end])
01137           val2.name = []
01138           for i in range(0, length):
01139             start = end
01140             end += 4
01141             (length,) = _struct_I.unpack(str[start:end])
01142             start = end
01143             end += length
01144             if python3:
01145               val3 = str[start:end].decode('utf-8')
01146             else:
01147               val3 = str[start:end]
01148             val2.name.append(val3)
01149           start = end
01150           end += 4
01151           (length,) = _struct_I.unpack(str[start:end])
01152           pattern = '<%sd'%length
01153           start = end
01154           end += struct.calcsize(pattern)
01155           val2.position = struct.unpack(pattern, str[start:end])
01156           start = end
01157           end += 4
01158           (length,) = _struct_I.unpack(str[start:end])
01159           pattern = '<%sd'%length
01160           start = end
01161           end += struct.calcsize(pattern)
01162           val2.velocity = struct.unpack(pattern, str[start:end])
01163           start = end
01164           end += 4
01165           (length,) = _struct_I.unpack(str[start:end])
01166           pattern = '<%sd'%length
01167           start = end
01168           end += struct.calcsize(pattern)
01169           val2.effort = struct.unpack(pattern, str[start:end])
01170           val1.joint_points.append(val2)
01171         start = end
01172         end += 1
01173         (val1.verbose,) = _struct_B.unpack(str[start:end])
01174         val1.verbose = bool(val1.verbose)
01175         _v58 = val1.snapshot
01176         _v59 = _v58.header
01177         start = end
01178         end += 4
01179         (_v59.seq,) = _struct_I.unpack(str[start:end])
01180         _v60 = _v59.stamp
01181         _x = _v60
01182         start = end
01183         end += 8
01184         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01185         start = end
01186         end += 4
01187         (length,) = _struct_I.unpack(str[start:end])
01188         start = end
01189         end += length
01190         if python3:
01191           _v59.frame_id = str[start:end].decode('utf-8')
01192         else:
01193           _v59.frame_id = str[start:end]
01194         _x = _v58
01195         start = end
01196         end += 32
01197         (_x.angle_min, _x.angle_max, _x.angle_increment, _x.time_increment, _x.range_min, _x.range_max, _x.readings_per_scan, _x.num_scans,) = _struct_6f2I.unpack(str[start:end])
01198         start = end
01199         end += 4
01200         (length,) = _struct_I.unpack(str[start:end])
01201         pattern = '<%sf'%length
01202         start = end
01203         end += struct.calcsize(pattern)
01204         _v58.ranges = struct.unpack(pattern, str[start:end])
01205         start = end
01206         end += 4
01207         (length,) = _struct_I.unpack(str[start:end])
01208         pattern = '<%sf'%length
01209         start = end
01210         end += struct.calcsize(pattern)
01211         _v58.intensities = struct.unpack(pattern, str[start:end])
01212         start = end
01213         end += 4
01214         (length,) = _struct_I.unpack(str[start:end])
01215         _v58.scan_start = []
01216         for i in range(0, length):
01217           val3 = genpy.Time()
01218           _x = val3
01219           start = end
01220           end += 8
01221           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01222           _v58.scan_start.append(val3)
01223         _v61 = val1.laser_image
01224         _v62 = _v61.header
01225         start = end
01226         end += 4
01227         (_v62.seq,) = _struct_I.unpack(str[start:end])
01228         _v63 = _v62.stamp
01229         _x = _v63
01230         start = end
01231         end += 8
01232         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01233         start = end
01234         end += 4
01235         (length,) = _struct_I.unpack(str[start:end])
01236         start = end
01237         end += length
01238         if python3:
01239           _v62.frame_id = str[start:end].decode('utf-8')
01240         else:
01241           _v62.frame_id = str[start:end]
01242         _x = _v61
01243         start = end
01244         end += 8
01245         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
01246         start = end
01247         end += 4
01248         (length,) = _struct_I.unpack(str[start:end])
01249         start = end
01250         end += length
01251         if python3:
01252           _v61.encoding = str[start:end].decode('utf-8')
01253         else:
01254           _v61.encoding = str[start:end]
01255         _x = _v61
01256         start = end
01257         end += 5
01258         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
01259         start = end
01260         end += 4
01261         (length,) = _struct_I.unpack(str[start:end])
01262         start = end
01263         end += length
01264         if python3:
01265           _v61.data = str[start:end].decode('utf-8')
01266         else:
01267           _v61.data = str[start:end]
01268         _v64 = val1.image_features
01269         _v65 = _v64.header
01270         start = end
01271         end += 4
01272         (_v65.seq,) = _struct_I.unpack(str[start:end])
01273         _v66 = _v65.stamp
01274         _x = _v66
01275         start = end
01276         end += 8
01277         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01278         start = end
01279         end += 4
01280         (length,) = _struct_I.unpack(str[start:end])
01281         start = end
01282         end += length
01283         if python3:
01284           _v65.frame_id = str[start:end].decode('utf-8')
01285         else:
01286           _v65.frame_id = str[start:end]
01287         start = end
01288         end += 4
01289         (length,) = _struct_I.unpack(str[start:end])
01290         _v64.object_points = []
01291         for i in range(0, length):
01292           val3 = geometry_msgs.msg.Point()
01293           _x = val3
01294           start = end
01295           end += 24
01296           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01297           _v64.object_points.append(val3)
01298         start = end
01299         end += 4
01300         (length,) = _struct_I.unpack(str[start:end])
01301         _v64.image_points = []
01302         for i in range(0, length):
01303           val3 = geometry_msgs.msg.Point()
01304           _x = val3
01305           start = end
01306           end += 24
01307           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01308           _v64.image_points.append(val3)
01309         start = end
01310         end += 1
01311         (_v64.success,) = _struct_B.unpack(str[start:end])
01312         _v67 = val1.joint_features
01313         _v68 = _v67.header
01314         start = end
01315         end += 4
01316         (_v68.seq,) = _struct_I.unpack(str[start:end])
01317         _v69 = _v68.stamp
01318         _x = _v69
01319         start = end
01320         end += 8
01321         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01322         start = end
01323         end += 4
01324         (length,) = _struct_I.unpack(str[start:end])
01325         start = end
01326         end += length
01327         if python3:
01328           _v68.frame_id = str[start:end].decode('utf-8')
01329         else:
01330           _v68.frame_id = str[start:end]
01331         start = end
01332         end += 4
01333         (length,) = _struct_I.unpack(str[start:end])
01334         _v67.object_points = []
01335         for i in range(0, length):
01336           val3 = geometry_msgs.msg.Point()
01337           _x = val3
01338           start = end
01339           end += 24
01340           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01341           _v67.object_points.append(val3)
01342         start = end
01343         end += 4
01344         (length,) = _struct_I.unpack(str[start:end])
01345         _v67.joint_points = []
01346         for i in range(0, length):
01347           val3 = sensor_msgs.msg.JointState()
01348           _v70 = val3.header
01349           start = end
01350           end += 4
01351           (_v70.seq,) = _struct_I.unpack(str[start:end])
01352           _v71 = _v70.stamp
01353           _x = _v71
01354           start = end
01355           end += 8
01356           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01357           start = end
01358           end += 4
01359           (length,) = _struct_I.unpack(str[start:end])
01360           start = end
01361           end += length
01362           if python3:
01363             _v70.frame_id = str[start:end].decode('utf-8')
01364           else:
01365             _v70.frame_id = str[start:end]
01366           start = end
01367           end += 4
01368           (length,) = _struct_I.unpack(str[start:end])
01369           val3.name = []
01370           for i in range(0, length):
01371             start = end
01372             end += 4
01373             (length,) = _struct_I.unpack(str[start:end])
01374             start = end
01375             end += length
01376             if python3:
01377               val4 = str[start:end].decode('utf-8')
01378             else:
01379               val4 = str[start:end]
01380             val3.name.append(val4)
01381           start = end
01382           end += 4
01383           (length,) = _struct_I.unpack(str[start:end])
01384           pattern = '<%sd'%length
01385           start = end
01386           end += struct.calcsize(pattern)
01387           val3.position = struct.unpack(pattern, str[start:end])
01388           start = end
01389           end += 4
01390           (length,) = _struct_I.unpack(str[start:end])
01391           pattern = '<%sd'%length
01392           start = end
01393           end += struct.calcsize(pattern)
01394           val3.velocity = struct.unpack(pattern, str[start:end])
01395           start = end
01396           end += 4
01397           (length,) = _struct_I.unpack(str[start:end])
01398           pattern = '<%sd'%length
01399           start = end
01400           end += struct.calcsize(pattern)
01401           val3.effort = struct.unpack(pattern, str[start:end])
01402           _v67.joint_points.append(val3)
01403         self.M_laser.append(val1)
01404       start = end
01405       end += 4
01406       (length,) = _struct_I.unpack(str[start:end])
01407       self.M_chain = []
01408       for i in range(0, length):
01409         val1 = calibration_msgs.msg.ChainMeasurement()
01410         _v72 = val1.header
01411         start = end
01412         end += 4
01413         (_v72.seq,) = _struct_I.unpack(str[start:end])
01414         _v73 = _v72.stamp
01415         _x = _v73
01416         start = end
01417         end += 8
01418         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01419         start = end
01420         end += 4
01421         (length,) = _struct_I.unpack(str[start:end])
01422         start = end
01423         end += length
01424         if python3:
01425           _v72.frame_id = str[start:end].decode('utf-8')
01426         else:
01427           _v72.frame_id = str[start:end]
01428         start = end
01429         end += 4
01430         (length,) = _struct_I.unpack(str[start:end])
01431         start = end
01432         end += length
01433         if python3:
01434           val1.chain_id = str[start:end].decode('utf-8')
01435         else:
01436           val1.chain_id = str[start:end]
01437         _v74 = val1.chain_state
01438         _v75 = _v74.header
01439         start = end
01440         end += 4
01441         (_v75.seq,) = _struct_I.unpack(str[start:end])
01442         _v76 = _v75.stamp
01443         _x = _v76
01444         start = end
01445         end += 8
01446         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01447         start = end
01448         end += 4
01449         (length,) = _struct_I.unpack(str[start:end])
01450         start = end
01451         end += length
01452         if python3:
01453           _v75.frame_id = str[start:end].decode('utf-8')
01454         else:
01455           _v75.frame_id = str[start:end]
01456         start = end
01457         end += 4
01458         (length,) = _struct_I.unpack(str[start:end])
01459         _v74.name = []
01460         for i in range(0, length):
01461           start = end
01462           end += 4
01463           (length,) = _struct_I.unpack(str[start:end])
01464           start = end
01465           end += length
01466           if python3:
01467             val3 = str[start:end].decode('utf-8')
01468           else:
01469             val3 = str[start:end]
01470           _v74.name.append(val3)
01471         start = end
01472         end += 4
01473         (length,) = _struct_I.unpack(str[start:end])
01474         pattern = '<%sd'%length
01475         start = end
01476         end += struct.calcsize(pattern)
01477         _v74.position = struct.unpack(pattern, str[start:end])
01478         start = end
01479         end += 4
01480         (length,) = _struct_I.unpack(str[start:end])
01481         pattern = '<%sd'%length
01482         start = end
01483         end += struct.calcsize(pattern)
01484         _v74.velocity = struct.unpack(pattern, str[start:end])
01485         start = end
01486         end += 4
01487         (length,) = _struct_I.unpack(str[start:end])
01488         pattern = '<%sd'%length
01489         start = end
01490         end += struct.calcsize(pattern)
01491         _v74.effort = struct.unpack(pattern, str[start:end])
01492         self.M_chain.append(val1)
01493       return self
01494     except struct.error as e:
01495       raise genpy.DeserializationError(e) #most likely buffer underfill
01496 
01497 
01498   def serialize_numpy(self, buff, numpy):
01499     """
01500     serialize message with numpy array types into buffer
01501     :param buff: buffer, ``StringIO``
01502     :param numpy: numpy python module
01503     """
01504     try:
01505       _x = self.sample_id
01506       length = len(_x)
01507       if python3 or type(_x) == unicode:
01508         _x = _x.encode('utf-8')
01509         length = len(_x)
01510       buff.write(struct.pack('<I%ss'%length, length, _x))
01511       _x = self.target_id
01512       length = len(_x)
01513       if python3 or type(_x) == unicode:
01514         _x = _x.encode('utf-8')
01515         length = len(_x)
01516       buff.write(struct.pack('<I%ss'%length, length, _x))
01517       _x = self.chain_id
01518       length = len(_x)
01519       if python3 or type(_x) == unicode:
01520         _x = _x.encode('utf-8')
01521         length = len(_x)
01522       buff.write(struct.pack('<I%ss'%length, length, _x))
01523       length = len(self.M_cam)
01524       buff.write(_struct_I.pack(length))
01525       for val1 in self.M_cam:
01526         _v77 = val1.header
01527         buff.write(_struct_I.pack(_v77.seq))
01528         _v78 = _v77.stamp
01529         _x = _v78
01530         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01531         _x = _v77.frame_id
01532         length = len(_x)
01533         if python3 or type(_x) == unicode:
01534           _x = _x.encode('utf-8')
01535           length = len(_x)
01536         buff.write(struct.pack('<I%ss'%length, length, _x))
01537         _x = val1.camera_id
01538         length = len(_x)
01539         if python3 or type(_x) == unicode:
01540           _x = _x.encode('utf-8')
01541           length = len(_x)
01542         buff.write(struct.pack('<I%ss'%length, length, _x))
01543         length = len(val1.image_points)
01544         buff.write(_struct_I.pack(length))
01545         for val2 in val1.image_points:
01546           _x = val2
01547           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01548         _v79 = val1.cam_info
01549         _v80 = _v79.header
01550         buff.write(_struct_I.pack(_v80.seq))
01551         _v81 = _v80.stamp
01552         _x = _v81
01553         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01554         _x = _v80.frame_id
01555         length = len(_x)
01556         if python3 or type(_x) == unicode:
01557           _x = _x.encode('utf-8')
01558           length = len(_x)
01559         buff.write(struct.pack('<I%ss'%length, length, _x))
01560         _x = _v79
01561         buff.write(_struct_2I.pack(_x.height, _x.width))
01562         _x = _v79.distortion_model
01563         length = len(_x)
01564         if python3 or type(_x) == unicode:
01565           _x = _x.encode('utf-8')
01566           length = len(_x)
01567         buff.write(struct.pack('<I%ss'%length, length, _x))
01568         length = len(_v79.D)
01569         buff.write(_struct_I.pack(length))
01570         pattern = '<%sd'%length
01571         buff.write(_v79.D.tostring())
01572         buff.write(_v79.K.tostring())
01573         buff.write(_v79.R.tostring())
01574         buff.write(_v79.P.tostring())
01575         _x = _v79
01576         buff.write(_struct_2I.pack(_x.binning_x, _x.binning_y))
01577         _v82 = _v79.roi
01578         _x = _v82
01579         buff.write(_struct_4IB.pack(_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify))
01580         buff.write(_struct_B.pack(val1.verbose))
01581         _v83 = val1.image
01582         _v84 = _v83.header
01583         buff.write(_struct_I.pack(_v84.seq))
01584         _v85 = _v84.stamp
01585         _x = _v85
01586         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01587         _x = _v84.frame_id
01588         length = len(_x)
01589         if python3 or type(_x) == unicode:
01590           _x = _x.encode('utf-8')
01591           length = len(_x)
01592         buff.write(struct.pack('<I%ss'%length, length, _x))
01593         _x = _v83
01594         buff.write(_struct_2I.pack(_x.height, _x.width))
01595         _x = _v83.encoding
01596         length = len(_x)
01597         if python3 or type(_x) == unicode:
01598           _x = _x.encode('utf-8')
01599           length = len(_x)
01600         buff.write(struct.pack('<I%ss'%length, length, _x))
01601         _x = _v83
01602         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01603         _x = _v83.data
01604         length = len(_x)
01605         # - if encoded as a list instead, serialize as bytes instead of string
01606         if type(_x) in [list, tuple]:
01607           buff.write(struct.pack('<I%sB'%length, length, *_x))
01608         else:
01609           buff.write(struct.pack('<I%ss'%length, length, _x))
01610         _v86 = val1.image_rect
01611         _v87 = _v86.header
01612         buff.write(_struct_I.pack(_v87.seq))
01613         _v88 = _v87.stamp
01614         _x = _v88
01615         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01616         _x = _v87.frame_id
01617         length = len(_x)
01618         if python3 or type(_x) == unicode:
01619           _x = _x.encode('utf-8')
01620           length = len(_x)
01621         buff.write(struct.pack('<I%ss'%length, length, _x))
01622         _x = _v86
01623         buff.write(_struct_2I.pack(_x.height, _x.width))
01624         _x = _v86.encoding
01625         length = len(_x)
01626         if python3 or type(_x) == unicode:
01627           _x = _x.encode('utf-8')
01628           length = len(_x)
01629         buff.write(struct.pack('<I%ss'%length, length, _x))
01630         _x = _v86
01631         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01632         _x = _v86.data
01633         length = len(_x)
01634         # - if encoded as a list instead, serialize as bytes instead of string
01635         if type(_x) in [list, tuple]:
01636           buff.write(struct.pack('<I%sB'%length, length, *_x))
01637         else:
01638           buff.write(struct.pack('<I%ss'%length, length, _x))
01639         _v89 = val1.features
01640         _v90 = _v89.header
01641         buff.write(_struct_I.pack(_v90.seq))
01642         _v91 = _v90.stamp
01643         _x = _v91
01644         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01645         _x = _v90.frame_id
01646         length = len(_x)
01647         if python3 or type(_x) == unicode:
01648           _x = _x.encode('utf-8')
01649           length = len(_x)
01650         buff.write(struct.pack('<I%ss'%length, length, _x))
01651         length = len(_v89.object_points)
01652         buff.write(_struct_I.pack(length))
01653         for val3 in _v89.object_points:
01654           _x = val3
01655           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01656         length = len(_v89.image_points)
01657         buff.write(_struct_I.pack(length))
01658         for val3 in _v89.image_points:
01659           _x = val3
01660           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01661         buff.write(_struct_B.pack(_v89.success))
01662       length = len(self.M_laser)
01663       buff.write(_struct_I.pack(length))
01664       for val1 in self.M_laser:
01665         _v92 = val1.header
01666         buff.write(_struct_I.pack(_v92.seq))
01667         _v93 = _v92.stamp
01668         _x = _v93
01669         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01670         _x = _v92.frame_id
01671         length = len(_x)
01672         if python3 or type(_x) == unicode:
01673           _x = _x.encode('utf-8')
01674           length = len(_x)
01675         buff.write(struct.pack('<I%ss'%length, length, _x))
01676         _x = val1.laser_id
01677         length = len(_x)
01678         if python3 or type(_x) == unicode:
01679           _x = _x.encode('utf-8')
01680           length = len(_x)
01681         buff.write(struct.pack('<I%ss'%length, length, _x))
01682         length = len(val1.joint_points)
01683         buff.write(_struct_I.pack(length))
01684         for val2 in val1.joint_points:
01685           _v94 = val2.header
01686           buff.write(_struct_I.pack(_v94.seq))
01687           _v95 = _v94.stamp
01688           _x = _v95
01689           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01690           _x = _v94.frame_id
01691           length = len(_x)
01692           if python3 or type(_x) == unicode:
01693             _x = _x.encode('utf-8')
01694             length = len(_x)
01695           buff.write(struct.pack('<I%ss'%length, length, _x))
01696           length = len(val2.name)
01697           buff.write(_struct_I.pack(length))
01698           for val3 in val2.name:
01699             length = len(val3)
01700             if python3 or type(val3) == unicode:
01701               val3 = val3.encode('utf-8')
01702               length = len(val3)
01703             buff.write(struct.pack('<I%ss'%length, length, val3))
01704           length = len(val2.position)
01705           buff.write(_struct_I.pack(length))
01706           pattern = '<%sd'%length
01707           buff.write(val2.position.tostring())
01708           length = len(val2.velocity)
01709           buff.write(_struct_I.pack(length))
01710           pattern = '<%sd'%length
01711           buff.write(val2.velocity.tostring())
01712           length = len(val2.effort)
01713           buff.write(_struct_I.pack(length))
01714           pattern = '<%sd'%length
01715           buff.write(val2.effort.tostring())
01716         buff.write(_struct_B.pack(val1.verbose))
01717         _v96 = val1.snapshot
01718         _v97 = _v96.header
01719         buff.write(_struct_I.pack(_v97.seq))
01720         _v98 = _v97.stamp
01721         _x = _v98
01722         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01723         _x = _v97.frame_id
01724         length = len(_x)
01725         if python3 or type(_x) == unicode:
01726           _x = _x.encode('utf-8')
01727           length = len(_x)
01728         buff.write(struct.pack('<I%ss'%length, length, _x))
01729         _x = _v96
01730         buff.write(_struct_6f2I.pack(_x.angle_min, _x.angle_max, _x.angle_increment, _x.time_increment, _x.range_min, _x.range_max, _x.readings_per_scan, _x.num_scans))
01731         length = len(_v96.ranges)
01732         buff.write(_struct_I.pack(length))
01733         pattern = '<%sf'%length
01734         buff.write(_v96.ranges.tostring())
01735         length = len(_v96.intensities)
01736         buff.write(_struct_I.pack(length))
01737         pattern = '<%sf'%length
01738         buff.write(_v96.intensities.tostring())
01739         length = len(_v96.scan_start)
01740         buff.write(_struct_I.pack(length))
01741         for val3 in _v96.scan_start:
01742           _x = val3
01743           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01744         _v99 = val1.laser_image
01745         _v100 = _v99.header
01746         buff.write(_struct_I.pack(_v100.seq))
01747         _v101 = _v100.stamp
01748         _x = _v101
01749         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01750         _x = _v100.frame_id
01751         length = len(_x)
01752         if python3 or type(_x) == unicode:
01753           _x = _x.encode('utf-8')
01754           length = len(_x)
01755         buff.write(struct.pack('<I%ss'%length, length, _x))
01756         _x = _v99
01757         buff.write(_struct_2I.pack(_x.height, _x.width))
01758         _x = _v99.encoding
01759         length = len(_x)
01760         if python3 or type(_x) == unicode:
01761           _x = _x.encode('utf-8')
01762           length = len(_x)
01763         buff.write(struct.pack('<I%ss'%length, length, _x))
01764         _x = _v99
01765         buff.write(_struct_BI.pack(_x.is_bigendian, _x.step))
01766         _x = _v99.data
01767         length = len(_x)
01768         # - if encoded as a list instead, serialize as bytes instead of string
01769         if type(_x) in [list, tuple]:
01770           buff.write(struct.pack('<I%sB'%length, length, *_x))
01771         else:
01772           buff.write(struct.pack('<I%ss'%length, length, _x))
01773         _v102 = val1.image_features
01774         _v103 = _v102.header
01775         buff.write(_struct_I.pack(_v103.seq))
01776         _v104 = _v103.stamp
01777         _x = _v104
01778         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01779         _x = _v103.frame_id
01780         length = len(_x)
01781         if python3 or type(_x) == unicode:
01782           _x = _x.encode('utf-8')
01783           length = len(_x)
01784         buff.write(struct.pack('<I%ss'%length, length, _x))
01785         length = len(_v102.object_points)
01786         buff.write(_struct_I.pack(length))
01787         for val3 in _v102.object_points:
01788           _x = val3
01789           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01790         length = len(_v102.image_points)
01791         buff.write(_struct_I.pack(length))
01792         for val3 in _v102.image_points:
01793           _x = val3
01794           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01795         buff.write(_struct_B.pack(_v102.success))
01796         _v105 = val1.joint_features
01797         _v106 = _v105.header
01798         buff.write(_struct_I.pack(_v106.seq))
01799         _v107 = _v106.stamp
01800         _x = _v107
01801         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01802         _x = _v106.frame_id
01803         length = len(_x)
01804         if python3 or type(_x) == unicode:
01805           _x = _x.encode('utf-8')
01806           length = len(_x)
01807         buff.write(struct.pack('<I%ss'%length, length, _x))
01808         length = len(_v105.object_points)
01809         buff.write(_struct_I.pack(length))
01810         for val3 in _v105.object_points:
01811           _x = val3
01812           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01813         length = len(_v105.joint_points)
01814         buff.write(_struct_I.pack(length))
01815         for val3 in _v105.joint_points:
01816           _v108 = val3.header
01817           buff.write(_struct_I.pack(_v108.seq))
01818           _v109 = _v108.stamp
01819           _x = _v109
01820           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01821           _x = _v108.frame_id
01822           length = len(_x)
01823           if python3 or type(_x) == unicode:
01824             _x = _x.encode('utf-8')
01825             length = len(_x)
01826           buff.write(struct.pack('<I%ss'%length, length, _x))
01827           length = len(val3.name)
01828           buff.write(_struct_I.pack(length))
01829           for val4 in val3.name:
01830             length = len(val4)
01831             if python3 or type(val4) == unicode:
01832               val4 = val4.encode('utf-8')
01833               length = len(val4)
01834             buff.write(struct.pack('<I%ss'%length, length, val4))
01835           length = len(val3.position)
01836           buff.write(_struct_I.pack(length))
01837           pattern = '<%sd'%length
01838           buff.write(val3.position.tostring())
01839           length = len(val3.velocity)
01840           buff.write(_struct_I.pack(length))
01841           pattern = '<%sd'%length
01842           buff.write(val3.velocity.tostring())
01843           length = len(val3.effort)
01844           buff.write(_struct_I.pack(length))
01845           pattern = '<%sd'%length
01846           buff.write(val3.effort.tostring())
01847       length = len(self.M_chain)
01848       buff.write(_struct_I.pack(length))
01849       for val1 in self.M_chain:
01850         _v110 = val1.header
01851         buff.write(_struct_I.pack(_v110.seq))
01852         _v111 = _v110.stamp
01853         _x = _v111
01854         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01855         _x = _v110.frame_id
01856         length = len(_x)
01857         if python3 or type(_x) == unicode:
01858           _x = _x.encode('utf-8')
01859           length = len(_x)
01860         buff.write(struct.pack('<I%ss'%length, length, _x))
01861         _x = val1.chain_id
01862         length = len(_x)
01863         if python3 or type(_x) == unicode:
01864           _x = _x.encode('utf-8')
01865           length = len(_x)
01866         buff.write(struct.pack('<I%ss'%length, length, _x))
01867         _v112 = val1.chain_state
01868         _v113 = _v112.header
01869         buff.write(_struct_I.pack(_v113.seq))
01870         _v114 = _v113.stamp
01871         _x = _v114
01872         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01873         _x = _v113.frame_id
01874         length = len(_x)
01875         if python3 or type(_x) == unicode:
01876           _x = _x.encode('utf-8')
01877           length = len(_x)
01878         buff.write(struct.pack('<I%ss'%length, length, _x))
01879         length = len(_v112.name)
01880         buff.write(_struct_I.pack(length))
01881         for val3 in _v112.name:
01882           length = len(val3)
01883           if python3 or type(val3) == unicode:
01884             val3 = val3.encode('utf-8')
01885             length = len(val3)
01886           buff.write(struct.pack('<I%ss'%length, length, val3))
01887         length = len(_v112.position)
01888         buff.write(_struct_I.pack(length))
01889         pattern = '<%sd'%length
01890         buff.write(_v112.position.tostring())
01891         length = len(_v112.velocity)
01892         buff.write(_struct_I.pack(length))
01893         pattern = '<%sd'%length
01894         buff.write(_v112.velocity.tostring())
01895         length = len(_v112.effort)
01896         buff.write(_struct_I.pack(length))
01897         pattern = '<%sd'%length
01898         buff.write(_v112.effort.tostring())
01899     except struct.error as se: self._check_types(se)
01900     except TypeError as te: self._check_types(te)
01901 
01902   def deserialize_numpy(self, str, numpy):
01903     """
01904     unpack serialized message in str into this message instance using numpy for array types
01905     :param str: byte array of serialized message, ``str``
01906     :param numpy: numpy python module
01907     """
01908     try:
01909       if self.M_cam is None:
01910         self.M_cam = None
01911       if self.M_laser is None:
01912         self.M_laser = None
01913       if self.M_chain is None:
01914         self.M_chain = None
01915       end = 0
01916       start = end
01917       end += 4
01918       (length,) = _struct_I.unpack(str[start:end])
01919       start = end
01920       end += length
01921       if python3:
01922         self.sample_id = str[start:end].decode('utf-8')
01923       else:
01924         self.sample_id = str[start:end]
01925       start = end
01926       end += 4
01927       (length,) = _struct_I.unpack(str[start:end])
01928       start = end
01929       end += length
01930       if python3:
01931         self.target_id = str[start:end].decode('utf-8')
01932       else:
01933         self.target_id = str[start:end]
01934       start = end
01935       end += 4
01936       (length,) = _struct_I.unpack(str[start:end])
01937       start = end
01938       end += length
01939       if python3:
01940         self.chain_id = str[start:end].decode('utf-8')
01941       else:
01942         self.chain_id = str[start:end]
01943       start = end
01944       end += 4
01945       (length,) = _struct_I.unpack(str[start:end])
01946       self.M_cam = []
01947       for i in range(0, length):
01948         val1 = calibration_msgs.msg.CameraMeasurement()
01949         _v115 = val1.header
01950         start = end
01951         end += 4
01952         (_v115.seq,) = _struct_I.unpack(str[start:end])
01953         _v116 = _v115.stamp
01954         _x = _v116
01955         start = end
01956         end += 8
01957         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01958         start = end
01959         end += 4
01960         (length,) = _struct_I.unpack(str[start:end])
01961         start = end
01962         end += length
01963         if python3:
01964           _v115.frame_id = str[start:end].decode('utf-8')
01965         else:
01966           _v115.frame_id = str[start:end]
01967         start = end
01968         end += 4
01969         (length,) = _struct_I.unpack(str[start:end])
01970         start = end
01971         end += length
01972         if python3:
01973           val1.camera_id = str[start:end].decode('utf-8')
01974         else:
01975           val1.camera_id = str[start:end]
01976         start = end
01977         end += 4
01978         (length,) = _struct_I.unpack(str[start:end])
01979         val1.image_points = []
01980         for i in range(0, length):
01981           val2 = geometry_msgs.msg.Point()
01982           _x = val2
01983           start = end
01984           end += 24
01985           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01986           val1.image_points.append(val2)
01987         _v117 = val1.cam_info
01988         _v118 = _v117.header
01989         start = end
01990         end += 4
01991         (_v118.seq,) = _struct_I.unpack(str[start:end])
01992         _v119 = _v118.stamp
01993         _x = _v119
01994         start = end
01995         end += 8
01996         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01997         start = end
01998         end += 4
01999         (length,) = _struct_I.unpack(str[start:end])
02000         start = end
02001         end += length
02002         if python3:
02003           _v118.frame_id = str[start:end].decode('utf-8')
02004         else:
02005           _v118.frame_id = str[start:end]
02006         _x = _v117
02007         start = end
02008         end += 8
02009         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02010         start = end
02011         end += 4
02012         (length,) = _struct_I.unpack(str[start:end])
02013         start = end
02014         end += length
02015         if python3:
02016           _v117.distortion_model = str[start:end].decode('utf-8')
02017         else:
02018           _v117.distortion_model = str[start:end]
02019         start = end
02020         end += 4
02021         (length,) = _struct_I.unpack(str[start:end])
02022         pattern = '<%sd'%length
02023         start = end
02024         end += struct.calcsize(pattern)
02025         _v117.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02026         start = end
02027         end += 72
02028         _v117.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
02029         start = end
02030         end += 72
02031         _v117.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
02032         start = end
02033         end += 96
02034         _v117.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12)
02035         _x = _v117
02036         start = end
02037         end += 8
02038         (_x.binning_x, _x.binning_y,) = _struct_2I.unpack(str[start:end])
02039         _v120 = _v117.roi
02040         _x = _v120
02041         start = end
02042         end += 17
02043         (_x.x_offset, _x.y_offset, _x.height, _x.width, _x.do_rectify,) = _struct_4IB.unpack(str[start:end])
02044         _v120.do_rectify = bool(_v120.do_rectify)
02045         start = end
02046         end += 1
02047         (val1.verbose,) = _struct_B.unpack(str[start:end])
02048         val1.verbose = bool(val1.verbose)
02049         _v121 = val1.image
02050         _v122 = _v121.header
02051         start = end
02052         end += 4
02053         (_v122.seq,) = _struct_I.unpack(str[start:end])
02054         _v123 = _v122.stamp
02055         _x = _v123
02056         start = end
02057         end += 8
02058         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02059         start = end
02060         end += 4
02061         (length,) = _struct_I.unpack(str[start:end])
02062         start = end
02063         end += length
02064         if python3:
02065           _v122.frame_id = str[start:end].decode('utf-8')
02066         else:
02067           _v122.frame_id = str[start:end]
02068         _x = _v121
02069         start = end
02070         end += 8
02071         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02072         start = end
02073         end += 4
02074         (length,) = _struct_I.unpack(str[start:end])
02075         start = end
02076         end += length
02077         if python3:
02078           _v121.encoding = str[start:end].decode('utf-8')
02079         else:
02080           _v121.encoding = str[start:end]
02081         _x = _v121
02082         start = end
02083         end += 5
02084         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02085         start = end
02086         end += 4
02087         (length,) = _struct_I.unpack(str[start:end])
02088         start = end
02089         end += length
02090         if python3:
02091           _v121.data = str[start:end].decode('utf-8')
02092         else:
02093           _v121.data = str[start:end]
02094         _v124 = val1.image_rect
02095         _v125 = _v124.header
02096         start = end
02097         end += 4
02098         (_v125.seq,) = _struct_I.unpack(str[start:end])
02099         _v126 = _v125.stamp
02100         _x = _v126
02101         start = end
02102         end += 8
02103         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02104         start = end
02105         end += 4
02106         (length,) = _struct_I.unpack(str[start:end])
02107         start = end
02108         end += length
02109         if python3:
02110           _v125.frame_id = str[start:end].decode('utf-8')
02111         else:
02112           _v125.frame_id = str[start:end]
02113         _x = _v124
02114         start = end
02115         end += 8
02116         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02117         start = end
02118         end += 4
02119         (length,) = _struct_I.unpack(str[start:end])
02120         start = end
02121         end += length
02122         if python3:
02123           _v124.encoding = str[start:end].decode('utf-8')
02124         else:
02125           _v124.encoding = str[start:end]
02126         _x = _v124
02127         start = end
02128         end += 5
02129         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02130         start = end
02131         end += 4
02132         (length,) = _struct_I.unpack(str[start:end])
02133         start = end
02134         end += length
02135         if python3:
02136           _v124.data = str[start:end].decode('utf-8')
02137         else:
02138           _v124.data = str[start:end]
02139         _v127 = val1.features
02140         _v128 = _v127.header
02141         start = end
02142         end += 4
02143         (_v128.seq,) = _struct_I.unpack(str[start:end])
02144         _v129 = _v128.stamp
02145         _x = _v129
02146         start = end
02147         end += 8
02148         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02149         start = end
02150         end += 4
02151         (length,) = _struct_I.unpack(str[start:end])
02152         start = end
02153         end += length
02154         if python3:
02155           _v128.frame_id = str[start:end].decode('utf-8')
02156         else:
02157           _v128.frame_id = str[start:end]
02158         start = end
02159         end += 4
02160         (length,) = _struct_I.unpack(str[start:end])
02161         _v127.object_points = []
02162         for i in range(0, length):
02163           val3 = geometry_msgs.msg.Point()
02164           _x = val3
02165           start = end
02166           end += 24
02167           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02168           _v127.object_points.append(val3)
02169         start = end
02170         end += 4
02171         (length,) = _struct_I.unpack(str[start:end])
02172         _v127.image_points = []
02173         for i in range(0, length):
02174           val3 = geometry_msgs.msg.Point()
02175           _x = val3
02176           start = end
02177           end += 24
02178           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02179           _v127.image_points.append(val3)
02180         start = end
02181         end += 1
02182         (_v127.success,) = _struct_B.unpack(str[start:end])
02183         self.M_cam.append(val1)
02184       start = end
02185       end += 4
02186       (length,) = _struct_I.unpack(str[start:end])
02187       self.M_laser = []
02188       for i in range(0, length):
02189         val1 = calibration_msgs.msg.LaserMeasurement()
02190         _v130 = val1.header
02191         start = end
02192         end += 4
02193         (_v130.seq,) = _struct_I.unpack(str[start:end])
02194         _v131 = _v130.stamp
02195         _x = _v131
02196         start = end
02197         end += 8
02198         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02199         start = end
02200         end += 4
02201         (length,) = _struct_I.unpack(str[start:end])
02202         start = end
02203         end += length
02204         if python3:
02205           _v130.frame_id = str[start:end].decode('utf-8')
02206         else:
02207           _v130.frame_id = str[start:end]
02208         start = end
02209         end += 4
02210         (length,) = _struct_I.unpack(str[start:end])
02211         start = end
02212         end += length
02213         if python3:
02214           val1.laser_id = str[start:end].decode('utf-8')
02215         else:
02216           val1.laser_id = str[start:end]
02217         start = end
02218         end += 4
02219         (length,) = _struct_I.unpack(str[start:end])
02220         val1.joint_points = []
02221         for i in range(0, length):
02222           val2 = sensor_msgs.msg.JointState()
02223           _v132 = val2.header
02224           start = end
02225           end += 4
02226           (_v132.seq,) = _struct_I.unpack(str[start:end])
02227           _v133 = _v132.stamp
02228           _x = _v133
02229           start = end
02230           end += 8
02231           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02232           start = end
02233           end += 4
02234           (length,) = _struct_I.unpack(str[start:end])
02235           start = end
02236           end += length
02237           if python3:
02238             _v132.frame_id = str[start:end].decode('utf-8')
02239           else:
02240             _v132.frame_id = str[start:end]
02241           start = end
02242           end += 4
02243           (length,) = _struct_I.unpack(str[start:end])
02244           val2.name = []
02245           for i in range(0, length):
02246             start = end
02247             end += 4
02248             (length,) = _struct_I.unpack(str[start:end])
02249             start = end
02250             end += length
02251             if python3:
02252               val3 = str[start:end].decode('utf-8')
02253             else:
02254               val3 = str[start:end]
02255             val2.name.append(val3)
02256           start = end
02257           end += 4
02258           (length,) = _struct_I.unpack(str[start:end])
02259           pattern = '<%sd'%length
02260           start = end
02261           end += struct.calcsize(pattern)
02262           val2.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02263           start = end
02264           end += 4
02265           (length,) = _struct_I.unpack(str[start:end])
02266           pattern = '<%sd'%length
02267           start = end
02268           end += struct.calcsize(pattern)
02269           val2.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02270           start = end
02271           end += 4
02272           (length,) = _struct_I.unpack(str[start:end])
02273           pattern = '<%sd'%length
02274           start = end
02275           end += struct.calcsize(pattern)
02276           val2.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02277           val1.joint_points.append(val2)
02278         start = end
02279         end += 1
02280         (val1.verbose,) = _struct_B.unpack(str[start:end])
02281         val1.verbose = bool(val1.verbose)
02282         _v134 = val1.snapshot
02283         _v135 = _v134.header
02284         start = end
02285         end += 4
02286         (_v135.seq,) = _struct_I.unpack(str[start:end])
02287         _v136 = _v135.stamp
02288         _x = _v136
02289         start = end
02290         end += 8
02291         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02292         start = end
02293         end += 4
02294         (length,) = _struct_I.unpack(str[start:end])
02295         start = end
02296         end += length
02297         if python3:
02298           _v135.frame_id = str[start:end].decode('utf-8')
02299         else:
02300           _v135.frame_id = str[start:end]
02301         _x = _v134
02302         start = end
02303         end += 32
02304         (_x.angle_min, _x.angle_max, _x.angle_increment, _x.time_increment, _x.range_min, _x.range_max, _x.readings_per_scan, _x.num_scans,) = _struct_6f2I.unpack(str[start:end])
02305         start = end
02306         end += 4
02307         (length,) = _struct_I.unpack(str[start:end])
02308         pattern = '<%sf'%length
02309         start = end
02310         end += struct.calcsize(pattern)
02311         _v134.ranges = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
02312         start = end
02313         end += 4
02314         (length,) = _struct_I.unpack(str[start:end])
02315         pattern = '<%sf'%length
02316         start = end
02317         end += struct.calcsize(pattern)
02318         _v134.intensities = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
02319         start = end
02320         end += 4
02321         (length,) = _struct_I.unpack(str[start:end])
02322         _v134.scan_start = []
02323         for i in range(0, length):
02324           val3 = genpy.Time()
02325           _x = val3
02326           start = end
02327           end += 8
02328           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02329           _v134.scan_start.append(val3)
02330         _v137 = val1.laser_image
02331         _v138 = _v137.header
02332         start = end
02333         end += 4
02334         (_v138.seq,) = _struct_I.unpack(str[start:end])
02335         _v139 = _v138.stamp
02336         _x = _v139
02337         start = end
02338         end += 8
02339         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02340         start = end
02341         end += 4
02342         (length,) = _struct_I.unpack(str[start:end])
02343         start = end
02344         end += length
02345         if python3:
02346           _v138.frame_id = str[start:end].decode('utf-8')
02347         else:
02348           _v138.frame_id = str[start:end]
02349         _x = _v137
02350         start = end
02351         end += 8
02352         (_x.height, _x.width,) = _struct_2I.unpack(str[start:end])
02353         start = end
02354         end += 4
02355         (length,) = _struct_I.unpack(str[start:end])
02356         start = end
02357         end += length
02358         if python3:
02359           _v137.encoding = str[start:end].decode('utf-8')
02360         else:
02361           _v137.encoding = str[start:end]
02362         _x = _v137
02363         start = end
02364         end += 5
02365         (_x.is_bigendian, _x.step,) = _struct_BI.unpack(str[start:end])
02366         start = end
02367         end += 4
02368         (length,) = _struct_I.unpack(str[start:end])
02369         start = end
02370         end += length
02371         if python3:
02372           _v137.data = str[start:end].decode('utf-8')
02373         else:
02374           _v137.data = str[start:end]
02375         _v140 = val1.image_features
02376         _v141 = _v140.header
02377         start = end
02378         end += 4
02379         (_v141.seq,) = _struct_I.unpack(str[start:end])
02380         _v142 = _v141.stamp
02381         _x = _v142
02382         start = end
02383         end += 8
02384         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02385         start = end
02386         end += 4
02387         (length,) = _struct_I.unpack(str[start:end])
02388         start = end
02389         end += length
02390         if python3:
02391           _v141.frame_id = str[start:end].decode('utf-8')
02392         else:
02393           _v141.frame_id = str[start:end]
02394         start = end
02395         end += 4
02396         (length,) = _struct_I.unpack(str[start:end])
02397         _v140.object_points = []
02398         for i in range(0, length):
02399           val3 = geometry_msgs.msg.Point()
02400           _x = val3
02401           start = end
02402           end += 24
02403           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02404           _v140.object_points.append(val3)
02405         start = end
02406         end += 4
02407         (length,) = _struct_I.unpack(str[start:end])
02408         _v140.image_points = []
02409         for i in range(0, length):
02410           val3 = geometry_msgs.msg.Point()
02411           _x = val3
02412           start = end
02413           end += 24
02414           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02415           _v140.image_points.append(val3)
02416         start = end
02417         end += 1
02418         (_v140.success,) = _struct_B.unpack(str[start:end])
02419         _v143 = val1.joint_features
02420         _v144 = _v143.header
02421         start = end
02422         end += 4
02423         (_v144.seq,) = _struct_I.unpack(str[start:end])
02424         _v145 = _v144.stamp
02425         _x = _v145
02426         start = end
02427         end += 8
02428         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02429         start = end
02430         end += 4
02431         (length,) = _struct_I.unpack(str[start:end])
02432         start = end
02433         end += length
02434         if python3:
02435           _v144.frame_id = str[start:end].decode('utf-8')
02436         else:
02437           _v144.frame_id = str[start:end]
02438         start = end
02439         end += 4
02440         (length,) = _struct_I.unpack(str[start:end])
02441         _v143.object_points = []
02442         for i in range(0, length):
02443           val3 = geometry_msgs.msg.Point()
02444           _x = val3
02445           start = end
02446           end += 24
02447           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02448           _v143.object_points.append(val3)
02449         start = end
02450         end += 4
02451         (length,) = _struct_I.unpack(str[start:end])
02452         _v143.joint_points = []
02453         for i in range(0, length):
02454           val3 = sensor_msgs.msg.JointState()
02455           _v146 = val3.header
02456           start = end
02457           end += 4
02458           (_v146.seq,) = _struct_I.unpack(str[start:end])
02459           _v147 = _v146.stamp
02460           _x = _v147
02461           start = end
02462           end += 8
02463           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02464           start = end
02465           end += 4
02466           (length,) = _struct_I.unpack(str[start:end])
02467           start = end
02468           end += length
02469           if python3:
02470             _v146.frame_id = str[start:end].decode('utf-8')
02471           else:
02472             _v146.frame_id = str[start:end]
02473           start = end
02474           end += 4
02475           (length,) = _struct_I.unpack(str[start:end])
02476           val3.name = []
02477           for i in range(0, length):
02478             start = end
02479             end += 4
02480             (length,) = _struct_I.unpack(str[start:end])
02481             start = end
02482             end += length
02483             if python3:
02484               val4 = str[start:end].decode('utf-8')
02485             else:
02486               val4 = str[start:end]
02487             val3.name.append(val4)
02488           start = end
02489           end += 4
02490           (length,) = _struct_I.unpack(str[start:end])
02491           pattern = '<%sd'%length
02492           start = end
02493           end += struct.calcsize(pattern)
02494           val3.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02495           start = end
02496           end += 4
02497           (length,) = _struct_I.unpack(str[start:end])
02498           pattern = '<%sd'%length
02499           start = end
02500           end += struct.calcsize(pattern)
02501           val3.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02502           start = end
02503           end += 4
02504           (length,) = _struct_I.unpack(str[start:end])
02505           pattern = '<%sd'%length
02506           start = end
02507           end += struct.calcsize(pattern)
02508           val3.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02509           _v143.joint_points.append(val3)
02510         self.M_laser.append(val1)
02511       start = end
02512       end += 4
02513       (length,) = _struct_I.unpack(str[start:end])
02514       self.M_chain = []
02515       for i in range(0, length):
02516         val1 = calibration_msgs.msg.ChainMeasurement()
02517         _v148 = val1.header
02518         start = end
02519         end += 4
02520         (_v148.seq,) = _struct_I.unpack(str[start:end])
02521         _v149 = _v148.stamp
02522         _x = _v149
02523         start = end
02524         end += 8
02525         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02526         start = end
02527         end += 4
02528         (length,) = _struct_I.unpack(str[start:end])
02529         start = end
02530         end += length
02531         if python3:
02532           _v148.frame_id = str[start:end].decode('utf-8')
02533         else:
02534           _v148.frame_id = str[start:end]
02535         start = end
02536         end += 4
02537         (length,) = _struct_I.unpack(str[start:end])
02538         start = end
02539         end += length
02540         if python3:
02541           val1.chain_id = str[start:end].decode('utf-8')
02542         else:
02543           val1.chain_id = str[start:end]
02544         _v150 = val1.chain_state
02545         _v151 = _v150.header
02546         start = end
02547         end += 4
02548         (_v151.seq,) = _struct_I.unpack(str[start:end])
02549         _v152 = _v151.stamp
02550         _x = _v152
02551         start = end
02552         end += 8
02553         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02554         start = end
02555         end += 4
02556         (length,) = _struct_I.unpack(str[start:end])
02557         start = end
02558         end += length
02559         if python3:
02560           _v151.frame_id = str[start:end].decode('utf-8')
02561         else:
02562           _v151.frame_id = str[start:end]
02563         start = end
02564         end += 4
02565         (length,) = _struct_I.unpack(str[start:end])
02566         _v150.name = []
02567         for i in range(0, length):
02568           start = end
02569           end += 4
02570           (length,) = _struct_I.unpack(str[start:end])
02571           start = end
02572           end += length
02573           if python3:
02574             val3 = str[start:end].decode('utf-8')
02575           else:
02576             val3 = str[start:end]
02577           _v150.name.append(val3)
02578         start = end
02579         end += 4
02580         (length,) = _struct_I.unpack(str[start:end])
02581         pattern = '<%sd'%length
02582         start = end
02583         end += struct.calcsize(pattern)
02584         _v150.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02585         start = end
02586         end += 4
02587         (length,) = _struct_I.unpack(str[start:end])
02588         pattern = '<%sd'%length
02589         start = end
02590         end += struct.calcsize(pattern)
02591         _v150.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02592         start = end
02593         end += 4
02594         (length,) = _struct_I.unpack(str[start:end])
02595         pattern = '<%sd'%length
02596         start = end
02597         end += struct.calcsize(pattern)
02598         _v150.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02599         self.M_chain.append(val1)
02600       return self
02601     except struct.error as e:
02602       raise genpy.DeserializationError(e) #most likely buffer underfill
02603 
02604 _struct_I = genpy.struct_I
02605 _struct_B = struct.Struct("<B")
02606 _struct_12d = struct.Struct("<12d")
02607 _struct_9d = struct.Struct("<9d")
02608 _struct_BI = struct.Struct("<BI")
02609 _struct_6f2I = struct.Struct("<6f2I")
02610 _struct_2I = struct.Struct("<2I")
02611 _struct_4IB = struct.Struct("<4IB")
02612 _struct_3d = struct.Struct("<3d")
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


calibration_msgs
Author(s): Vijay Pradeep
autogenerated on Thu Aug 15 2013 10:15:15