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