_GetSnapshotAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from pr2_tilt_laser_interface/GetSnapshotAction.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 pr2_tilt_laser_interface.msg
00008 import sensor_msgs.msg
00009 import genpy
00010 import actionlib_msgs.msg
00011 import std_msgs.msg
00012 
00013 class GetSnapshotAction(genpy.Message):
00014   _md5sum = "a02433255d6053a289c4e30e1bb6194d"
00015   _type = "pr2_tilt_laser_interface/GetSnapshotAction"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018 
00019 GetSnapshotActionGoal action_goal
00020 GetSnapshotActionResult action_result
00021 GetSnapshotActionFeedback action_feedback
00022 
00023 ================================================================================
00024 MSG: pr2_tilt_laser_interface/GetSnapshotActionGoal
00025 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00026 
00027 Header header
00028 actionlib_msgs/GoalID goal_id
00029 GetSnapshotGoal goal
00030 
00031 ================================================================================
00032 MSG: std_msgs/Header
00033 # Standard metadata for higher-level stamped data types.
00034 # This is generally used to communicate timestamped data 
00035 # in a particular coordinate frame.
00036 # 
00037 # sequence ID: consecutively increasing ID 
00038 uint32 seq
00039 #Two-integer timestamp that is expressed as:
00040 # * stamp.secs: seconds (stamp_secs) since epoch
00041 # * stamp.nsecs: nanoseconds since stamp_secs
00042 # time-handling sugar is provided by the client library
00043 time stamp
00044 #Frame this data is associated with
00045 # 0: no frame
00046 # 1: global frame
00047 string frame_id
00048 
00049 ================================================================================
00050 MSG: actionlib_msgs/GoalID
00051 # The stamp should store the time at which this goal was requested.
00052 # It is used by an action server when it tries to preempt all
00053 # goals that were requested before a certain time
00054 time stamp
00055 
00056 # The id provides a way to associate feedback and
00057 # result message with specific goal requests. The id
00058 # specified must be unique.
00059 string id
00060 
00061 
00062 ================================================================================
00063 MSG: pr2_tilt_laser_interface/GetSnapshotGoal
00064 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00065 # Goal
00066 # We always want to command. Don't need this bool
00067 # bool command_laser   # True: Use the command below. False: Use existing profile
00068 float32 start_angle
00069 float32 end_angle
00070 float32 speed
00071 bool hi_fidelity
00072 bool continuous
00073 
00074 ================================================================================
00075 MSG: pr2_tilt_laser_interface/GetSnapshotActionResult
00076 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00077 
00078 Header header
00079 actionlib_msgs/GoalStatus status
00080 GetSnapshotResult result
00081 
00082 ================================================================================
00083 MSG: actionlib_msgs/GoalStatus
00084 GoalID goal_id
00085 uint8 status
00086 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00087 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00088 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00089                             #   and has since completed its execution (Terminal State)
00090 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00091 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00092                             #    to some failure (Terminal State)
00093 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00094                             #    because the goal was unattainable or invalid (Terminal State)
00095 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00096                             #    and has not yet completed execution
00097 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00098                             #    but the action server has not yet confirmed that the goal is canceled
00099 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00100                             #    and was successfully cancelled (Terminal State)
00101 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00102                             #    sent over the wire by an action server
00103 
00104 #Allow for the user to associate a string with GoalStatus for debugging
00105 string text
00106 
00107 
00108 ================================================================================
00109 MSG: pr2_tilt_laser_interface/GetSnapshotResult
00110 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00111 # Result
00112 sensor_msgs/PointCloud2 cloud
00113 
00114 
00115 ================================================================================
00116 MSG: sensor_msgs/PointCloud2
00117 # This message holds a collection of N-dimensional points, which may
00118 # contain additional information such as normals, intensity, etc. The
00119 # point data is stored as a binary blob, its layout described by the
00120 # contents of the "fields" array.
00121 
00122 # The point cloud data may be organized 2d (image-like) or 1d
00123 # (unordered). Point clouds organized as 2d images may be produced by
00124 # camera depth sensors such as stereo or time-of-flight.
00125 
00126 # Time of sensor data acquisition, and the coordinate frame ID (for 3d
00127 # points).
00128 Header header
00129 
00130 # 2D structure of the point cloud. If the cloud is unordered, height is
00131 # 1 and width is the length of the point cloud.
00132 uint32 height
00133 uint32 width
00134 
00135 # Describes the channels and their layout in the binary data blob.
00136 PointField[] fields
00137 
00138 bool    is_bigendian # Is this data bigendian?
00139 uint32  point_step   # Length of a point in bytes
00140 uint32  row_step     # Length of a row in bytes
00141 uint8[] data         # Actual point data, size is (row_step*height)
00142 
00143 bool is_dense        # True if there are no invalid points
00144 
00145 ================================================================================
00146 MSG: sensor_msgs/PointField
00147 # This message holds the description of one point entry in the
00148 # PointCloud2 message format.
00149 uint8 INT8    = 1
00150 uint8 UINT8   = 2
00151 uint8 INT16   = 3
00152 uint8 UINT16  = 4
00153 uint8 INT32   = 5
00154 uint8 UINT32  = 6
00155 uint8 FLOAT32 = 7
00156 uint8 FLOAT64 = 8
00157 
00158 string name      # Name of field
00159 uint32 offset    # Offset from start of point struct
00160 uint8  datatype  # Datatype enumeration, see above
00161 uint32 count     # How many elements in the field
00162 
00163 ================================================================================
00164 MSG: pr2_tilt_laser_interface/GetSnapshotActionFeedback
00165 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00166 
00167 Header header
00168 actionlib_msgs/GoalStatus status
00169 GetSnapshotFeedback feedback
00170 
00171 ================================================================================
00172 MSG: pr2_tilt_laser_interface/GetSnapshotFeedback
00173 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00174 # Feedback
00175 sensor_msgs/PointCloud2 cloud
00176 
00177 
00178 
00179 """
00180   __slots__ = ['action_goal','action_result','action_feedback']
00181   _slot_types = ['pr2_tilt_laser_interface/GetSnapshotActionGoal','pr2_tilt_laser_interface/GetSnapshotActionResult','pr2_tilt_laser_interface/GetSnapshotActionFeedback']
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(GetSnapshotAction, 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_tilt_laser_interface.msg.GetSnapshotActionGoal()
00202       if self.action_result is None:
00203         self.action_result = pr2_tilt_laser_interface.msg.GetSnapshotActionResult()
00204       if self.action_feedback is None:
00205         self.action_feedback = pr2_tilt_laser_interface.msg.GetSnapshotActionFeedback()
00206     else:
00207       self.action_goal = pr2_tilt_laser_interface.msg.GetSnapshotActionGoal()
00208       self.action_result = pr2_tilt_laser_interface.msg.GetSnapshotActionResult()
00209       self.action_feedback = pr2_tilt_laser_interface.msg.GetSnapshotActionFeedback()
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_3f2B3I.pack(_x.action_goal.goal.start_angle, _x.action_goal.goal.end_angle, _x.action_goal.goal.speed, _x.action_goal.goal.hi_fidelity, _x.action_goal.goal.continuous, _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       _x = self
00271       buff.write(_struct_2I.pack(_x.action_result.result.cloud.height, _x.action_result.result.cloud.width))
00272       length = len(self.action_result.result.cloud.fields)
00273       buff.write(_struct_I.pack(length))
00274       for val1 in self.action_result.result.cloud.fields:
00275         _x = val1.name
00276         length = len(_x)
00277         if python3 or type(_x) == unicode:
00278           _x = _x.encode('utf-8')
00279           length = len(_x)
00280         buff.write(struct.pack('<I%ss'%length, length, _x))
00281         _x = val1
00282         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00283       _x = self
00284       buff.write(_struct_B2I.pack(_x.action_result.result.cloud.is_bigendian, _x.action_result.result.cloud.point_step, _x.action_result.result.cloud.row_step))
00285       _x = self.action_result.result.cloud.data
00286       length = len(_x)
00287       # - if encoded as a list instead, serialize as bytes instead of string
00288       if type(_x) in [list, tuple]:
00289         buff.write(struct.pack('<I%sB'%length, length, *_x))
00290       else:
00291         buff.write(struct.pack('<I%ss'%length, length, _x))
00292       _x = self
00293       buff.write(_struct_B3I.pack(_x.action_result.result.cloud.is_dense, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00294       _x = self.action_feedback.header.frame_id
00295       length = len(_x)
00296       if python3 or type(_x) == unicode:
00297         _x = _x.encode('utf-8')
00298         length = len(_x)
00299       buff.write(struct.pack('<I%ss'%length, length, _x))
00300       _x = self
00301       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00302       _x = self.action_feedback.status.goal_id.id
00303       length = len(_x)
00304       if python3 or type(_x) == unicode:
00305         _x = _x.encode('utf-8')
00306         length = len(_x)
00307       buff.write(struct.pack('<I%ss'%length, length, _x))
00308       buff.write(_struct_B.pack(self.action_feedback.status.status))
00309       _x = self.action_feedback.status.text
00310       length = len(_x)
00311       if python3 or type(_x) == unicode:
00312         _x = _x.encode('utf-8')
00313         length = len(_x)
00314       buff.write(struct.pack('<I%ss'%length, length, _x))
00315       _x = self
00316       buff.write(_struct_3I.pack(_x.action_feedback.feedback.cloud.header.seq, _x.action_feedback.feedback.cloud.header.stamp.secs, _x.action_feedback.feedback.cloud.header.stamp.nsecs))
00317       _x = self.action_feedback.feedback.cloud.header.frame_id
00318       length = len(_x)
00319       if python3 or type(_x) == unicode:
00320         _x = _x.encode('utf-8')
00321         length = len(_x)
00322       buff.write(struct.pack('<I%ss'%length, length, _x))
00323       _x = self
00324       buff.write(_struct_2I.pack(_x.action_feedback.feedback.cloud.height, _x.action_feedback.feedback.cloud.width))
00325       length = len(self.action_feedback.feedback.cloud.fields)
00326       buff.write(_struct_I.pack(length))
00327       for val1 in self.action_feedback.feedback.cloud.fields:
00328         _x = val1.name
00329         length = len(_x)
00330         if python3 or type(_x) == unicode:
00331           _x = _x.encode('utf-8')
00332           length = len(_x)
00333         buff.write(struct.pack('<I%ss'%length, length, _x))
00334         _x = val1
00335         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00336       _x = self
00337       buff.write(_struct_B2I.pack(_x.action_feedback.feedback.cloud.is_bigendian, _x.action_feedback.feedback.cloud.point_step, _x.action_feedback.feedback.cloud.row_step))
00338       _x = self.action_feedback.feedback.cloud.data
00339       length = len(_x)
00340       # - if encoded as a list instead, serialize as bytes instead of string
00341       if type(_x) in [list, tuple]:
00342         buff.write(struct.pack('<I%sB'%length, length, *_x))
00343       else:
00344         buff.write(struct.pack('<I%ss'%length, length, _x))
00345       buff.write(_struct_B.pack(self.action_feedback.feedback.cloud.is_dense))
00346     except struct.error as se: self._check_types(se)
00347     except TypeError as te: self._check_types(te)
00348 
00349   def deserialize(self, str):
00350     """
00351     unpack serialized message in str into this message instance
00352     :param str: byte array of serialized message, ``str``
00353     """
00354     try:
00355       if self.action_goal is None:
00356         self.action_goal = pr2_tilt_laser_interface.msg.GetSnapshotActionGoal()
00357       if self.action_result is None:
00358         self.action_result = pr2_tilt_laser_interface.msg.GetSnapshotActionResult()
00359       if self.action_feedback is None:
00360         self.action_feedback = pr2_tilt_laser_interface.msg.GetSnapshotActionFeedback()
00361       end = 0
00362       _x = self
00363       start = end
00364       end += 12
00365       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00366       start = end
00367       end += 4
00368       (length,) = _struct_I.unpack(str[start:end])
00369       start = end
00370       end += length
00371       if python3:
00372         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00373       else:
00374         self.action_goal.header.frame_id = str[start:end]
00375       _x = self
00376       start = end
00377       end += 8
00378       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00379       start = end
00380       end += 4
00381       (length,) = _struct_I.unpack(str[start:end])
00382       start = end
00383       end += length
00384       if python3:
00385         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00386       else:
00387         self.action_goal.goal_id.id = str[start:end]
00388       _x = self
00389       start = end
00390       end += 26
00391       (_x.action_goal.goal.start_angle, _x.action_goal.goal.end_angle, _x.action_goal.goal.speed, _x.action_goal.goal.hi_fidelity, _x.action_goal.goal.continuous, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3f2B3I.unpack(str[start:end])
00392       self.action_goal.goal.hi_fidelity = bool(self.action_goal.goal.hi_fidelity)
00393       self.action_goal.goal.continuous = bool(self.action_goal.goal.continuous)
00394       start = end
00395       end += 4
00396       (length,) = _struct_I.unpack(str[start:end])
00397       start = end
00398       end += length
00399       if python3:
00400         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00401       else:
00402         self.action_result.header.frame_id = str[start:end]
00403       _x = self
00404       start = end
00405       end += 8
00406       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00407       start = end
00408       end += 4
00409       (length,) = _struct_I.unpack(str[start:end])
00410       start = end
00411       end += length
00412       if python3:
00413         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00414       else:
00415         self.action_result.status.goal_id.id = str[start:end]
00416       start = end
00417       end += 1
00418       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00419       start = end
00420       end += 4
00421       (length,) = _struct_I.unpack(str[start:end])
00422       start = end
00423       end += length
00424       if python3:
00425         self.action_result.status.text = str[start:end].decode('utf-8')
00426       else:
00427         self.action_result.status.text = str[start:end]
00428       _x = self
00429       start = end
00430       end += 12
00431       (_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])
00432       start = end
00433       end += 4
00434       (length,) = _struct_I.unpack(str[start:end])
00435       start = end
00436       end += length
00437       if python3:
00438         self.action_result.result.cloud.header.frame_id = str[start:end].decode('utf-8')
00439       else:
00440         self.action_result.result.cloud.header.frame_id = str[start:end]
00441       _x = self
00442       start = end
00443       end += 8
00444       (_x.action_result.result.cloud.height, _x.action_result.result.cloud.width,) = _struct_2I.unpack(str[start:end])
00445       start = end
00446       end += 4
00447       (length,) = _struct_I.unpack(str[start:end])
00448       self.action_result.result.cloud.fields = []
00449       for i in range(0, length):
00450         val1 = sensor_msgs.msg.PointField()
00451         start = end
00452         end += 4
00453         (length,) = _struct_I.unpack(str[start:end])
00454         start = end
00455         end += length
00456         if python3:
00457           val1.name = str[start:end].decode('utf-8')
00458         else:
00459           val1.name = str[start:end]
00460         _x = val1
00461         start = end
00462         end += 9
00463         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00464         self.action_result.result.cloud.fields.append(val1)
00465       _x = self
00466       start = end
00467       end += 9
00468       (_x.action_result.result.cloud.is_bigendian, _x.action_result.result.cloud.point_step, _x.action_result.result.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00469       self.action_result.result.cloud.is_bigendian = bool(self.action_result.result.cloud.is_bigendian)
00470       start = end
00471       end += 4
00472       (length,) = _struct_I.unpack(str[start:end])
00473       start = end
00474       end += length
00475       if python3:
00476         self.action_result.result.cloud.data = str[start:end].decode('utf-8')
00477       else:
00478         self.action_result.result.cloud.data = str[start:end]
00479       _x = self
00480       start = end
00481       end += 13
00482       (_x.action_result.result.cloud.is_dense, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00483       self.action_result.result.cloud.is_dense = bool(self.action_result.result.cloud.is_dense)
00484       start = end
00485       end += 4
00486       (length,) = _struct_I.unpack(str[start:end])
00487       start = end
00488       end += length
00489       if python3:
00490         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00491       else:
00492         self.action_feedback.header.frame_id = str[start:end]
00493       _x = self
00494       start = end
00495       end += 8
00496       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00497       start = end
00498       end += 4
00499       (length,) = _struct_I.unpack(str[start:end])
00500       start = end
00501       end += length
00502       if python3:
00503         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00504       else:
00505         self.action_feedback.status.goal_id.id = str[start:end]
00506       start = end
00507       end += 1
00508       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00509       start = end
00510       end += 4
00511       (length,) = _struct_I.unpack(str[start:end])
00512       start = end
00513       end += length
00514       if python3:
00515         self.action_feedback.status.text = str[start:end].decode('utf-8')
00516       else:
00517         self.action_feedback.status.text = str[start:end]
00518       _x = self
00519       start = end
00520       end += 12
00521       (_x.action_feedback.feedback.cloud.header.seq, _x.action_feedback.feedback.cloud.header.stamp.secs, _x.action_feedback.feedback.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00522       start = end
00523       end += 4
00524       (length,) = _struct_I.unpack(str[start:end])
00525       start = end
00526       end += length
00527       if python3:
00528         self.action_feedback.feedback.cloud.header.frame_id = str[start:end].decode('utf-8')
00529       else:
00530         self.action_feedback.feedback.cloud.header.frame_id = str[start:end]
00531       _x = self
00532       start = end
00533       end += 8
00534       (_x.action_feedback.feedback.cloud.height, _x.action_feedback.feedback.cloud.width,) = _struct_2I.unpack(str[start:end])
00535       start = end
00536       end += 4
00537       (length,) = _struct_I.unpack(str[start:end])
00538       self.action_feedback.feedback.cloud.fields = []
00539       for i in range(0, length):
00540         val1 = sensor_msgs.msg.PointField()
00541         start = end
00542         end += 4
00543         (length,) = _struct_I.unpack(str[start:end])
00544         start = end
00545         end += length
00546         if python3:
00547           val1.name = str[start:end].decode('utf-8')
00548         else:
00549           val1.name = str[start:end]
00550         _x = val1
00551         start = end
00552         end += 9
00553         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00554         self.action_feedback.feedback.cloud.fields.append(val1)
00555       _x = self
00556       start = end
00557       end += 9
00558       (_x.action_feedback.feedback.cloud.is_bigendian, _x.action_feedback.feedback.cloud.point_step, _x.action_feedback.feedback.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00559       self.action_feedback.feedback.cloud.is_bigendian = bool(self.action_feedback.feedback.cloud.is_bigendian)
00560       start = end
00561       end += 4
00562       (length,) = _struct_I.unpack(str[start:end])
00563       start = end
00564       end += length
00565       if python3:
00566         self.action_feedback.feedback.cloud.data = str[start:end].decode('utf-8')
00567       else:
00568         self.action_feedback.feedback.cloud.data = str[start:end]
00569       start = end
00570       end += 1
00571       (self.action_feedback.feedback.cloud.is_dense,) = _struct_B.unpack(str[start:end])
00572       self.action_feedback.feedback.cloud.is_dense = bool(self.action_feedback.feedback.cloud.is_dense)
00573       return self
00574     except struct.error as e:
00575       raise genpy.DeserializationError(e) #most likely buffer underfill
00576 
00577 
00578   def serialize_numpy(self, buff, numpy):
00579     """
00580     serialize message with numpy array types into buffer
00581     :param buff: buffer, ``StringIO``
00582     :param numpy: numpy python module
00583     """
00584     try:
00585       _x = self
00586       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00587       _x = self.action_goal.header.frame_id
00588       length = len(_x)
00589       if python3 or type(_x) == unicode:
00590         _x = _x.encode('utf-8')
00591         length = len(_x)
00592       buff.write(struct.pack('<I%ss'%length, length, _x))
00593       _x = self
00594       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00595       _x = self.action_goal.goal_id.id
00596       length = len(_x)
00597       if python3 or type(_x) == unicode:
00598         _x = _x.encode('utf-8')
00599         length = len(_x)
00600       buff.write(struct.pack('<I%ss'%length, length, _x))
00601       _x = self
00602       buff.write(_struct_3f2B3I.pack(_x.action_goal.goal.start_angle, _x.action_goal.goal.end_angle, _x.action_goal.goal.speed, _x.action_goal.goal.hi_fidelity, _x.action_goal.goal.continuous, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00603       _x = self.action_result.header.frame_id
00604       length = len(_x)
00605       if python3 or type(_x) == unicode:
00606         _x = _x.encode('utf-8')
00607         length = len(_x)
00608       buff.write(struct.pack('<I%ss'%length, length, _x))
00609       _x = self
00610       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00611       _x = self.action_result.status.goal_id.id
00612       length = len(_x)
00613       if python3 or type(_x) == unicode:
00614         _x = _x.encode('utf-8')
00615         length = len(_x)
00616       buff.write(struct.pack('<I%ss'%length, length, _x))
00617       buff.write(_struct_B.pack(self.action_result.status.status))
00618       _x = self.action_result.status.text
00619       length = len(_x)
00620       if python3 or type(_x) == unicode:
00621         _x = _x.encode('utf-8')
00622         length = len(_x)
00623       buff.write(struct.pack('<I%ss'%length, length, _x))
00624       _x = self
00625       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))
00626       _x = self.action_result.result.cloud.header.frame_id
00627       length = len(_x)
00628       if python3 or type(_x) == unicode:
00629         _x = _x.encode('utf-8')
00630         length = len(_x)
00631       buff.write(struct.pack('<I%ss'%length, length, _x))
00632       _x = self
00633       buff.write(_struct_2I.pack(_x.action_result.result.cloud.height, _x.action_result.result.cloud.width))
00634       length = len(self.action_result.result.cloud.fields)
00635       buff.write(_struct_I.pack(length))
00636       for val1 in self.action_result.result.cloud.fields:
00637         _x = val1.name
00638         length = len(_x)
00639         if python3 or type(_x) == unicode:
00640           _x = _x.encode('utf-8')
00641           length = len(_x)
00642         buff.write(struct.pack('<I%ss'%length, length, _x))
00643         _x = val1
00644         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00645       _x = self
00646       buff.write(_struct_B2I.pack(_x.action_result.result.cloud.is_bigendian, _x.action_result.result.cloud.point_step, _x.action_result.result.cloud.row_step))
00647       _x = self.action_result.result.cloud.data
00648       length = len(_x)
00649       # - if encoded as a list instead, serialize as bytes instead of string
00650       if type(_x) in [list, tuple]:
00651         buff.write(struct.pack('<I%sB'%length, length, *_x))
00652       else:
00653         buff.write(struct.pack('<I%ss'%length, length, _x))
00654       _x = self
00655       buff.write(_struct_B3I.pack(_x.action_result.result.cloud.is_dense, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00656       _x = self.action_feedback.header.frame_id
00657       length = len(_x)
00658       if python3 or type(_x) == unicode:
00659         _x = _x.encode('utf-8')
00660         length = len(_x)
00661       buff.write(struct.pack('<I%ss'%length, length, _x))
00662       _x = self
00663       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00664       _x = self.action_feedback.status.goal_id.id
00665       length = len(_x)
00666       if python3 or type(_x) == unicode:
00667         _x = _x.encode('utf-8')
00668         length = len(_x)
00669       buff.write(struct.pack('<I%ss'%length, length, _x))
00670       buff.write(_struct_B.pack(self.action_feedback.status.status))
00671       _x = self.action_feedback.status.text
00672       length = len(_x)
00673       if python3 or type(_x) == unicode:
00674         _x = _x.encode('utf-8')
00675         length = len(_x)
00676       buff.write(struct.pack('<I%ss'%length, length, _x))
00677       _x = self
00678       buff.write(_struct_3I.pack(_x.action_feedback.feedback.cloud.header.seq, _x.action_feedback.feedback.cloud.header.stamp.secs, _x.action_feedback.feedback.cloud.header.stamp.nsecs))
00679       _x = self.action_feedback.feedback.cloud.header.frame_id
00680       length = len(_x)
00681       if python3 or type(_x) == unicode:
00682         _x = _x.encode('utf-8')
00683         length = len(_x)
00684       buff.write(struct.pack('<I%ss'%length, length, _x))
00685       _x = self
00686       buff.write(_struct_2I.pack(_x.action_feedback.feedback.cloud.height, _x.action_feedback.feedback.cloud.width))
00687       length = len(self.action_feedback.feedback.cloud.fields)
00688       buff.write(_struct_I.pack(length))
00689       for val1 in self.action_feedback.feedback.cloud.fields:
00690         _x = val1.name
00691         length = len(_x)
00692         if python3 or type(_x) == unicode:
00693           _x = _x.encode('utf-8')
00694           length = len(_x)
00695         buff.write(struct.pack('<I%ss'%length, length, _x))
00696         _x = val1
00697         buff.write(_struct_IBI.pack(_x.offset, _x.datatype, _x.count))
00698       _x = self
00699       buff.write(_struct_B2I.pack(_x.action_feedback.feedback.cloud.is_bigendian, _x.action_feedback.feedback.cloud.point_step, _x.action_feedback.feedback.cloud.row_step))
00700       _x = self.action_feedback.feedback.cloud.data
00701       length = len(_x)
00702       # - if encoded as a list instead, serialize as bytes instead of string
00703       if type(_x) in [list, tuple]:
00704         buff.write(struct.pack('<I%sB'%length, length, *_x))
00705       else:
00706         buff.write(struct.pack('<I%ss'%length, length, _x))
00707       buff.write(_struct_B.pack(self.action_feedback.feedback.cloud.is_dense))
00708     except struct.error as se: self._check_types(se)
00709     except TypeError as te: self._check_types(te)
00710 
00711   def deserialize_numpy(self, str, numpy):
00712     """
00713     unpack serialized message in str into this message instance using numpy for array types
00714     :param str: byte array of serialized message, ``str``
00715     :param numpy: numpy python module
00716     """
00717     try:
00718       if self.action_goal is None:
00719         self.action_goal = pr2_tilt_laser_interface.msg.GetSnapshotActionGoal()
00720       if self.action_result is None:
00721         self.action_result = pr2_tilt_laser_interface.msg.GetSnapshotActionResult()
00722       if self.action_feedback is None:
00723         self.action_feedback = pr2_tilt_laser_interface.msg.GetSnapshotActionFeedback()
00724       end = 0
00725       _x = self
00726       start = end
00727       end += 12
00728       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00729       start = end
00730       end += 4
00731       (length,) = _struct_I.unpack(str[start:end])
00732       start = end
00733       end += length
00734       if python3:
00735         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00736       else:
00737         self.action_goal.header.frame_id = str[start:end]
00738       _x = self
00739       start = end
00740       end += 8
00741       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00742       start = end
00743       end += 4
00744       (length,) = _struct_I.unpack(str[start:end])
00745       start = end
00746       end += length
00747       if python3:
00748         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00749       else:
00750         self.action_goal.goal_id.id = str[start:end]
00751       _x = self
00752       start = end
00753       end += 26
00754       (_x.action_goal.goal.start_angle, _x.action_goal.goal.end_angle, _x.action_goal.goal.speed, _x.action_goal.goal.hi_fidelity, _x.action_goal.goal.continuous, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3f2B3I.unpack(str[start:end])
00755       self.action_goal.goal.hi_fidelity = bool(self.action_goal.goal.hi_fidelity)
00756       self.action_goal.goal.continuous = bool(self.action_goal.goal.continuous)
00757       start = end
00758       end += 4
00759       (length,) = _struct_I.unpack(str[start:end])
00760       start = end
00761       end += length
00762       if python3:
00763         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00764       else:
00765         self.action_result.header.frame_id = str[start:end]
00766       _x = self
00767       start = end
00768       end += 8
00769       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00770       start = end
00771       end += 4
00772       (length,) = _struct_I.unpack(str[start:end])
00773       start = end
00774       end += length
00775       if python3:
00776         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00777       else:
00778         self.action_result.status.goal_id.id = str[start:end]
00779       start = end
00780       end += 1
00781       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00782       start = end
00783       end += 4
00784       (length,) = _struct_I.unpack(str[start:end])
00785       start = end
00786       end += length
00787       if python3:
00788         self.action_result.status.text = str[start:end].decode('utf-8')
00789       else:
00790         self.action_result.status.text = str[start:end]
00791       _x = self
00792       start = end
00793       end += 12
00794       (_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])
00795       start = end
00796       end += 4
00797       (length,) = _struct_I.unpack(str[start:end])
00798       start = end
00799       end += length
00800       if python3:
00801         self.action_result.result.cloud.header.frame_id = str[start:end].decode('utf-8')
00802       else:
00803         self.action_result.result.cloud.header.frame_id = str[start:end]
00804       _x = self
00805       start = end
00806       end += 8
00807       (_x.action_result.result.cloud.height, _x.action_result.result.cloud.width,) = _struct_2I.unpack(str[start:end])
00808       start = end
00809       end += 4
00810       (length,) = _struct_I.unpack(str[start:end])
00811       self.action_result.result.cloud.fields = []
00812       for i in range(0, length):
00813         val1 = sensor_msgs.msg.PointField()
00814         start = end
00815         end += 4
00816         (length,) = _struct_I.unpack(str[start:end])
00817         start = end
00818         end += length
00819         if python3:
00820           val1.name = str[start:end].decode('utf-8')
00821         else:
00822           val1.name = str[start:end]
00823         _x = val1
00824         start = end
00825         end += 9
00826         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00827         self.action_result.result.cloud.fields.append(val1)
00828       _x = self
00829       start = end
00830       end += 9
00831       (_x.action_result.result.cloud.is_bigendian, _x.action_result.result.cloud.point_step, _x.action_result.result.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00832       self.action_result.result.cloud.is_bigendian = bool(self.action_result.result.cloud.is_bigendian)
00833       start = end
00834       end += 4
00835       (length,) = _struct_I.unpack(str[start:end])
00836       start = end
00837       end += length
00838       if python3:
00839         self.action_result.result.cloud.data = str[start:end].decode('utf-8')
00840       else:
00841         self.action_result.result.cloud.data = str[start:end]
00842       _x = self
00843       start = end
00844       end += 13
00845       (_x.action_result.result.cloud.is_dense, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00846       self.action_result.result.cloud.is_dense = bool(self.action_result.result.cloud.is_dense)
00847       start = end
00848       end += 4
00849       (length,) = _struct_I.unpack(str[start:end])
00850       start = end
00851       end += length
00852       if python3:
00853         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00854       else:
00855         self.action_feedback.header.frame_id = str[start:end]
00856       _x = self
00857       start = end
00858       end += 8
00859       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(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         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00867       else:
00868         self.action_feedback.status.goal_id.id = str[start:end]
00869       start = end
00870       end += 1
00871       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00872       start = end
00873       end += 4
00874       (length,) = _struct_I.unpack(str[start:end])
00875       start = end
00876       end += length
00877       if python3:
00878         self.action_feedback.status.text = str[start:end].decode('utf-8')
00879       else:
00880         self.action_feedback.status.text = str[start:end]
00881       _x = self
00882       start = end
00883       end += 12
00884       (_x.action_feedback.feedback.cloud.header.seq, _x.action_feedback.feedback.cloud.header.stamp.secs, _x.action_feedback.feedback.cloud.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00885       start = end
00886       end += 4
00887       (length,) = _struct_I.unpack(str[start:end])
00888       start = end
00889       end += length
00890       if python3:
00891         self.action_feedback.feedback.cloud.header.frame_id = str[start:end].decode('utf-8')
00892       else:
00893         self.action_feedback.feedback.cloud.header.frame_id = str[start:end]
00894       _x = self
00895       start = end
00896       end += 8
00897       (_x.action_feedback.feedback.cloud.height, _x.action_feedback.feedback.cloud.width,) = _struct_2I.unpack(str[start:end])
00898       start = end
00899       end += 4
00900       (length,) = _struct_I.unpack(str[start:end])
00901       self.action_feedback.feedback.cloud.fields = []
00902       for i in range(0, length):
00903         val1 = sensor_msgs.msg.PointField()
00904         start = end
00905         end += 4
00906         (length,) = _struct_I.unpack(str[start:end])
00907         start = end
00908         end += length
00909         if python3:
00910           val1.name = str[start:end].decode('utf-8')
00911         else:
00912           val1.name = str[start:end]
00913         _x = val1
00914         start = end
00915         end += 9
00916         (_x.offset, _x.datatype, _x.count,) = _struct_IBI.unpack(str[start:end])
00917         self.action_feedback.feedback.cloud.fields.append(val1)
00918       _x = self
00919       start = end
00920       end += 9
00921       (_x.action_feedback.feedback.cloud.is_bigendian, _x.action_feedback.feedback.cloud.point_step, _x.action_feedback.feedback.cloud.row_step,) = _struct_B2I.unpack(str[start:end])
00922       self.action_feedback.feedback.cloud.is_bigendian = bool(self.action_feedback.feedback.cloud.is_bigendian)
00923       start = end
00924       end += 4
00925       (length,) = _struct_I.unpack(str[start:end])
00926       start = end
00927       end += length
00928       if python3:
00929         self.action_feedback.feedback.cloud.data = str[start:end].decode('utf-8')
00930       else:
00931         self.action_feedback.feedback.cloud.data = str[start:end]
00932       start = end
00933       end += 1
00934       (self.action_feedback.feedback.cloud.is_dense,) = _struct_B.unpack(str[start:end])
00935       self.action_feedback.feedback.cloud.is_dense = bool(self.action_feedback.feedback.cloud.is_dense)
00936       return self
00937     except struct.error as e:
00938       raise genpy.DeserializationError(e) #most likely buffer underfill
00939 
00940 _struct_I = genpy.struct_I
00941 _struct_IBI = struct.Struct("<IBI")
00942 _struct_B = struct.Struct("<B")
00943 _struct_3I = struct.Struct("<3I")
00944 _struct_3f2B3I = struct.Struct("<3f2B3I")
00945 _struct_B2I = struct.Struct("<B2I")
00946 _struct_2I = struct.Struct("<2I")
00947 _struct_B3I = struct.Struct("<B3I")


pr2_tilt_laser_interface
Author(s): Radu Rusu, Wim Meeussen, Vijay Pradeep
autogenerated on Sat Dec 28 2013 17:25:13