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