00001 """autogenerated by genmsg_py from DoorCmd.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 DoorCmd(roslib.message.Message):
00010 _md5sum = "5cc30e56a9970953e15b3f2cd05f9d0c"
00011 _type = "door_msgs/DoorCmd"
00012 _has_header = False
00013 _full_text = """door_msgs/Door door
00014 int32 side
00015 int32 PULL=0
00016 int32 PUSH=1
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
00087 PULL = 0
00088 PUSH = 1
00089
00090 __slots__ = ['door','side']
00091 _slot_types = ['door_msgs/Door','int32']
00092
00093 def __init__(self, *args, **kwds):
00094 """
00095 Constructor. Any message fields that are implicitly/explicitly
00096 set to None will be assigned a default value. The recommend
00097 use is keyword arguments as this is more robust to future message
00098 changes. You cannot mix in-order arguments and keyword arguments.
00099
00100 The available fields are:
00101 door,side
00102
00103 @param args: complete set of field values, in .msg order
00104 @param kwds: use keyword arguments corresponding to message field names
00105 to set specific fields.
00106 """
00107 if args or kwds:
00108 super(DoorCmd, self).__init__(*args, **kwds)
00109
00110 if self.door is None:
00111 self.door = door_msgs.msg.Door()
00112 if self.side is None:
00113 self.side = 0
00114 else:
00115 self.door = door_msgs.msg.Door()
00116 self.side = 0
00117
00118 def _get_types(self):
00119 """
00120 internal API method
00121 """
00122 return self._slot_types
00123
00124 def serialize(self, buff):
00125 """
00126 serialize message into buffer
00127 @param buff: buffer
00128 @type buff: StringIO
00129 """
00130 try:
00131 _x = self
00132 buff.write(_struct_3I.pack(_x.door.header.seq, _x.door.header.stamp.secs, _x.door.header.stamp.nsecs))
00133 _x = self.door.header.frame_id
00134 length = len(_x)
00135 buff.write(struct.pack('<I%ss'%length, length, _x))
00136 _x = self
00137 buff.write(_struct_16f3i3dfi.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, _x.side))
00138 except struct.error, se: self._check_types(se)
00139 except TypeError, te: self._check_types(te)
00140
00141 def deserialize(self, str):
00142 """
00143 unpack serialized message in str into this message instance
00144 @param str: byte array of serialized message
00145 @type str: str
00146 """
00147 try:
00148 if self.door is None:
00149 self.door = door_msgs.msg.Door()
00150 end = 0
00151 _x = self
00152 start = end
00153 end += 12
00154 (_x.door.header.seq, _x.door.header.stamp.secs, _x.door.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00155 start = end
00156 end += 4
00157 (length,) = _struct_I.unpack(str[start:end])
00158 start = end
00159 end += length
00160 self.door.header.frame_id = str[start:end]
00161 _x = self
00162 start = end
00163 end += 108
00164 (_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, _x.side,) = _struct_16f3i3dfi.unpack(str[start:end])
00165 return self
00166 except struct.error, e:
00167 raise roslib.message.DeserializationError(e)
00168
00169
00170 def serialize_numpy(self, buff, numpy):
00171 """
00172 serialize message with numpy array types into buffer
00173 @param buff: buffer
00174 @type buff: StringIO
00175 @param numpy: numpy python module
00176 @type numpy module
00177 """
00178 try:
00179 _x = self
00180 buff.write(_struct_3I.pack(_x.door.header.seq, _x.door.header.stamp.secs, _x.door.header.stamp.nsecs))
00181 _x = self.door.header.frame_id
00182 length = len(_x)
00183 buff.write(struct.pack('<I%ss'%length, length, _x))
00184 _x = self
00185 buff.write(_struct_16f3i3dfi.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, _x.side))
00186 except struct.error, se: self._check_types(se)
00187 except TypeError, te: self._check_types(te)
00188
00189 def deserialize_numpy(self, str, numpy):
00190 """
00191 unpack serialized message in str into this message instance using numpy for array types
00192 @param str: byte array of serialized message
00193 @type str: str
00194 @param numpy: numpy python module
00195 @type numpy: module
00196 """
00197 try:
00198 if self.door is None:
00199 self.door = door_msgs.msg.Door()
00200 end = 0
00201 _x = self
00202 start = end
00203 end += 12
00204 (_x.door.header.seq, _x.door.header.stamp.secs, _x.door.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00205 start = end
00206 end += 4
00207 (length,) = _struct_I.unpack(str[start:end])
00208 start = end
00209 end += length
00210 self.door.header.frame_id = str[start:end]
00211 _x = self
00212 start = end
00213 end += 108
00214 (_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, _x.side,) = _struct_16f3i3dfi.unpack(str[start:end])
00215 return self
00216 except struct.error, e:
00217 raise roslib.message.DeserializationError(e)
00218
00219 _struct_I = roslib.message.struct_I
00220 _struct_3I = struct.Struct("<3I")
00221 _struct_16f3i3dfi = struct.Struct("<16f3i3dfi")