00001 """autogenerated by genmsg_py from DoorResult.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import std_msgs.msg
00007 import door_msgs.msg
00008
00009 class DoorResult(roslib.message.Message):
00010 _md5sum = "72afb754afb6ff619fa1a692675498c0"
00011 _type = "door_msgs/DoorResult"
00012 _has_header = False
00013 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00014 # result
00015 door_msgs/Door door
00016
00017 ================================================================================
00018 MSG: door_msgs/Door
00019 Header header
00020 geometry_msgs/Point32 frame_p1 ## position of the door frame
00021 geometry_msgs/Point32 frame_p2 ## position of the door frame
00022 geometry_msgs/Point32 door_p1 ## Ground plane projection of a point on the plane of the door
00023 geometry_msgs/Point32 door_p2 ## Ground plane projection of a point on the plane of the door
00024 geometry_msgs/Point32 handle ## Position of the door handle
00025 float32 height ## Height of the door
00026
00027 int32 UNKNOWN=0
00028
00029 int32 HINGE_P1=1
00030 int32 HINGE_P2=2
00031 int32 hinge
00032
00033 int32 ROT_DIR_CLOCKWISE=1
00034 int32 ROT_DIR_COUNTERCLOCKWISE=2
00035 int32 rot_dir
00036
00037 int32 LOCKED=1
00038 int32 LATCHED=2
00039 int32 UNLATCHED=3
00040 int32 latch_state
00041
00042 geometry_msgs/Vector3 travel_dir ## vector pointing in the direction the robot is going to travel through the door
00043 float32 weight ## @Sachin: what do we use this for?
00044
00045
00046
00047 ================================================================================
00048 MSG: std_msgs/Header
00049 # Standard metadata for higher-level stamped data types.
00050 # This is generally used to communicate timestamped data
00051 # in a particular coordinate frame.
00052 #
00053 # sequence ID: consecutively increasing ID
00054 uint32 seq
00055 #Two-integer timestamp that is expressed as:
00056 # * stamp.secs: seconds (stamp_secs) since epoch
00057 # * stamp.nsecs: nanoseconds since stamp_secs
00058 # time-handling sugar is provided by the client library
00059 time stamp
00060 #Frame this data is associated with
00061 # 0: no frame
00062 # 1: global frame
00063 string frame_id
00064
00065 ================================================================================
00066 MSG: geometry_msgs/Point32
00067 # This contains the position of a point in free space(with 32 bits of precision).
00068 # It is recommeded to use Point wherever possible instead of Point32.
00069 #
00070 # This recommendation is to promote interoperability.
00071 #
00072 # This message is designed to take up less space when sending
00073 # lots of points at once, as in the case of a PointCloud.
00074
00075 float32 x
00076 float32 y
00077 float32 z
00078 ================================================================================
00079 MSG: geometry_msgs/Vector3
00080 # This represents a vector in free space.
00081
00082 float64 x
00083 float64 y
00084 float64 z
00085 """
00086 __slots__ = ['door']
00087 _slot_types = ['door_msgs/Door']
00088
00089 def __init__(self, *args, **kwds):
00090 """
00091 Constructor. Any message fields that are implicitly/explicitly
00092 set to None will be assigned a default value. The recommend
00093 use is keyword arguments as this is more robust to future message
00094 changes. You cannot mix in-order arguments and keyword arguments.
00095
00096 The available fields are:
00097 door
00098
00099 @param args: complete set of field values, in .msg order
00100 @param kwds: use keyword arguments corresponding to message field names
00101 to set specific fields.
00102 """
00103 if args or kwds:
00104 super(DoorResult, self).__init__(*args, **kwds)
00105
00106 if self.door is None:
00107 self.door = door_msgs.msg.Door()
00108 else:
00109 self.door = door_msgs.msg.Door()
00110
00111 def _get_types(self):
00112 """
00113 internal API method
00114 """
00115 return self._slot_types
00116
00117 def serialize(self, buff):
00118 """
00119 serialize message into buffer
00120 @param buff: buffer
00121 @type buff: StringIO
00122 """
00123 try:
00124 _x = self
00125 buff.write(_struct_3I.pack(_x.door.header.seq, _x.door.header.stamp.secs, _x.door.header.stamp.nsecs))
00126 _x = self.door.header.frame_id
00127 length = len(_x)
00128 buff.write(struct.pack('<I%ss'%length, length, _x))
00129 _x = self
00130 buff.write(_struct_16f3i3df.pack(_x.door.frame_p1.x, _x.door.frame_p1.y, _x.door.frame_p1.z, _x.door.frame_p2.x, _x.door.frame_p2.y, _x.door.frame_p2.z, _x.door.door_p1.x, _x.door.door_p1.y, _x.door.door_p1.z, _x.door.door_p2.x, _x.door.door_p2.y, _x.door.door_p2.z, _x.door.handle.x, _x.door.handle.y, _x.door.handle.z, _x.door.height, _x.door.hinge, _x.door.rot_dir, _x.door.latch_state, _x.door.travel_dir.x, _x.door.travel_dir.y, _x.door.travel_dir.z, _x.door.weight))
00131 except struct.error, se: self._check_types(se)
00132 except TypeError, te: self._check_types(te)
00133
00134 def deserialize(self, str):
00135 """
00136 unpack serialized message in str into this message instance
00137 @param str: byte array of serialized message
00138 @type str: str
00139 """
00140 try:
00141 if self.door is None:
00142 self.door = door_msgs.msg.Door()
00143 end = 0
00144 _x = self
00145 start = end
00146 end += 12
00147 (_x.door.header.seq, _x.door.header.stamp.secs, _x.door.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00148 start = end
00149 end += 4
00150 (length,) = _struct_I.unpack(str[start:end])
00151 start = end
00152 end += length
00153 self.door.header.frame_id = str[start:end]
00154 _x = self
00155 start = end
00156 end += 104
00157 (_x.door.frame_p1.x, _x.door.frame_p1.y, _x.door.frame_p1.z, _x.door.frame_p2.x, _x.door.frame_p2.y, _x.door.frame_p2.z, _x.door.door_p1.x, _x.door.door_p1.y, _x.door.door_p1.z, _x.door.door_p2.x, _x.door.door_p2.y, _x.door.door_p2.z, _x.door.handle.x, _x.door.handle.y, _x.door.handle.z, _x.door.height, _x.door.hinge, _x.door.rot_dir, _x.door.latch_state, _x.door.travel_dir.x, _x.door.travel_dir.y, _x.door.travel_dir.z, _x.door.weight,) = _struct_16f3i3df.unpack(str[start:end])
00158 return self
00159 except struct.error, e:
00160 raise roslib.message.DeserializationError(e)
00161
00162
00163 def serialize_numpy(self, buff, numpy):
00164 """
00165 serialize message with numpy array types into buffer
00166 @param buff: buffer
00167 @type buff: StringIO
00168 @param numpy: numpy python module
00169 @type numpy module
00170 """
00171 try:
00172 _x = self
00173 buff.write(_struct_3I.pack(_x.door.header.seq, _x.door.header.stamp.secs, _x.door.header.stamp.nsecs))
00174 _x = self.door.header.frame_id
00175 length = len(_x)
00176 buff.write(struct.pack('<I%ss'%length, length, _x))
00177 _x = self
00178 buff.write(_struct_16f3i3df.pack(_x.door.frame_p1.x, _x.door.frame_p1.y, _x.door.frame_p1.z, _x.door.frame_p2.x, _x.door.frame_p2.y, _x.door.frame_p2.z, _x.door.door_p1.x, _x.door.door_p1.y, _x.door.door_p1.z, _x.door.door_p2.x, _x.door.door_p2.y, _x.door.door_p2.z, _x.door.handle.x, _x.door.handle.y, _x.door.handle.z, _x.door.height, _x.door.hinge, _x.door.rot_dir, _x.door.latch_state, _x.door.travel_dir.x, _x.door.travel_dir.y, _x.door.travel_dir.z, _x.door.weight))
00179 except struct.error, se: self._check_types(se)
00180 except TypeError, te: self._check_types(te)
00181
00182 def deserialize_numpy(self, str, numpy):
00183 """
00184 unpack serialized message in str into this message instance using numpy for array types
00185 @param str: byte array of serialized message
00186 @type str: str
00187 @param numpy: numpy python module
00188 @type numpy: module
00189 """
00190 try:
00191 if self.door is None:
00192 self.door = door_msgs.msg.Door()
00193 end = 0
00194 _x = self
00195 start = end
00196 end += 12
00197 (_x.door.header.seq, _x.door.header.stamp.secs, _x.door.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00198 start = end
00199 end += 4
00200 (length,) = _struct_I.unpack(str[start:end])
00201 start = end
00202 end += length
00203 self.door.header.frame_id = str[start:end]
00204 _x = self
00205 start = end
00206 end += 104
00207 (_x.door.frame_p1.x, _x.door.frame_p1.y, _x.door.frame_p1.z, _x.door.frame_p2.x, _x.door.frame_p2.y, _x.door.frame_p2.z, _x.door.door_p1.x, _x.door.door_p1.y, _x.door.door_p1.z, _x.door.door_p2.x, _x.door.door_p2.y, _x.door.door_p2.z, _x.door.handle.x, _x.door.handle.y, _x.door.handle.z, _x.door.height, _x.door.hinge, _x.door.rot_dir, _x.door.latch_state, _x.door.travel_dir.x, _x.door.travel_dir.y, _x.door.travel_dir.z, _x.door.weight,) = _struct_16f3i3df.unpack(str[start:end])
00208 return self
00209 except struct.error, e:
00210 raise roslib.message.DeserializationError(e)
00211
00212 _struct_I = roslib.message.struct_I
00213 _struct_3I = struct.Struct("<3I")
00214 _struct_16f3i3df = struct.Struct("<16f3i3df")