_DoorAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from door_msgs/DoorAction.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006 
00007 import geometry_msgs.msg
00008 import std_msgs.msg
00009 import genpy
00010 import actionlib_msgs.msg
00011 import door_msgs.msg
00012 
00013 class DoorAction(genpy.Message):
00014   _md5sum = "09daec85681f57839e2a9dcef0a9b828"
00015   _type = "door_msgs/DoorAction"
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 DoorActionGoal action_goal
00020 DoorActionResult action_result
00021 DoorActionFeedback action_feedback
00022 
00023 ================================================================================
00024 MSG: door_msgs/DoorActionGoal
00025 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00026 
00027 Header header
00028 actionlib_msgs/GoalID goal_id
00029 DoorGoal 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: door_msgs/DoorGoal
00064 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00065 # goal
00066 door_msgs/Door door
00067 
00068 ================================================================================
00069 MSG: door_msgs/Door
00070 Header header
00071 geometry_msgs/Point32 frame_p1  ## position of the door frame
00072 geometry_msgs/Point32 frame_p2  ## position of the door frame
00073 geometry_msgs/Point32 door_p1   ## Ground plane projection of a point on the plane of the door 
00074 geometry_msgs/Point32 door_p2   ## Ground plane projection of a point on the plane of the door
00075 geometry_msgs/Point32 handle    ## Position of the door handle
00076 float32 height               ## Height of the door
00077 
00078 int32 UNKNOWN=0
00079 
00080 int32 HINGE_P1=1
00081 int32 HINGE_P2=2
00082 int32 hinge                  
00083 
00084 int32 ROT_DIR_CLOCKWISE=1
00085 int32 ROT_DIR_COUNTERCLOCKWISE=2
00086 int32 rot_dir                
00087 
00088 int32 LOCKED=1
00089 int32 LATCHED=2
00090 int32 UNLATCHED=3
00091 int32 latch_state            
00092 
00093 geometry_msgs/Vector3 travel_dir           ## vector pointing in the direction the robot is going to travel through the door
00094 float32 weight               ## @Sachin: what do we use this for?
00095 
00096 
00097 
00098 ================================================================================
00099 MSG: geometry_msgs/Point32
00100 # This contains the position of a point in free space(with 32 bits of precision).
00101 # It is recommeded to use Point wherever possible instead of Point32.  
00102 # 
00103 # This recommendation is to promote interoperability.  
00104 #
00105 # This message is designed to take up less space when sending
00106 # lots of points at once, as in the case of a PointCloud.  
00107 
00108 float32 x
00109 float32 y
00110 float32 z
00111 ================================================================================
00112 MSG: geometry_msgs/Vector3
00113 # This represents a vector in free space. 
00114 
00115 float64 x
00116 float64 y
00117 float64 z
00118 ================================================================================
00119 MSG: door_msgs/DoorActionResult
00120 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00121 
00122 Header header
00123 actionlib_msgs/GoalStatus status
00124 DoorResult result
00125 
00126 ================================================================================
00127 MSG: actionlib_msgs/GoalStatus
00128 GoalID goal_id
00129 uint8 status
00130 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00131 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00132 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00133                             #   and has since completed its execution (Terminal State)
00134 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00135 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00136                             #    to some failure (Terminal State)
00137 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00138                             #    because the goal was unattainable or invalid (Terminal State)
00139 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00140                             #    and has not yet completed execution
00141 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00142                             #    but the action server has not yet confirmed that the goal is canceled
00143 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00144                             #    and was successfully cancelled (Terminal State)
00145 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00146                             #    sent over the wire by an action server
00147 
00148 #Allow for the user to associate a string with GoalStatus for debugging
00149 string text
00150 
00151 
00152 ================================================================================
00153 MSG: door_msgs/DoorResult
00154 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00155 # result
00156 door_msgs/Door door
00157 
00158 ================================================================================
00159 MSG: door_msgs/DoorActionFeedback
00160 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00161 
00162 Header header
00163 actionlib_msgs/GoalStatus status
00164 DoorFeedback feedback
00165 
00166 ================================================================================
00167 MSG: door_msgs/DoorFeedback
00168 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00169 
00170 
00171 """
00172   __slots__ = ['action_goal','action_result','action_feedback']
00173   _slot_types = ['door_msgs/DoorActionGoal','door_msgs/DoorActionResult','door_msgs/DoorActionFeedback']
00174 
00175   def __init__(self, *args, **kwds):
00176     """
00177     Constructor. Any message fields that are implicitly/explicitly
00178     set to None will be assigned a default value. The recommend
00179     use is keyword arguments as this is more robust to future message
00180     changes.  You cannot mix in-order arguments and keyword arguments.
00181 
00182     The available fields are:
00183        action_goal,action_result,action_feedback
00184 
00185     :param args: complete set of field values, in .msg order
00186     :param kwds: use keyword arguments corresponding to message field names
00187     to set specific fields.
00188     """
00189     if args or kwds:
00190       super(DoorAction, self).__init__(*args, **kwds)
00191       #message fields cannot be None, assign default values for those that are
00192       if self.action_goal is None:
00193         self.action_goal = door_msgs.msg.DoorActionGoal()
00194       if self.action_result is None:
00195         self.action_result = door_msgs.msg.DoorActionResult()
00196       if self.action_feedback is None:
00197         self.action_feedback = door_msgs.msg.DoorActionFeedback()
00198     else:
00199       self.action_goal = door_msgs.msg.DoorActionGoal()
00200       self.action_result = door_msgs.msg.DoorActionResult()
00201       self.action_feedback = door_msgs.msg.DoorActionFeedback()
00202 
00203   def _get_types(self):
00204     """
00205     internal API method
00206     """
00207     return self._slot_types
00208 
00209   def serialize(self, buff):
00210     """
00211     serialize message into buffer
00212     :param buff: buffer, ``StringIO``
00213     """
00214     try:
00215       _x = self
00216       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00217       _x = self.action_goal.header.frame_id
00218       length = len(_x)
00219       if python3 or type(_x) == unicode:
00220         _x = _x.encode('utf-8')
00221         length = len(_x)
00222       buff.write(struct.pack('<I%ss'%length, length, _x))
00223       _x = self
00224       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00225       _x = self.action_goal.goal_id.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_3I.pack(_x.action_goal.goal.door.header.seq, _x.action_goal.goal.door.header.stamp.secs, _x.action_goal.goal.door.header.stamp.nsecs))
00233       _x = self.action_goal.goal.door.header.frame_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_16f3i3df3I.pack(_x.action_goal.goal.door.frame_p1.x, _x.action_goal.goal.door.frame_p1.y, _x.action_goal.goal.door.frame_p1.z, _x.action_goal.goal.door.frame_p2.x, _x.action_goal.goal.door.frame_p2.y, _x.action_goal.goal.door.frame_p2.z, _x.action_goal.goal.door.door_p1.x, _x.action_goal.goal.door.door_p1.y, _x.action_goal.goal.door.door_p1.z, _x.action_goal.goal.door.door_p2.x, _x.action_goal.goal.door.door_p2.y, _x.action_goal.goal.door.door_p2.z, _x.action_goal.goal.door.handle.x, _x.action_goal.goal.door.handle.y, _x.action_goal.goal.door.handle.z, _x.action_goal.goal.door.height, _x.action_goal.goal.door.hinge, _x.action_goal.goal.door.rot_dir, _x.action_goal.goal.door.latch_state, _x.action_goal.goal.door.travel_dir.x, _x.action_goal.goal.door.travel_dir.y, _x.action_goal.goal.door.travel_dir.z, _x.action_goal.goal.door.weight, _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.door.header.seq, _x.action_result.result.door.header.stamp.secs, _x.action_result.result.door.header.stamp.nsecs))
00264       _x = self.action_result.result.door.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_16f3i3df3I.pack(_x.action_result.result.door.frame_p1.x, _x.action_result.result.door.frame_p1.y, _x.action_result.result.door.frame_p1.z, _x.action_result.result.door.frame_p2.x, _x.action_result.result.door.frame_p2.y, _x.action_result.result.door.frame_p2.z, _x.action_result.result.door.door_p1.x, _x.action_result.result.door.door_p1.y, _x.action_result.result.door.door_p1.z, _x.action_result.result.door.door_p2.x, _x.action_result.result.door.door_p2.y, _x.action_result.result.door.door_p2.z, _x.action_result.result.door.handle.x, _x.action_result.result.door.handle.y, _x.action_result.result.door.handle.z, _x.action_result.result.door.height, _x.action_result.result.door.hinge, _x.action_result.result.door.rot_dir, _x.action_result.result.door.latch_state, _x.action_result.result.door.travel_dir.x, _x.action_result.result.door.travel_dir.y, _x.action_result.result.door.travel_dir.z, _x.action_result.result.door.weight, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00272       _x = self.action_feedback.header.frame_id
00273       length = len(_x)
00274       if python3 or type(_x) == unicode:
00275         _x = _x.encode('utf-8')
00276         length = len(_x)
00277       buff.write(struct.pack('<I%ss'%length, length, _x))
00278       _x = self
00279       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00280       _x = self.action_feedback.status.goal_id.id
00281       length = len(_x)
00282       if python3 or type(_x) == unicode:
00283         _x = _x.encode('utf-8')
00284         length = len(_x)
00285       buff.write(struct.pack('<I%ss'%length, length, _x))
00286       buff.write(_struct_B.pack(self.action_feedback.status.status))
00287       _x = self.action_feedback.status.text
00288       length = len(_x)
00289       if python3 or type(_x) == unicode:
00290         _x = _x.encode('utf-8')
00291         length = len(_x)
00292       buff.write(struct.pack('<I%ss'%length, length, _x))
00293     except struct.error as se: self._check_types(se)
00294     except TypeError as te: self._check_types(te)
00295 
00296   def deserialize(self, str):
00297     """
00298     unpack serialized message in str into this message instance
00299     :param str: byte array of serialized message, ``str``
00300     """
00301     try:
00302       if self.action_goal is None:
00303         self.action_goal = door_msgs.msg.DoorActionGoal()
00304       if self.action_result is None:
00305         self.action_result = door_msgs.msg.DoorActionResult()
00306       if self.action_feedback is None:
00307         self.action_feedback = door_msgs.msg.DoorActionFeedback()
00308       end = 0
00309       _x = self
00310       start = end
00311       end += 12
00312       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00313       start = end
00314       end += 4
00315       (length,) = _struct_I.unpack(str[start:end])
00316       start = end
00317       end += length
00318       if python3:
00319         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00320       else:
00321         self.action_goal.header.frame_id = str[start:end]
00322       _x = self
00323       start = end
00324       end += 8
00325       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00326       start = end
00327       end += 4
00328       (length,) = _struct_I.unpack(str[start:end])
00329       start = end
00330       end += length
00331       if python3:
00332         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00333       else:
00334         self.action_goal.goal_id.id = str[start:end]
00335       _x = self
00336       start = end
00337       end += 12
00338       (_x.action_goal.goal.door.header.seq, _x.action_goal.goal.door.header.stamp.secs, _x.action_goal.goal.door.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00339       start = end
00340       end += 4
00341       (length,) = _struct_I.unpack(str[start:end])
00342       start = end
00343       end += length
00344       if python3:
00345         self.action_goal.goal.door.header.frame_id = str[start:end].decode('utf-8')
00346       else:
00347         self.action_goal.goal.door.header.frame_id = str[start:end]
00348       _x = self
00349       start = end
00350       end += 116
00351       (_x.action_goal.goal.door.frame_p1.x, _x.action_goal.goal.door.frame_p1.y, _x.action_goal.goal.door.frame_p1.z, _x.action_goal.goal.door.frame_p2.x, _x.action_goal.goal.door.frame_p2.y, _x.action_goal.goal.door.frame_p2.z, _x.action_goal.goal.door.door_p1.x, _x.action_goal.goal.door.door_p1.y, _x.action_goal.goal.door.door_p1.z, _x.action_goal.goal.door.door_p2.x, _x.action_goal.goal.door.door_p2.y, _x.action_goal.goal.door.door_p2.z, _x.action_goal.goal.door.handle.x, _x.action_goal.goal.door.handle.y, _x.action_goal.goal.door.handle.z, _x.action_goal.goal.door.height, _x.action_goal.goal.door.hinge, _x.action_goal.goal.door.rot_dir, _x.action_goal.goal.door.latch_state, _x.action_goal.goal.door.travel_dir.x, _x.action_goal.goal.door.travel_dir.y, _x.action_goal.goal.door.travel_dir.z, _x.action_goal.goal.door.weight, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_16f3i3df3I.unpack(str[start:end])
00352       start = end
00353       end += 4
00354       (length,) = _struct_I.unpack(str[start:end])
00355       start = end
00356       end += length
00357       if python3:
00358         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00359       else:
00360         self.action_result.header.frame_id = str[start:end]
00361       _x = self
00362       start = end
00363       end += 8
00364       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00365       start = end
00366       end += 4
00367       (length,) = _struct_I.unpack(str[start:end])
00368       start = end
00369       end += length
00370       if python3:
00371         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00372       else:
00373         self.action_result.status.goal_id.id = str[start:end]
00374       start = end
00375       end += 1
00376       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00377       start = end
00378       end += 4
00379       (length,) = _struct_I.unpack(str[start:end])
00380       start = end
00381       end += length
00382       if python3:
00383         self.action_result.status.text = str[start:end].decode('utf-8')
00384       else:
00385         self.action_result.status.text = str[start:end]
00386       _x = self
00387       start = end
00388       end += 12
00389       (_x.action_result.result.door.header.seq, _x.action_result.result.door.header.stamp.secs, _x.action_result.result.door.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00390       start = end
00391       end += 4
00392       (length,) = _struct_I.unpack(str[start:end])
00393       start = end
00394       end += length
00395       if python3:
00396         self.action_result.result.door.header.frame_id = str[start:end].decode('utf-8')
00397       else:
00398         self.action_result.result.door.header.frame_id = str[start:end]
00399       _x = self
00400       start = end
00401       end += 116
00402       (_x.action_result.result.door.frame_p1.x, _x.action_result.result.door.frame_p1.y, _x.action_result.result.door.frame_p1.z, _x.action_result.result.door.frame_p2.x, _x.action_result.result.door.frame_p2.y, _x.action_result.result.door.frame_p2.z, _x.action_result.result.door.door_p1.x, _x.action_result.result.door.door_p1.y, _x.action_result.result.door.door_p1.z, _x.action_result.result.door.door_p2.x, _x.action_result.result.door.door_p2.y, _x.action_result.result.door.door_p2.z, _x.action_result.result.door.handle.x, _x.action_result.result.door.handle.y, _x.action_result.result.door.handle.z, _x.action_result.result.door.height, _x.action_result.result.door.hinge, _x.action_result.result.door.rot_dir, _x.action_result.result.door.latch_state, _x.action_result.result.door.travel_dir.x, _x.action_result.result.door.travel_dir.y, _x.action_result.result.door.travel_dir.z, _x.action_result.result.door.weight, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_16f3i3df3I.unpack(str[start:end])
00403       start = end
00404       end += 4
00405       (length,) = _struct_I.unpack(str[start:end])
00406       start = end
00407       end += length
00408       if python3:
00409         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00410       else:
00411         self.action_feedback.header.frame_id = str[start:end]
00412       _x = self
00413       start = end
00414       end += 8
00415       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00416       start = end
00417       end += 4
00418       (length,) = _struct_I.unpack(str[start:end])
00419       start = end
00420       end += length
00421       if python3:
00422         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00423       else:
00424         self.action_feedback.status.goal_id.id = str[start:end]
00425       start = end
00426       end += 1
00427       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00428       start = end
00429       end += 4
00430       (length,) = _struct_I.unpack(str[start:end])
00431       start = end
00432       end += length
00433       if python3:
00434         self.action_feedback.status.text = str[start:end].decode('utf-8')
00435       else:
00436         self.action_feedback.status.text = str[start:end]
00437       return self
00438     except struct.error as e:
00439       raise genpy.DeserializationError(e) #most likely buffer underfill
00440 
00441 
00442   def serialize_numpy(self, buff, numpy):
00443     """
00444     serialize message with numpy array types into buffer
00445     :param buff: buffer, ``StringIO``
00446     :param numpy: numpy python module
00447     """
00448     try:
00449       _x = self
00450       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00451       _x = self.action_goal.header.frame_id
00452       length = len(_x)
00453       if python3 or type(_x) == unicode:
00454         _x = _x.encode('utf-8')
00455         length = len(_x)
00456       buff.write(struct.pack('<I%ss'%length, length, _x))
00457       _x = self
00458       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00459       _x = self.action_goal.goal_id.id
00460       length = len(_x)
00461       if python3 or type(_x) == unicode:
00462         _x = _x.encode('utf-8')
00463         length = len(_x)
00464       buff.write(struct.pack('<I%ss'%length, length, _x))
00465       _x = self
00466       buff.write(_struct_3I.pack(_x.action_goal.goal.door.header.seq, _x.action_goal.goal.door.header.stamp.secs, _x.action_goal.goal.door.header.stamp.nsecs))
00467       _x = self.action_goal.goal.door.header.frame_id
00468       length = len(_x)
00469       if python3 or type(_x) == unicode:
00470         _x = _x.encode('utf-8')
00471         length = len(_x)
00472       buff.write(struct.pack('<I%ss'%length, length, _x))
00473       _x = self
00474       buff.write(_struct_16f3i3df3I.pack(_x.action_goal.goal.door.frame_p1.x, _x.action_goal.goal.door.frame_p1.y, _x.action_goal.goal.door.frame_p1.z, _x.action_goal.goal.door.frame_p2.x, _x.action_goal.goal.door.frame_p2.y, _x.action_goal.goal.door.frame_p2.z, _x.action_goal.goal.door.door_p1.x, _x.action_goal.goal.door.door_p1.y, _x.action_goal.goal.door.door_p1.z, _x.action_goal.goal.door.door_p2.x, _x.action_goal.goal.door.door_p2.y, _x.action_goal.goal.door.door_p2.z, _x.action_goal.goal.door.handle.x, _x.action_goal.goal.door.handle.y, _x.action_goal.goal.door.handle.z, _x.action_goal.goal.door.height, _x.action_goal.goal.door.hinge, _x.action_goal.goal.door.rot_dir, _x.action_goal.goal.door.latch_state, _x.action_goal.goal.door.travel_dir.x, _x.action_goal.goal.door.travel_dir.y, _x.action_goal.goal.door.travel_dir.z, _x.action_goal.goal.door.weight, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00475       _x = self.action_result.header.frame_id
00476       length = len(_x)
00477       if python3 or type(_x) == unicode:
00478         _x = _x.encode('utf-8')
00479         length = len(_x)
00480       buff.write(struct.pack('<I%ss'%length, length, _x))
00481       _x = self
00482       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00483       _x = self.action_result.status.goal_id.id
00484       length = len(_x)
00485       if python3 or type(_x) == unicode:
00486         _x = _x.encode('utf-8')
00487         length = len(_x)
00488       buff.write(struct.pack('<I%ss'%length, length, _x))
00489       buff.write(_struct_B.pack(self.action_result.status.status))
00490       _x = self.action_result.status.text
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_3I.pack(_x.action_result.result.door.header.seq, _x.action_result.result.door.header.stamp.secs, _x.action_result.result.door.header.stamp.nsecs))
00498       _x = self.action_result.result.door.header.frame_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_16f3i3df3I.pack(_x.action_result.result.door.frame_p1.x, _x.action_result.result.door.frame_p1.y, _x.action_result.result.door.frame_p1.z, _x.action_result.result.door.frame_p2.x, _x.action_result.result.door.frame_p2.y, _x.action_result.result.door.frame_p2.z, _x.action_result.result.door.door_p1.x, _x.action_result.result.door.door_p1.y, _x.action_result.result.door.door_p1.z, _x.action_result.result.door.door_p2.x, _x.action_result.result.door.door_p2.y, _x.action_result.result.door.door_p2.z, _x.action_result.result.door.handle.x, _x.action_result.result.door.handle.y, _x.action_result.result.door.handle.z, _x.action_result.result.door.height, _x.action_result.result.door.hinge, _x.action_result.result.door.rot_dir, _x.action_result.result.door.latch_state, _x.action_result.result.door.travel_dir.x, _x.action_result.result.door.travel_dir.y, _x.action_result.result.door.travel_dir.z, _x.action_result.result.door.weight, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00506       _x = self.action_feedback.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_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00514       _x = self.action_feedback.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_feedback.status.status))
00521       _x = self.action_feedback.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     except struct.error as se: self._check_types(se)
00528     except TypeError as te: self._check_types(te)
00529 
00530   def deserialize_numpy(self, str, numpy):
00531     """
00532     unpack serialized message in str into this message instance using numpy for array types
00533     :param str: byte array of serialized message, ``str``
00534     :param numpy: numpy python module
00535     """
00536     try:
00537       if self.action_goal is None:
00538         self.action_goal = door_msgs.msg.DoorActionGoal()
00539       if self.action_result is None:
00540         self.action_result = door_msgs.msg.DoorActionResult()
00541       if self.action_feedback is None:
00542         self.action_feedback = door_msgs.msg.DoorActionFeedback()
00543       end = 0
00544       _x = self
00545       start = end
00546       end += 12
00547       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00548       start = end
00549       end += 4
00550       (length,) = _struct_I.unpack(str[start:end])
00551       start = end
00552       end += length
00553       if python3:
00554         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00555       else:
00556         self.action_goal.header.frame_id = str[start:end]
00557       _x = self
00558       start = end
00559       end += 8
00560       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00561       start = end
00562       end += 4
00563       (length,) = _struct_I.unpack(str[start:end])
00564       start = end
00565       end += length
00566       if python3:
00567         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00568       else:
00569         self.action_goal.goal_id.id = str[start:end]
00570       _x = self
00571       start = end
00572       end += 12
00573       (_x.action_goal.goal.door.header.seq, _x.action_goal.goal.door.header.stamp.secs, _x.action_goal.goal.door.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00574       start = end
00575       end += 4
00576       (length,) = _struct_I.unpack(str[start:end])
00577       start = end
00578       end += length
00579       if python3:
00580         self.action_goal.goal.door.header.frame_id = str[start:end].decode('utf-8')
00581       else:
00582         self.action_goal.goal.door.header.frame_id = str[start:end]
00583       _x = self
00584       start = end
00585       end += 116
00586       (_x.action_goal.goal.door.frame_p1.x, _x.action_goal.goal.door.frame_p1.y, _x.action_goal.goal.door.frame_p1.z, _x.action_goal.goal.door.frame_p2.x, _x.action_goal.goal.door.frame_p2.y, _x.action_goal.goal.door.frame_p2.z, _x.action_goal.goal.door.door_p1.x, _x.action_goal.goal.door.door_p1.y, _x.action_goal.goal.door.door_p1.z, _x.action_goal.goal.door.door_p2.x, _x.action_goal.goal.door.door_p2.y, _x.action_goal.goal.door.door_p2.z, _x.action_goal.goal.door.handle.x, _x.action_goal.goal.door.handle.y, _x.action_goal.goal.door.handle.z, _x.action_goal.goal.door.height, _x.action_goal.goal.door.hinge, _x.action_goal.goal.door.rot_dir, _x.action_goal.goal.door.latch_state, _x.action_goal.goal.door.travel_dir.x, _x.action_goal.goal.door.travel_dir.y, _x.action_goal.goal.door.travel_dir.z, _x.action_goal.goal.door.weight, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_16f3i3df3I.unpack(str[start:end])
00587       start = end
00588       end += 4
00589       (length,) = _struct_I.unpack(str[start:end])
00590       start = end
00591       end += length
00592       if python3:
00593         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00594       else:
00595         self.action_result.header.frame_id = str[start:end]
00596       _x = self
00597       start = end
00598       end += 8
00599       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00600       start = end
00601       end += 4
00602       (length,) = _struct_I.unpack(str[start:end])
00603       start = end
00604       end += length
00605       if python3:
00606         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00607       else:
00608         self.action_result.status.goal_id.id = str[start:end]
00609       start = end
00610       end += 1
00611       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00612       start = end
00613       end += 4
00614       (length,) = _struct_I.unpack(str[start:end])
00615       start = end
00616       end += length
00617       if python3:
00618         self.action_result.status.text = str[start:end].decode('utf-8')
00619       else:
00620         self.action_result.status.text = str[start:end]
00621       _x = self
00622       start = end
00623       end += 12
00624       (_x.action_result.result.door.header.seq, _x.action_result.result.door.header.stamp.secs, _x.action_result.result.door.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00625       start = end
00626       end += 4
00627       (length,) = _struct_I.unpack(str[start:end])
00628       start = end
00629       end += length
00630       if python3:
00631         self.action_result.result.door.header.frame_id = str[start:end].decode('utf-8')
00632       else:
00633         self.action_result.result.door.header.frame_id = str[start:end]
00634       _x = self
00635       start = end
00636       end += 116
00637       (_x.action_result.result.door.frame_p1.x, _x.action_result.result.door.frame_p1.y, _x.action_result.result.door.frame_p1.z, _x.action_result.result.door.frame_p2.x, _x.action_result.result.door.frame_p2.y, _x.action_result.result.door.frame_p2.z, _x.action_result.result.door.door_p1.x, _x.action_result.result.door.door_p1.y, _x.action_result.result.door.door_p1.z, _x.action_result.result.door.door_p2.x, _x.action_result.result.door.door_p2.y, _x.action_result.result.door.door_p2.z, _x.action_result.result.door.handle.x, _x.action_result.result.door.handle.y, _x.action_result.result.door.handle.z, _x.action_result.result.door.height, _x.action_result.result.door.hinge, _x.action_result.result.door.rot_dir, _x.action_result.result.door.latch_state, _x.action_result.result.door.travel_dir.x, _x.action_result.result.door.travel_dir.y, _x.action_result.result.door.travel_dir.z, _x.action_result.result.door.weight, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_16f3i3df3I.unpack(str[start:end])
00638       start = end
00639       end += 4
00640       (length,) = _struct_I.unpack(str[start:end])
00641       start = end
00642       end += length
00643       if python3:
00644         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00645       else:
00646         self.action_feedback.header.frame_id = str[start:end]
00647       _x = self
00648       start = end
00649       end += 8
00650       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00651       start = end
00652       end += 4
00653       (length,) = _struct_I.unpack(str[start:end])
00654       start = end
00655       end += length
00656       if python3:
00657         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00658       else:
00659         self.action_feedback.status.goal_id.id = str[start:end]
00660       start = end
00661       end += 1
00662       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00663       start = end
00664       end += 4
00665       (length,) = _struct_I.unpack(str[start:end])
00666       start = end
00667       end += length
00668       if python3:
00669         self.action_feedback.status.text = str[start:end].decode('utf-8')
00670       else:
00671         self.action_feedback.status.text = str[start:end]
00672       return self
00673     except struct.error as e:
00674       raise genpy.DeserializationError(e) #most likely buffer underfill
00675 
00676 _struct_I = genpy.struct_I
00677 _struct_3I = struct.Struct("<3I")
00678 _struct_B = struct.Struct("<B")
00679 _struct_16f3i3df3I = struct.Struct("<16f3i3df3I")
00680 _struct_2I = struct.Struct("<2I")


door_msgs
Author(s): Wim Meeussen
autogenerated on Wed Dec 11 2013 14:16:35