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