00001 """autogenerated by genpy from pr2_laser_snapshotter/TiltLaserSnapshotAction.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 actionlib_msgs.msg
00008 import geometry_msgs.msg
00009 import pr2_laser_snapshotter.msg
00010 import sensor_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013 
00014 class TiltLaserSnapshotAction(genpy.Message):
00015   _md5sum = "f83cd41811454f8a69824e814d67c9ce"
00016   _type = "pr2_laser_snapshotter/TiltLaserSnapshotAction"
00017   _has_header = False 
00018   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019 
00020 TiltLaserSnapshotActionGoal action_goal
00021 TiltLaserSnapshotActionResult action_result
00022 TiltLaserSnapshotActionFeedback action_feedback
00023 
00024 ================================================================================
00025 MSG: pr2_laser_snapshotter/TiltLaserSnapshotActionGoal
00026 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00027 
00028 Header header
00029 actionlib_msgs/GoalID goal_id
00030 TiltLaserSnapshotGoal goal
00031 
00032 ================================================================================
00033 MSG: std_msgs/Header
00034 # Standard metadata for higher-level stamped data types.
00035 # This is generally used to communicate timestamped data 
00036 # in a particular coordinate frame.
00037 # 
00038 # sequence ID: consecutively increasing ID 
00039 uint32 seq
00040 #Two-integer timestamp that is expressed as:
00041 # * stamp.secs: seconds (stamp_secs) since epoch
00042 # * stamp.nsecs: nanoseconds since stamp_secs
00043 # time-handling sugar is provided by the client library
00044 time stamp
00045 #Frame this data is associated with
00046 # 0: no frame
00047 # 1: global frame
00048 string frame_id
00049 
00050 ================================================================================
00051 MSG: actionlib_msgs/GoalID
00052 # The stamp should store the time at which this goal was requested.
00053 # It is used by an action server when it tries to preempt all
00054 # goals that were requested before a certain time
00055 time stamp
00056 
00057 # The id provides a way to associate feedback and
00058 # result message with specific goal requests. The id
00059 # specified must be unique.
00060 string id
00061 
00062 
00063 ================================================================================
00064 MSG: pr2_laser_snapshotter/TiltLaserSnapshotGoal
00065 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00066 float64 angle_begin
00067 float64 angle_end
00068 float64 duration
00069 
00070 ================================================================================
00071 MSG: pr2_laser_snapshotter/TiltLaserSnapshotActionResult
00072 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00073 
00074 Header header
00075 actionlib_msgs/GoalStatus status
00076 TiltLaserSnapshotResult result
00077 
00078 ================================================================================
00079 MSG: actionlib_msgs/GoalStatus
00080 GoalID goal_id
00081 uint8 status
00082 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00083 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00084 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00085                             #   and has since completed its execution (Terminal State)
00086 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00087 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00088                             #    to some failure (Terminal State)
00089 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00090                             #    because the goal was unattainable or invalid (Terminal State)
00091 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00092                             #    and has not yet completed execution
00093 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00094                             #    but the action server has not yet confirmed that the goal is canceled
00095 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00096                             #    and was successfully cancelled (Terminal State)
00097 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00098                             #    sent over the wire by an action server
00099 
00100 #Allow for the user to associate a string with GoalStatus for debugging
00101 string text
00102 
00103 
00104 ================================================================================
00105 MSG: pr2_laser_snapshotter/TiltLaserSnapshotResult
00106 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00107 sensor_msgs/PointCloud cloud
00108 
00109 ================================================================================
00110 MSG: sensor_msgs/PointCloud
00111 # This message holds a collection of 3d points, plus optional additional
00112 # information about each point.
00113 
00114 # Time of sensor data acquisition, coordinate frame ID.
00115 Header header
00116 
00117 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00118 # in the frame given in the header.
00119 geometry_msgs/Point32[] points
00120 
00121 # Each channel should have the same number of elements as points array,
00122 # and the data in each channel should correspond 1:1 with each point.
00123 # Channel names in common practice are listed in ChannelFloat32.msg.
00124 ChannelFloat32[] channels
00125 
00126 ================================================================================
00127 MSG: geometry_msgs/Point32
00128 # This contains the position of a point in free space(with 32 bits of precision).
00129 # It is recommeded to use Point wherever possible instead of Point32.  
00130 # 
00131 # This recommendation is to promote interoperability.  
00132 #
00133 # This message is designed to take up less space when sending
00134 # lots of points at once, as in the case of a PointCloud.  
00135 
00136 float32 x
00137 float32 y
00138 float32 z
00139 ================================================================================
00140 MSG: sensor_msgs/ChannelFloat32
00141 # This message is used by the PointCloud message to hold optional data
00142 # associated with each point in the cloud. The length of the values
00143 # array should be the same as the length of the points array in the
00144 # PointCloud, and each value should be associated with the corresponding
00145 # point.
00146 
00147 # Channel names in existing practice include:
00148 #   "u", "v" - row and column (respectively) in the left stereo image.
00149 #              This is opposite to usual conventions but remains for
00150 #              historical reasons. The newer PointCloud2 message has no
00151 #              such problem.
00152 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00153 #           (R,G,B) values packed into the least significant 24 bits,
00154 #           in order.
00155 #   "intensity" - laser or pixel intensity.
00156 #   "distance"
00157 
00158 # The channel name should give semantics of the channel (e.g.
00159 # "intensity" instead of "value").
00160 string name
00161 
00162 # The values array should be 1-1 with the elements of the associated
00163 # PointCloud.
00164 float32[] values
00165 
00166 ================================================================================
00167 MSG: pr2_laser_snapshotter/TiltLaserSnapshotActionFeedback
00168 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00169 
00170 Header header
00171 actionlib_msgs/GoalStatus status
00172 TiltLaserSnapshotFeedback feedback
00173 
00174 ================================================================================
00175 MSG: pr2_laser_snapshotter/TiltLaserSnapshotFeedback
00176 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00177 
00178 
00179 """
00180   __slots__ = ['action_goal','action_result','action_feedback']
00181   _slot_types = ['pr2_laser_snapshotter/TiltLaserSnapshotActionGoal','pr2_laser_snapshotter/TiltLaserSnapshotActionResult','pr2_laser_snapshotter/TiltLaserSnapshotActionFeedback']
00182 
00183   def __init__(self, *args, **kwds):
00184     """
00185     Constructor. Any message fields that are implicitly/explicitly
00186     set to None will be assigned a default value. The recommend
00187     use is keyword arguments as this is more robust to future message
00188     changes.  You cannot mix in-order arguments and keyword arguments.
00189 
00190     The available fields are:
00191        action_goal,action_result,action_feedback
00192 
00193     :param args: complete set of field values, in .msg order
00194     :param kwds: use keyword arguments corresponding to message field names
00195     to set specific fields.
00196     """
00197     if args or kwds:
00198       super(TiltLaserSnapshotAction, self).__init__(*args, **kwds)
00199       #message fields cannot be None, assign default values for those that are
00200       if self.action_goal is None:
00201         self.action_goal = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionGoal()
00202       if self.action_result is None:
00203         self.action_result = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionResult()
00204       if self.action_feedback is None:
00205         self.action_feedback = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionFeedback()
00206     else:
00207       self.action_goal = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionGoal()
00208       self.action_result = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionResult()
00209       self.action_feedback = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionFeedback()
00210 
00211   def _get_types(self):
00212     """
00213     internal API method
00214     """
00215     return self._slot_types
00216 
00217   def serialize(self, buff):
00218     """
00219     serialize message into buffer
00220     :param buff: buffer, ``StringIO``
00221     """
00222     try:
00223       _x = self
00224       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00225       _x = self.action_goal.header.frame_id
00226       length = len(_x)
00227       if python3 or type(_x) == unicode:
00228         _x = _x.encode('utf-8')
00229         length = len(_x)
00230       buff.write(struct.pack('<I%ss'%length, length, _x))
00231       _x = self
00232       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00233       _x = self.action_goal.goal_id.id
00234       length = len(_x)
00235       if python3 or type(_x) == unicode:
00236         _x = _x.encode('utf-8')
00237         length = len(_x)
00238       buff.write(struct.pack('<I%ss'%length, length, _x))
00239       _x = self
00240       buff.write(_struct_3d3I.pack(_x.action_goal.goal.angle_begin, _x.action_goal.goal.angle_end, _x.action_goal.goal.duration, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00241       _x = self.action_result.header.frame_id
00242       length = len(_x)
00243       if python3 or type(_x) == unicode:
00244         _x = _x.encode('utf-8')
00245         length = len(_x)
00246       buff.write(struct.pack('<I%ss'%length, length, _x))
00247       _x = self
00248       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00249       _x = self.action_result.status.goal_id.id
00250       length = len(_x)
00251       if python3 or type(_x) == unicode:
00252         _x = _x.encode('utf-8')
00253         length = len(_x)
00254       buff.write(struct.pack('<I%ss'%length, length, _x))
00255       buff.write(_struct_B.pack(self.action_result.status.status))
00256       _x = self.action_result.status.text
00257       length = len(_x)
00258       if python3 or type(_x) == unicode:
00259         _x = _x.encode('utf-8')
00260         length = len(_x)
00261       buff.write(struct.pack('<I%ss'%length, length, _x))
00262       _x = self
00263       buff.write(_struct_3I.pack(_x.action_result.result.cloud.header.seq, _x.action_result.result.cloud.header.stamp.secs, _x.action_result.result.cloud.header.stamp.nsecs))
00264       _x = self.action_result.result.cloud.header.frame_id
00265       length = len(_x)
00266       if python3 or type(_x) == unicode:
00267         _x = _x.encode('utf-8')
00268         length = len(_x)
00269       buff.write(struct.pack('<I%ss'%length, length, _x))
00270       length = len(self.action_result.result.cloud.points)
00271       buff.write(_struct_I.pack(length))
00272       for val1 in self.action_result.result.cloud.points:
00273         _x = val1
00274         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00275       length = len(self.action_result.result.cloud.channels)
00276       buff.write(_struct_I.pack(length))
00277       for val1 in self.action_result.result.cloud.channels:
00278         _x = val1.name
00279         length = len(_x)
00280         if python3 or type(_x) == unicode:
00281           _x = _x.encode('utf-8')
00282           length = len(_x)
00283         buff.write(struct.pack('<I%ss'%length, length, _x))
00284         length = len(val1.values)
00285         buff.write(_struct_I.pack(length))
00286         pattern = '<%sf'%length
00287         buff.write(struct.pack(pattern, *val1.values))
00288       _x = self
00289       buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00290       _x = self.action_feedback.header.frame_id
00291       length = len(_x)
00292       if python3 or type(_x) == unicode:
00293         _x = _x.encode('utf-8')
00294         length = len(_x)
00295       buff.write(struct.pack('<I%ss'%length, length, _x))
00296       _x = self
00297       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00298       _x = self.action_feedback.status.goal_id.id
00299       length = len(_x)
00300       if python3 or type(_x) == unicode:
00301         _x = _x.encode('utf-8')
00302         length = len(_x)
00303       buff.write(struct.pack('<I%ss'%length, length, _x))
00304       buff.write(_struct_B.pack(self.action_feedback.status.status))
00305       _x = self.action_feedback.status.text
00306       length = len(_x)
00307       if python3 or type(_x) == unicode:
00308         _x = _x.encode('utf-8')
00309         length = len(_x)
00310       buff.write(struct.pack('<I%ss'%length, length, _x))
00311     except struct.error as se: self._check_types(se)
00312     except TypeError as te: self._check_types(te)
00313 
00314   def deserialize(self, str):
00315     """
00316     unpack serialized message in str into this message instance
00317     :param str: byte array of serialized message, ``str``
00318     """
00319     try:
00320       if self.action_goal is None:
00321         self.action_goal = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionGoal()
00322       if self.action_result is None:
00323         self.action_result = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionResult()
00324       if self.action_feedback is None:
00325         self.action_feedback = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionFeedback()
00326       end = 0
00327       _x = self
00328       start = end
00329       end += 12
00330       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00331       start = end
00332       end += 4
00333       (length,) = _struct_I.unpack(str[start:end])
00334       start = end
00335       end += length
00336       if python3:
00337         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00338       else:
00339         self.action_goal.header.frame_id = str[start:end]
00340       _x = self
00341       start = end
00342       end += 8
00343       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00344       start = end
00345       end += 4
00346       (length,) = _struct_I.unpack(str[start:end])
00347       start = end
00348       end += length
00349       if python3:
00350         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00351       else:
00352         self.action_goal.goal_id.id = str[start:end]
00353       _x = self
00354       start = end
00355       end += 36
00356       (_x.action_goal.goal.angle_begin, _x.action_goal.goal.angle_end, _x.action_goal.goal.duration, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3d3I.unpack(str[start:end])
00357       start = end
00358       end += 4
00359       (length,) = _struct_I.unpack(str[start:end])
00360       start = end
00361       end += length
00362       if python3:
00363         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00364       else:
00365         self.action_result.header.frame_id = str[start:end]
00366       _x = self
00367       start = end
00368       end += 8
00369       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00370       start = end
00371       end += 4
00372       (length,) = _struct_I.unpack(str[start:end])
00373       start = end
00374       end += length
00375       if python3:
00376         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00377       else:
00378         self.action_result.status.goal_id.id = str[start:end]
00379       start = end
00380       end += 1
00381       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00382       start = end
00383       end += 4
00384       (length,) = _struct_I.unpack(str[start:end])
00385       start = end
00386       end += length
00387       if python3:
00388         self.action_result.status.text = str[start:end].decode('utf-8')
00389       else:
00390         self.action_result.status.text = str[start:end]
00391       _x = self
00392       start = end
00393       end += 12
00394       (_x.action_result.result.cloud.header.seq, _x.action_result.result.cloud.header.stamp.secs, _x.action_result.result.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00395       start = end
00396       end += 4
00397       (length,) = _struct_I.unpack(str[start:end])
00398       start = end
00399       end += length
00400       if python3:
00401         self.action_result.result.cloud.header.frame_id = str[start:end].decode('utf-8')
00402       else:
00403         self.action_result.result.cloud.header.frame_id = str[start:end]
00404       start = end
00405       end += 4
00406       (length,) = _struct_I.unpack(str[start:end])
00407       self.action_result.result.cloud.points = []
00408       for i in range(0, length):
00409         val1 = geometry_msgs.msg.Point32()
00410         _x = val1
00411         start = end
00412         end += 12
00413         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00414         self.action_result.result.cloud.points.append(val1)
00415       start = end
00416       end += 4
00417       (length,) = _struct_I.unpack(str[start:end])
00418       self.action_result.result.cloud.channels = []
00419       for i in range(0, length):
00420         val1 = sensor_msgs.msg.ChannelFloat32()
00421         start = end
00422         end += 4
00423         (length,) = _struct_I.unpack(str[start:end])
00424         start = end
00425         end += length
00426         if python3:
00427           val1.name = str[start:end].decode('utf-8')
00428         else:
00429           val1.name = str[start:end]
00430         start = end
00431         end += 4
00432         (length,) = _struct_I.unpack(str[start:end])
00433         pattern = '<%sf'%length
00434         start = end
00435         end += struct.calcsize(pattern)
00436         val1.values = struct.unpack(pattern, str[start:end])
00437         self.action_result.result.cloud.channels.append(val1)
00438       _x = self
00439       start = end
00440       end += 12
00441       (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00442       start = end
00443       end += 4
00444       (length,) = _struct_I.unpack(str[start:end])
00445       start = end
00446       end += length
00447       if python3:
00448         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00449       else:
00450         self.action_feedback.header.frame_id = str[start:end]
00451       _x = self
00452       start = end
00453       end += 8
00454       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00455       start = end
00456       end += 4
00457       (length,) = _struct_I.unpack(str[start:end])
00458       start = end
00459       end += length
00460       if python3:
00461         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00462       else:
00463         self.action_feedback.status.goal_id.id = str[start:end]
00464       start = end
00465       end += 1
00466       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00467       start = end
00468       end += 4
00469       (length,) = _struct_I.unpack(str[start:end])
00470       start = end
00471       end += length
00472       if python3:
00473         self.action_feedback.status.text = str[start:end].decode('utf-8')
00474       else:
00475         self.action_feedback.status.text = str[start:end]
00476       return self
00477     except struct.error as e:
00478       raise genpy.DeserializationError(e) #most likely buffer underfill
00479 
00480 
00481   def serialize_numpy(self, buff, numpy):
00482     """
00483     serialize message with numpy array types into buffer
00484     :param buff: buffer, ``StringIO``
00485     :param numpy: numpy python module
00486     """
00487     try:
00488       _x = self
00489       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00490       _x = self.action_goal.header.frame_id
00491       length = len(_x)
00492       if python3 or type(_x) == unicode:
00493         _x = _x.encode('utf-8')
00494         length = len(_x)
00495       buff.write(struct.pack('<I%ss'%length, length, _x))
00496       _x = self
00497       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00498       _x = self.action_goal.goal_id.id
00499       length = len(_x)
00500       if python3 or type(_x) == unicode:
00501         _x = _x.encode('utf-8')
00502         length = len(_x)
00503       buff.write(struct.pack('<I%ss'%length, length, _x))
00504       _x = self
00505       buff.write(_struct_3d3I.pack(_x.action_goal.goal.angle_begin, _x.action_goal.goal.angle_end, _x.action_goal.goal.duration, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00506       _x = self.action_result.header.frame_id
00507       length = len(_x)
00508       if python3 or type(_x) == unicode:
00509         _x = _x.encode('utf-8')
00510         length = len(_x)
00511       buff.write(struct.pack('<I%ss'%length, length, _x))
00512       _x = self
00513       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00514       _x = self.action_result.status.goal_id.id
00515       length = len(_x)
00516       if python3 or type(_x) == unicode:
00517         _x = _x.encode('utf-8')
00518         length = len(_x)
00519       buff.write(struct.pack('<I%ss'%length, length, _x))
00520       buff.write(_struct_B.pack(self.action_result.status.status))
00521       _x = self.action_result.status.text
00522       length = len(_x)
00523       if python3 or type(_x) == unicode:
00524         _x = _x.encode('utf-8')
00525         length = len(_x)
00526       buff.write(struct.pack('<I%ss'%length, length, _x))
00527       _x = self
00528       buff.write(_struct_3I.pack(_x.action_result.result.cloud.header.seq, _x.action_result.result.cloud.header.stamp.secs, _x.action_result.result.cloud.header.stamp.nsecs))
00529       _x = self.action_result.result.cloud.header.frame_id
00530       length = len(_x)
00531       if python3 or type(_x) == unicode:
00532         _x = _x.encode('utf-8')
00533         length = len(_x)
00534       buff.write(struct.pack('<I%ss'%length, length, _x))
00535       length = len(self.action_result.result.cloud.points)
00536       buff.write(_struct_I.pack(length))
00537       for val1 in self.action_result.result.cloud.points:
00538         _x = val1
00539         buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00540       length = len(self.action_result.result.cloud.channels)
00541       buff.write(_struct_I.pack(length))
00542       for val1 in self.action_result.result.cloud.channels:
00543         _x = val1.name
00544         length = len(_x)
00545         if python3 or type(_x) == unicode:
00546           _x = _x.encode('utf-8')
00547           length = len(_x)
00548         buff.write(struct.pack('<I%ss'%length, length, _x))
00549         length = len(val1.values)
00550         buff.write(_struct_I.pack(length))
00551         pattern = '<%sf'%length
00552         buff.write(val1.values.tostring())
00553       _x = self
00554       buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00555       _x = self.action_feedback.header.frame_id
00556       length = len(_x)
00557       if python3 or type(_x) == unicode:
00558         _x = _x.encode('utf-8')
00559         length = len(_x)
00560       buff.write(struct.pack('<I%ss'%length, length, _x))
00561       _x = self
00562       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00563       _x = self.action_feedback.status.goal_id.id
00564       length = len(_x)
00565       if python3 or type(_x) == unicode:
00566         _x = _x.encode('utf-8')
00567         length = len(_x)
00568       buff.write(struct.pack('<I%ss'%length, length, _x))
00569       buff.write(_struct_B.pack(self.action_feedback.status.status))
00570       _x = self.action_feedback.status.text
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     except struct.error as se: self._check_types(se)
00577     except TypeError as te: self._check_types(te)
00578 
00579   def deserialize_numpy(self, str, numpy):
00580     """
00581     unpack serialized message in str into this message instance using numpy for array types
00582     :param str: byte array of serialized message, ``str``
00583     :param numpy: numpy python module
00584     """
00585     try:
00586       if self.action_goal is None:
00587         self.action_goal = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionGoal()
00588       if self.action_result is None:
00589         self.action_result = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionResult()
00590       if self.action_feedback is None:
00591         self.action_feedback = pr2_laser_snapshotter.msg.TiltLaserSnapshotActionFeedback()
00592       end = 0
00593       _x = self
00594       start = end
00595       end += 12
00596       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00597       start = end
00598       end += 4
00599       (length,) = _struct_I.unpack(str[start:end])
00600       start = end
00601       end += length
00602       if python3:
00603         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00604       else:
00605         self.action_goal.header.frame_id = str[start:end]
00606       _x = self
00607       start = end
00608       end += 8
00609       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00610       start = end
00611       end += 4
00612       (length,) = _struct_I.unpack(str[start:end])
00613       start = end
00614       end += length
00615       if python3:
00616         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00617       else:
00618         self.action_goal.goal_id.id = str[start:end]
00619       _x = self
00620       start = end
00621       end += 36
00622       (_x.action_goal.goal.angle_begin, _x.action_goal.goal.angle_end, _x.action_goal.goal.duration, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3d3I.unpack(str[start:end])
00623       start = end
00624       end += 4
00625       (length,) = _struct_I.unpack(str[start:end])
00626       start = end
00627       end += length
00628       if python3:
00629         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00630       else:
00631         self.action_result.header.frame_id = str[start:end]
00632       _x = self
00633       start = end
00634       end += 8
00635       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00636       start = end
00637       end += 4
00638       (length,) = _struct_I.unpack(str[start:end])
00639       start = end
00640       end += length
00641       if python3:
00642         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00643       else:
00644         self.action_result.status.goal_id.id = str[start:end]
00645       start = end
00646       end += 1
00647       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00648       start = end
00649       end += 4
00650       (length,) = _struct_I.unpack(str[start:end])
00651       start = end
00652       end += length
00653       if python3:
00654         self.action_result.status.text = str[start:end].decode('utf-8')
00655       else:
00656         self.action_result.status.text = str[start:end]
00657       _x = self
00658       start = end
00659       end += 12
00660       (_x.action_result.result.cloud.header.seq, _x.action_result.result.cloud.header.stamp.secs, _x.action_result.result.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00661       start = end
00662       end += 4
00663       (length,) = _struct_I.unpack(str[start:end])
00664       start = end
00665       end += length
00666       if python3:
00667         self.action_result.result.cloud.header.frame_id = str[start:end].decode('utf-8')
00668       else:
00669         self.action_result.result.cloud.header.frame_id = str[start:end]
00670       start = end
00671       end += 4
00672       (length,) = _struct_I.unpack(str[start:end])
00673       self.action_result.result.cloud.points = []
00674       for i in range(0, length):
00675         val1 = geometry_msgs.msg.Point32()
00676         _x = val1
00677         start = end
00678         end += 12
00679         (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00680         self.action_result.result.cloud.points.append(val1)
00681       start = end
00682       end += 4
00683       (length,) = _struct_I.unpack(str[start:end])
00684       self.action_result.result.cloud.channels = []
00685       for i in range(0, length):
00686         val1 = sensor_msgs.msg.ChannelFloat32()
00687         start = end
00688         end += 4
00689         (length,) = _struct_I.unpack(str[start:end])
00690         start = end
00691         end += length
00692         if python3:
00693           val1.name = str[start:end].decode('utf-8')
00694         else:
00695           val1.name = str[start:end]
00696         start = end
00697         end += 4
00698         (length,) = _struct_I.unpack(str[start:end])
00699         pattern = '<%sf'%length
00700         start = end
00701         end += struct.calcsize(pattern)
00702         val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00703         self.action_result.result.cloud.channels.append(val1)
00704       _x = self
00705       start = end
00706       end += 12
00707       (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00708       start = end
00709       end += 4
00710       (length,) = _struct_I.unpack(str[start:end])
00711       start = end
00712       end += length
00713       if python3:
00714         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00715       else:
00716         self.action_feedback.header.frame_id = str[start:end]
00717       _x = self
00718       start = end
00719       end += 8
00720       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00721       start = end
00722       end += 4
00723       (length,) = _struct_I.unpack(str[start:end])
00724       start = end
00725       end += length
00726       if python3:
00727         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00728       else:
00729         self.action_feedback.status.goal_id.id = str[start:end]
00730       start = end
00731       end += 1
00732       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00733       start = end
00734       end += 4
00735       (length,) = _struct_I.unpack(str[start:end])
00736       start = end
00737       end += length
00738       if python3:
00739         self.action_feedback.status.text = str[start:end].decode('utf-8')
00740       else:
00741         self.action_feedback.status.text = str[start:end]
00742       return self
00743     except struct.error as e:
00744       raise genpy.DeserializationError(e) #most likely buffer underfill
00745 
00746 _struct_I = genpy.struct_I
00747 _struct_3d3I = struct.Struct("<3d3I")
00748 _struct_3I = struct.Struct("<3I")
00749 _struct_B = struct.Struct("<B")
00750 _struct_2I = struct.Struct("<2I")
00751 _struct_3f = struct.Struct("<3f")