00001 """autogenerated by genmsg_py from DoorAction.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import std_msgs.msg
00007 import roslib.rostime
00008 import actionlib_msgs.msg
00009 import door_msgs.msg
00010
00011 class DoorAction(roslib.message.Message):
00012 _md5sum = "09daec85681f57839e2a9dcef0a9b828"
00013 _type = "door_msgs/DoorAction"
00014 _has_header = False
00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00016
00017 DoorActionGoal action_goal
00018 DoorActionResult action_result
00019 DoorActionFeedback action_feedback
00020
00021 ================================================================================
00022 MSG: door_msgs/DoorActionGoal
00023 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00024
00025 Header header
00026 actionlib_msgs/GoalID goal_id
00027 DoorGoal goal
00028
00029 ================================================================================
00030 MSG: std_msgs/Header
00031 # Standard metadata for higher-level stamped data types.
00032 # This is generally used to communicate timestamped data
00033 # in a particular coordinate frame.
00034 #
00035 # sequence ID: consecutively increasing ID
00036 uint32 seq
00037 #Two-integer timestamp that is expressed as:
00038 # * stamp.secs: seconds (stamp_secs) since epoch
00039 # * stamp.nsecs: nanoseconds since stamp_secs
00040 # time-handling sugar is provided by the client library
00041 time stamp
00042 #Frame this data is associated with
00043 # 0: no frame
00044 # 1: global frame
00045 string frame_id
00046
00047 ================================================================================
00048 MSG: actionlib_msgs/GoalID
00049 # The stamp should store the time at which this goal was requested.
00050 # It is used by an action server when it tries to preempt all
00051 # goals that were requested before a certain time
00052 time stamp
00053
00054 # The id provides a way to associate feedback and
00055 # result message with specific goal requests. The id
00056 # specified must be unique.
00057 string id
00058
00059
00060 ================================================================================
00061 MSG: door_msgs/DoorGoal
00062 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00063 # goal
00064 door_msgs/Door door
00065
00066 ================================================================================
00067 MSG: door_msgs/Door
00068 Header header
00069 geometry_msgs/Point32 frame_p1 ## position of the door frame
00070 geometry_msgs/Point32 frame_p2 ## position of the door frame
00071 geometry_msgs/Point32 door_p1 ## Ground plane projection of a point on the plane of the door
00072 geometry_msgs/Point32 door_p2 ## Ground plane projection of a point on the plane of the door
00073 geometry_msgs/Point32 handle ## Position of the door handle
00074 float32 height ## Height of the door
00075
00076 int32 UNKNOWN=0
00077
00078 int32 HINGE_P1=1
00079 int32 HINGE_P2=2
00080 int32 hinge
00081
00082 int32 ROT_DIR_CLOCKWISE=1
00083 int32 ROT_DIR_COUNTERCLOCKWISE=2
00084 int32 rot_dir
00085
00086 int32 LOCKED=1
00087 int32 LATCHED=2
00088 int32 UNLATCHED=3
00089 int32 latch_state
00090
00091 geometry_msgs/Vector3 travel_dir ## vector pointing in the direction the robot is going to travel through the door
00092 float32 weight ## @Sachin: what do we use this for?
00093
00094
00095
00096 ================================================================================
00097 MSG: geometry_msgs/Point32
00098 # This contains the position of a point in free space(with 32 bits of precision).
00099 # It is recommeded to use Point wherever possible instead of Point32.
00100 #
00101 # This recommendation is to promote interoperability.
00102 #
00103 # This message is designed to take up less space when sending
00104 # lots of points at once, as in the case of a PointCloud.
00105
00106 float32 x
00107 float32 y
00108 float32 z
00109 ================================================================================
00110 MSG: geometry_msgs/Vector3
00111 # This represents a vector in free space.
00112
00113 float64 x
00114 float64 y
00115 float64 z
00116 ================================================================================
00117 MSG: door_msgs/DoorActionResult
00118 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00119
00120 Header header
00121 actionlib_msgs/GoalStatus status
00122 DoorResult result
00123
00124 ================================================================================
00125 MSG: actionlib_msgs/GoalStatus
00126 GoalID goal_id
00127 uint8 status
00128 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00129 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00130 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00131 # and has since completed its execution (Terminal State)
00132 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00133 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00134 # to some failure (Terminal State)
00135 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00136 # because the goal was unattainable or invalid (Terminal State)
00137 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00138 # and has not yet completed execution
00139 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00140 # but the action server has not yet confirmed that the goal is canceled
00141 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00142 # and was successfully cancelled (Terminal State)
00143 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00144 # sent over the wire by an action server
00145
00146 #Allow for the user to associate a string with GoalStatus for debugging
00147 string text
00148
00149
00150 ================================================================================
00151 MSG: door_msgs/DoorResult
00152 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00153 # result
00154 door_msgs/Door door
00155
00156 ================================================================================
00157 MSG: door_msgs/DoorActionFeedback
00158 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00159
00160 Header header
00161 actionlib_msgs/GoalStatus status
00162 DoorFeedback feedback
00163
00164 ================================================================================
00165 MSG: door_msgs/DoorFeedback
00166 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00167
00168
00169 """
00170 __slots__ = ['action_goal','action_result','action_feedback']
00171 _slot_types = ['door_msgs/DoorActionGoal','door_msgs/DoorActionResult','door_msgs/DoorActionFeedback']
00172
00173 def __init__(self, *args, **kwds):
00174 """
00175 Constructor. Any message fields that are implicitly/explicitly
00176 set to None will be assigned a default value. The recommend
00177 use is keyword arguments as this is more robust to future message
00178 changes. You cannot mix in-order arguments and keyword arguments.
00179
00180 The available fields are:
00181 action_goal,action_result,action_feedback
00182
00183 @param args: complete set of field values, in .msg order
00184 @param kwds: use keyword arguments corresponding to message field names
00185 to set specific fields.
00186 """
00187 if args or kwds:
00188 super(DoorAction, self).__init__(*args, **kwds)
00189
00190 if self.action_goal is None:
00191 self.action_goal = door_msgs.msg.DoorActionGoal()
00192 if self.action_result is None:
00193 self.action_result = door_msgs.msg.DoorActionResult()
00194 if self.action_feedback is None:
00195 self.action_feedback = door_msgs.msg.DoorActionFeedback()
00196 else:
00197 self.action_goal = door_msgs.msg.DoorActionGoal()
00198 self.action_result = door_msgs.msg.DoorActionResult()
00199 self.action_feedback = door_msgs.msg.DoorActionFeedback()
00200
00201 def _get_types(self):
00202 """
00203 internal API method
00204 """
00205 return self._slot_types
00206
00207 def serialize(self, buff):
00208 """
00209 serialize message into buffer
00210 @param buff: buffer
00211 @type buff: StringIO
00212 """
00213 try:
00214 _x = self
00215 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00216 _x = self.action_goal.header.frame_id
00217 length = len(_x)
00218 buff.write(struct.pack('<I%ss'%length, length, _x))
00219 _x = self
00220 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00221 _x = self.action_goal.goal_id.id
00222 length = len(_x)
00223 buff.write(struct.pack('<I%ss'%length, length, _x))
00224 _x = self
00225 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))
00226 _x = self.action_goal.goal.door.header.frame_id
00227 length = len(_x)
00228 buff.write(struct.pack('<I%ss'%length, length, _x))
00229 _x = self
00230 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))
00231 _x = self.action_result.header.frame_id
00232 length = len(_x)
00233 buff.write(struct.pack('<I%ss'%length, length, _x))
00234 _x = self
00235 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00236 _x = self.action_result.status.goal_id.id
00237 length = len(_x)
00238 buff.write(struct.pack('<I%ss'%length, length, _x))
00239 buff.write(_struct_B.pack(self.action_result.status.status))
00240 _x = self.action_result.status.text
00241 length = len(_x)
00242 buff.write(struct.pack('<I%ss'%length, length, _x))
00243 _x = self
00244 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))
00245 _x = self.action_result.result.door.header.frame_id
00246 length = len(_x)
00247 buff.write(struct.pack('<I%ss'%length, length, _x))
00248 _x = self
00249 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))
00250 _x = self.action_feedback.header.frame_id
00251 length = len(_x)
00252 buff.write(struct.pack('<I%ss'%length, length, _x))
00253 _x = self
00254 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00255 _x = self.action_feedback.status.goal_id.id
00256 length = len(_x)
00257 buff.write(struct.pack('<I%ss'%length, length, _x))
00258 buff.write(_struct_B.pack(self.action_feedback.status.status))
00259 _x = self.action_feedback.status.text
00260 length = len(_x)
00261 buff.write(struct.pack('<I%ss'%length, length, _x))
00262 except struct.error, se: self._check_types(se)
00263 except TypeError, te: self._check_types(te)
00264
00265 def deserialize(self, str):
00266 """
00267 unpack serialized message in str into this message instance
00268 @param str: byte array of serialized message
00269 @type str: str
00270 """
00271 try:
00272 if self.action_goal is None:
00273 self.action_goal = door_msgs.msg.DoorActionGoal()
00274 if self.action_result is None:
00275 self.action_result = door_msgs.msg.DoorActionResult()
00276 if self.action_feedback is None:
00277 self.action_feedback = door_msgs.msg.DoorActionFeedback()
00278 end = 0
00279 _x = self
00280 start = end
00281 end += 12
00282 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00283 start = end
00284 end += 4
00285 (length,) = _struct_I.unpack(str[start:end])
00286 start = end
00287 end += length
00288 self.action_goal.header.frame_id = str[start:end]
00289 _x = self
00290 start = end
00291 end += 8
00292 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00293 start = end
00294 end += 4
00295 (length,) = _struct_I.unpack(str[start:end])
00296 start = end
00297 end += length
00298 self.action_goal.goal_id.id = str[start:end]
00299 _x = self
00300 start = end
00301 end += 12
00302 (_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])
00303 start = end
00304 end += 4
00305 (length,) = _struct_I.unpack(str[start:end])
00306 start = end
00307 end += length
00308 self.action_goal.goal.door.header.frame_id = str[start:end]
00309 _x = self
00310 start = end
00311 end += 116
00312 (_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])
00313 start = end
00314 end += 4
00315 (length,) = _struct_I.unpack(str[start:end])
00316 start = end
00317 end += length
00318 self.action_result.header.frame_id = str[start:end]
00319 _x = self
00320 start = end
00321 end += 8
00322 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00323 start = end
00324 end += 4
00325 (length,) = _struct_I.unpack(str[start:end])
00326 start = end
00327 end += length
00328 self.action_result.status.goal_id.id = str[start:end]
00329 start = end
00330 end += 1
00331 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00332 start = end
00333 end += 4
00334 (length,) = _struct_I.unpack(str[start:end])
00335 start = end
00336 end += length
00337 self.action_result.status.text = str[start:end]
00338 _x = self
00339 start = end
00340 end += 12
00341 (_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])
00342 start = end
00343 end += 4
00344 (length,) = _struct_I.unpack(str[start:end])
00345 start = end
00346 end += length
00347 self.action_result.result.door.header.frame_id = str[start:end]
00348 _x = self
00349 start = end
00350 end += 116
00351 (_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])
00352 start = end
00353 end += 4
00354 (length,) = _struct_I.unpack(str[start:end])
00355 start = end
00356 end += length
00357 self.action_feedback.header.frame_id = str[start:end]
00358 _x = self
00359 start = end
00360 end += 8
00361 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00362 start = end
00363 end += 4
00364 (length,) = _struct_I.unpack(str[start:end])
00365 start = end
00366 end += length
00367 self.action_feedback.status.goal_id.id = str[start:end]
00368 start = end
00369 end += 1
00370 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00371 start = end
00372 end += 4
00373 (length,) = _struct_I.unpack(str[start:end])
00374 start = end
00375 end += length
00376 self.action_feedback.status.text = str[start:end]
00377 return self
00378 except struct.error, e:
00379 raise roslib.message.DeserializationError(e)
00380
00381
00382 def serialize_numpy(self, buff, numpy):
00383 """
00384 serialize message with numpy array types into buffer
00385 @param buff: buffer
00386 @type buff: StringIO
00387 @param numpy: numpy python module
00388 @type numpy module
00389 """
00390 try:
00391 _x = self
00392 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00393 _x = self.action_goal.header.frame_id
00394 length = len(_x)
00395 buff.write(struct.pack('<I%ss'%length, length, _x))
00396 _x = self
00397 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00398 _x = self.action_goal.goal_id.id
00399 length = len(_x)
00400 buff.write(struct.pack('<I%ss'%length, length, _x))
00401 _x = self
00402 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))
00403 _x = self.action_goal.goal.door.header.frame_id
00404 length = len(_x)
00405 buff.write(struct.pack('<I%ss'%length, length, _x))
00406 _x = self
00407 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))
00408 _x = self.action_result.header.frame_id
00409 length = len(_x)
00410 buff.write(struct.pack('<I%ss'%length, length, _x))
00411 _x = self
00412 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00413 _x = self.action_result.status.goal_id.id
00414 length = len(_x)
00415 buff.write(struct.pack('<I%ss'%length, length, _x))
00416 buff.write(_struct_B.pack(self.action_result.status.status))
00417 _x = self.action_result.status.text
00418 length = len(_x)
00419 buff.write(struct.pack('<I%ss'%length, length, _x))
00420 _x = self
00421 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))
00422 _x = self.action_result.result.door.header.frame_id
00423 length = len(_x)
00424 buff.write(struct.pack('<I%ss'%length, length, _x))
00425 _x = self
00426 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))
00427 _x = self.action_feedback.header.frame_id
00428 length = len(_x)
00429 buff.write(struct.pack('<I%ss'%length, length, _x))
00430 _x = self
00431 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00432 _x = self.action_feedback.status.goal_id.id
00433 length = len(_x)
00434 buff.write(struct.pack('<I%ss'%length, length, _x))
00435 buff.write(_struct_B.pack(self.action_feedback.status.status))
00436 _x = self.action_feedback.status.text
00437 length = len(_x)
00438 buff.write(struct.pack('<I%ss'%length, length, _x))
00439 except struct.error, se: self._check_types(se)
00440 except TypeError, te: self._check_types(te)
00441
00442 def deserialize_numpy(self, str, numpy):
00443 """
00444 unpack serialized message in str into this message instance using numpy for array types
00445 @param str: byte array of serialized message
00446 @type str: str
00447 @param numpy: numpy python module
00448 @type numpy: module
00449 """
00450 try:
00451 if self.action_goal is None:
00452 self.action_goal = door_msgs.msg.DoorActionGoal()
00453 if self.action_result is None:
00454 self.action_result = door_msgs.msg.DoorActionResult()
00455 if self.action_feedback is None:
00456 self.action_feedback = door_msgs.msg.DoorActionFeedback()
00457 end = 0
00458 _x = self
00459 start = end
00460 end += 12
00461 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00462 start = end
00463 end += 4
00464 (length,) = _struct_I.unpack(str[start:end])
00465 start = end
00466 end += length
00467 self.action_goal.header.frame_id = str[start:end]
00468 _x = self
00469 start = end
00470 end += 8
00471 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00472 start = end
00473 end += 4
00474 (length,) = _struct_I.unpack(str[start:end])
00475 start = end
00476 end += length
00477 self.action_goal.goal_id.id = str[start:end]
00478 _x = self
00479 start = end
00480 end += 12
00481 (_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])
00482 start = end
00483 end += 4
00484 (length,) = _struct_I.unpack(str[start:end])
00485 start = end
00486 end += length
00487 self.action_goal.goal.door.header.frame_id = str[start:end]
00488 _x = self
00489 start = end
00490 end += 116
00491 (_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])
00492 start = end
00493 end += 4
00494 (length,) = _struct_I.unpack(str[start:end])
00495 start = end
00496 end += length
00497 self.action_result.header.frame_id = str[start:end]
00498 _x = self
00499 start = end
00500 end += 8
00501 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00502 start = end
00503 end += 4
00504 (length,) = _struct_I.unpack(str[start:end])
00505 start = end
00506 end += length
00507 self.action_result.status.goal_id.id = str[start:end]
00508 start = end
00509 end += 1
00510 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00511 start = end
00512 end += 4
00513 (length,) = _struct_I.unpack(str[start:end])
00514 start = end
00515 end += length
00516 self.action_result.status.text = str[start:end]
00517 _x = self
00518 start = end
00519 end += 12
00520 (_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])
00521 start = end
00522 end += 4
00523 (length,) = _struct_I.unpack(str[start:end])
00524 start = end
00525 end += length
00526 self.action_result.result.door.header.frame_id = str[start:end]
00527 _x = self
00528 start = end
00529 end += 116
00530 (_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])
00531 start = end
00532 end += 4
00533 (length,) = _struct_I.unpack(str[start:end])
00534 start = end
00535 end += length
00536 self.action_feedback.header.frame_id = str[start:end]
00537 _x = self
00538 start = end
00539 end += 8
00540 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00541 start = end
00542 end += 4
00543 (length,) = _struct_I.unpack(str[start:end])
00544 start = end
00545 end += length
00546 self.action_feedback.status.goal_id.id = str[start:end]
00547 start = end
00548 end += 1
00549 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00550 start = end
00551 end += 4
00552 (length,) = _struct_I.unpack(str[start:end])
00553 start = end
00554 end += length
00555 self.action_feedback.status.text = str[start:end]
00556 return self
00557 except struct.error, e:
00558 raise roslib.message.DeserializationError(e)
00559
00560 _struct_I = roslib.message.struct_I
00561 _struct_3I = struct.Struct("<3I")
00562 _struct_B = struct.Struct("<B")
00563 _struct_16f3i3df3I = struct.Struct("<16f3i3df3I")
00564 _struct_2I = struct.Struct("<2I")