00001 """autogenerated by genmsg_py from DatabaseModelPoseList.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import std_msgs.msg
00006 import geometry_msgs.msg
00007 import household_objects_database_msgs.msg
00008
00009 class DatabaseModelPoseList(roslib.message.Message):
00010 _md5sum = "b6da97866be6263e3b2145e8cee8ebaf"
00011 _type = "household_objects_database_msgs/DatabaseModelPoseList"
00012 _has_header = False
00013 _full_text = """# stores a list of possible database models recognition results
00014 DatabaseModelPose[] model_list
00015 ================================================================================
00016 MSG: household_objects_database_msgs/DatabaseModelPose
00017 # Informs that a specific model from the Model Database has been
00018 # identified at a certain location
00019
00020 # the database id of the model
00021 int32 model_id
00022
00023 # the pose that it can be found in
00024 geometry_msgs/PoseStamped pose
00025
00026 # a measure of the confidence level in this detection result
00027 float32 confidence
00028 ================================================================================
00029 MSG: geometry_msgs/PoseStamped
00030 # A Pose with reference coordinate frame and timestamp
00031 Header header
00032 Pose pose
00033
00034 ================================================================================
00035 MSG: std_msgs/Header
00036 # Standard metadata for higher-level stamped data types.
00037 # This is generally used to communicate timestamped data
00038 # in a particular coordinate frame.
00039 #
00040 # sequence ID: consecutively increasing ID
00041 uint32 seq
00042 #Two-integer timestamp that is expressed as:
00043 # * stamp.secs: seconds (stamp_secs) since epoch
00044 # * stamp.nsecs: nanoseconds since stamp_secs
00045 # time-handling sugar is provided by the client library
00046 time stamp
00047 #Frame this data is associated with
00048 # 0: no frame
00049 # 1: global frame
00050 string frame_id
00051
00052 ================================================================================
00053 MSG: geometry_msgs/Pose
00054 # A representation of pose in free space, composed of postion and orientation.
00055 Point position
00056 Quaternion orientation
00057
00058 ================================================================================
00059 MSG: geometry_msgs/Point
00060 # This contains the position of a point in free space
00061 float64 x
00062 float64 y
00063 float64 z
00064
00065 ================================================================================
00066 MSG: geometry_msgs/Quaternion
00067 # This represents an orientation in free space in quaternion form.
00068
00069 float64 x
00070 float64 y
00071 float64 z
00072 float64 w
00073
00074 """
00075 __slots__ = ['model_list']
00076 _slot_types = ['household_objects_database_msgs/DatabaseModelPose[]']
00077
00078 def __init__(self, *args, **kwds):
00079 """
00080 Constructor. Any message fields that are implicitly/explicitly
00081 set to None will be assigned a default value. The recommend
00082 use is keyword arguments as this is more robust to future message
00083 changes. You cannot mix in-order arguments and keyword arguments.
00084
00085 The available fields are:
00086 model_list
00087
00088 @param args: complete set of field values, in .msg order
00089 @param kwds: use keyword arguments corresponding to message field names
00090 to set specific fields.
00091 """
00092 if args or kwds:
00093 super(DatabaseModelPoseList, self).__init__(*args, **kwds)
00094
00095 if self.model_list is None:
00096 self.model_list = []
00097 else:
00098 self.model_list = []
00099
00100 def _get_types(self):
00101 """
00102 internal API method
00103 """
00104 return self._slot_types
00105
00106 def serialize(self, buff):
00107 """
00108 serialize message into buffer
00109 @param buff: buffer
00110 @type buff: StringIO
00111 """
00112 try:
00113 length = len(self.model_list)
00114 buff.write(_struct_I.pack(length))
00115 for val1 in self.model_list:
00116 buff.write(_struct_i.pack(val1.model_id))
00117 _v1 = val1.pose
00118 _v2 = _v1.header
00119 buff.write(_struct_I.pack(_v2.seq))
00120 _v3 = _v2.stamp
00121 _x = _v3
00122 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00123 _x = _v2.frame_id
00124 length = len(_x)
00125 buff.write(struct.pack('<I%ss'%length, length, _x))
00126 _v4 = _v1.pose
00127 _v5 = _v4.position
00128 _x = _v5
00129 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00130 _v6 = _v4.orientation
00131 _x = _v6
00132 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00133 buff.write(_struct_f.pack(val1.confidence))
00134 except struct.error, se: self._check_types(se)
00135 except TypeError, te: self._check_types(te)
00136
00137 def deserialize(self, str):
00138 """
00139 unpack serialized message in str into this message instance
00140 @param str: byte array of serialized message
00141 @type str: str
00142 """
00143 try:
00144 end = 0
00145 start = end
00146 end += 4
00147 (length,) = _struct_I.unpack(str[start:end])
00148 self.model_list = []
00149 for i in xrange(0, length):
00150 val1 = household_objects_database_msgs.msg.DatabaseModelPose()
00151 start = end
00152 end += 4
00153 (val1.model_id,) = _struct_i.unpack(str[start:end])
00154 _v7 = val1.pose
00155 _v8 = _v7.header
00156 start = end
00157 end += 4
00158 (_v8.seq,) = _struct_I.unpack(str[start:end])
00159 _v9 = _v8.stamp
00160 _x = _v9
00161 start = end
00162 end += 8
00163 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00164 start = end
00165 end += 4
00166 (length,) = _struct_I.unpack(str[start:end])
00167 start = end
00168 end += length
00169 _v8.frame_id = str[start:end]
00170 _v10 = _v7.pose
00171 _v11 = _v10.position
00172 _x = _v11
00173 start = end
00174 end += 24
00175 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00176 _v12 = _v10.orientation
00177 _x = _v12
00178 start = end
00179 end += 32
00180 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00181 start = end
00182 end += 4
00183 (val1.confidence,) = _struct_f.unpack(str[start:end])
00184 self.model_list.append(val1)
00185 return self
00186 except struct.error, e:
00187 raise roslib.message.DeserializationError(e)
00188
00189
00190 def serialize_numpy(self, buff, numpy):
00191 """
00192 serialize message with numpy array types into buffer
00193 @param buff: buffer
00194 @type buff: StringIO
00195 @param numpy: numpy python module
00196 @type numpy module
00197 """
00198 try:
00199 length = len(self.model_list)
00200 buff.write(_struct_I.pack(length))
00201 for val1 in self.model_list:
00202 buff.write(_struct_i.pack(val1.model_id))
00203 _v13 = val1.pose
00204 _v14 = _v13.header
00205 buff.write(_struct_I.pack(_v14.seq))
00206 _v15 = _v14.stamp
00207 _x = _v15
00208 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00209 _x = _v14.frame_id
00210 length = len(_x)
00211 buff.write(struct.pack('<I%ss'%length, length, _x))
00212 _v16 = _v13.pose
00213 _v17 = _v16.position
00214 _x = _v17
00215 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00216 _v18 = _v16.orientation
00217 _x = _v18
00218 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00219 buff.write(_struct_f.pack(val1.confidence))
00220 except struct.error, se: self._check_types(se)
00221 except TypeError, te: self._check_types(te)
00222
00223 def deserialize_numpy(self, str, numpy):
00224 """
00225 unpack serialized message in str into this message instance using numpy for array types
00226 @param str: byte array of serialized message
00227 @type str: str
00228 @param numpy: numpy python module
00229 @type numpy: module
00230 """
00231 try:
00232 end = 0
00233 start = end
00234 end += 4
00235 (length,) = _struct_I.unpack(str[start:end])
00236 self.model_list = []
00237 for i in xrange(0, length):
00238 val1 = household_objects_database_msgs.msg.DatabaseModelPose()
00239 start = end
00240 end += 4
00241 (val1.model_id,) = _struct_i.unpack(str[start:end])
00242 _v19 = val1.pose
00243 _v20 = _v19.header
00244 start = end
00245 end += 4
00246 (_v20.seq,) = _struct_I.unpack(str[start:end])
00247 _v21 = _v20.stamp
00248 _x = _v21
00249 start = end
00250 end += 8
00251 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00252 start = end
00253 end += 4
00254 (length,) = _struct_I.unpack(str[start:end])
00255 start = end
00256 end += length
00257 _v20.frame_id = str[start:end]
00258 _v22 = _v19.pose
00259 _v23 = _v22.position
00260 _x = _v23
00261 start = end
00262 end += 24
00263 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00264 _v24 = _v22.orientation
00265 _x = _v24
00266 start = end
00267 end += 32
00268 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00269 start = end
00270 end += 4
00271 (val1.confidence,) = _struct_f.unpack(str[start:end])
00272 self.model_list.append(val1)
00273 return self
00274 except struct.error, e:
00275 raise roslib.message.DeserializationError(e)
00276
00277 _struct_I = roslib.message.struct_I
00278 _struct_f = struct.Struct("<f")
00279 _struct_i = struct.Struct("<i")
00280 _struct_4d = struct.Struct("<4d")
00281 _struct_2I = struct.Struct("<2I")
00282 _struct_3d = struct.Struct("<3d")