$search
00001 """autogenerated by genmsg_py from ModelHypothesis.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import arm_navigation_msgs.msg 00006 import geometry_msgs.msg 00007 import std_msgs.msg 00008 00009 class ModelHypothesis(roslib.message.Message): 00010 _md5sum = "4fbf66f058abb32b34d3bbb399568762" 00011 _type = "object_recognition_gui/ModelHypothesis" 00012 _has_header = False #flag to mark the presence of a Header object 00013 _full_text = """#describes a hypothesis about a recognized object (mesh+pose) 00014 00015 arm_navigation_msgs/Shape mesh 00016 geometry_msgs/PoseStamped pose 00017 00018 ================================================================================ 00019 MSG: arm_navigation_msgs/Shape 00020 byte SPHERE=0 00021 byte BOX=1 00022 byte CYLINDER=2 00023 byte MESH=3 00024 00025 byte type 00026 00027 00028 #### define sphere, box, cylinder #### 00029 # the origin of each shape is considered at the shape's center 00030 00031 # for sphere 00032 # radius := dimensions[0] 00033 00034 # for cylinder 00035 # radius := dimensions[0] 00036 # length := dimensions[1] 00037 # the length is along the Z axis 00038 00039 # for box 00040 # size_x := dimensions[0] 00041 # size_y := dimensions[1] 00042 # size_z := dimensions[2] 00043 float64[] dimensions 00044 00045 00046 #### define mesh #### 00047 00048 # list of triangles; triangle k is defined by tre vertices located 00049 # at indices triangles[3k], triangles[3k+1], triangles[3k+2] 00050 int32[] triangles 00051 geometry_msgs/Point[] vertices 00052 00053 ================================================================================ 00054 MSG: geometry_msgs/Point 00055 # This contains the position of a point in free space 00056 float64 x 00057 float64 y 00058 float64 z 00059 00060 ================================================================================ 00061 MSG: geometry_msgs/PoseStamped 00062 # A Pose with reference coordinate frame and timestamp 00063 Header header 00064 Pose pose 00065 00066 ================================================================================ 00067 MSG: std_msgs/Header 00068 # Standard metadata for higher-level stamped data types. 00069 # This is generally used to communicate timestamped data 00070 # in a particular coordinate frame. 00071 # 00072 # sequence ID: consecutively increasing ID 00073 uint32 seq 00074 #Two-integer timestamp that is expressed as: 00075 # * stamp.secs: seconds (stamp_secs) since epoch 00076 # * stamp.nsecs: nanoseconds since stamp_secs 00077 # time-handling sugar is provided by the client library 00078 time stamp 00079 #Frame this data is associated with 00080 # 0: no frame 00081 # 1: global frame 00082 string frame_id 00083 00084 ================================================================================ 00085 MSG: geometry_msgs/Pose 00086 # A representation of pose in free space, composed of postion and orientation. 00087 Point position 00088 Quaternion orientation 00089 00090 ================================================================================ 00091 MSG: geometry_msgs/Quaternion 00092 # This represents an orientation in free space in quaternion form. 00093 00094 float64 x 00095 float64 y 00096 float64 z 00097 float64 w 00098 00099 """ 00100 __slots__ = ['mesh','pose'] 00101 _slot_types = ['arm_navigation_msgs/Shape','geometry_msgs/PoseStamped'] 00102 00103 def __init__(self, *args, **kwds): 00104 """ 00105 Constructor. Any message fields that are implicitly/explicitly 00106 set to None will be assigned a default value. The recommend 00107 use is keyword arguments as this is more robust to future message 00108 changes. You cannot mix in-order arguments and keyword arguments. 00109 00110 The available fields are: 00111 mesh,pose 00112 00113 @param args: complete set of field values, in .msg order 00114 @param kwds: use keyword arguments corresponding to message field names 00115 to set specific fields. 00116 """ 00117 if args or kwds: 00118 super(ModelHypothesis, self).__init__(*args, **kwds) 00119 #message fields cannot be None, assign default values for those that are 00120 if self.mesh is None: 00121 self.mesh = arm_navigation_msgs.msg.Shape() 00122 if self.pose is None: 00123 self.pose = geometry_msgs.msg.PoseStamped() 00124 else: 00125 self.mesh = arm_navigation_msgs.msg.Shape() 00126 self.pose = geometry_msgs.msg.PoseStamped() 00127 00128 def _get_types(self): 00129 """ 00130 internal API method 00131 """ 00132 return self._slot_types 00133 00134 def serialize(self, buff): 00135 """ 00136 serialize message into buffer 00137 @param buff: buffer 00138 @type buff: StringIO 00139 """ 00140 try: 00141 buff.write(_struct_b.pack(self.mesh.type)) 00142 length = len(self.mesh.dimensions) 00143 buff.write(_struct_I.pack(length)) 00144 pattern = '<%sd'%length 00145 buff.write(struct.pack(pattern, *self.mesh.dimensions)) 00146 length = len(self.mesh.triangles) 00147 buff.write(_struct_I.pack(length)) 00148 pattern = '<%si'%length 00149 buff.write(struct.pack(pattern, *self.mesh.triangles)) 00150 length = len(self.mesh.vertices) 00151 buff.write(_struct_I.pack(length)) 00152 for val1 in self.mesh.vertices: 00153 _x = val1 00154 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00155 _x = self 00156 buff.write(_struct_3I.pack(_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs)) 00157 _x = self.pose.header.frame_id 00158 length = len(_x) 00159 buff.write(struct.pack('<I%ss'%length, length, _x)) 00160 _x = self 00161 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)) 00162 except struct.error as se: self._check_types(se) 00163 except TypeError as te: self._check_types(te) 00164 00165 def deserialize(self, str): 00166 """ 00167 unpack serialized message in str into this message instance 00168 @param str: byte array of serialized message 00169 @type str: str 00170 """ 00171 try: 00172 if self.mesh is None: 00173 self.mesh = arm_navigation_msgs.msg.Shape() 00174 if self.pose is None: 00175 self.pose = geometry_msgs.msg.PoseStamped() 00176 end = 0 00177 start = end 00178 end += 1 00179 (self.mesh.type,) = _struct_b.unpack(str[start:end]) 00180 start = end 00181 end += 4 00182 (length,) = _struct_I.unpack(str[start:end]) 00183 pattern = '<%sd'%length 00184 start = end 00185 end += struct.calcsize(pattern) 00186 self.mesh.dimensions = struct.unpack(pattern, str[start:end]) 00187 start = end 00188 end += 4 00189 (length,) = _struct_I.unpack(str[start:end]) 00190 pattern = '<%si'%length 00191 start = end 00192 end += struct.calcsize(pattern) 00193 self.mesh.triangles = struct.unpack(pattern, str[start:end]) 00194 start = end 00195 end += 4 00196 (length,) = _struct_I.unpack(str[start:end]) 00197 self.mesh.vertices = [] 00198 for i in range(0, length): 00199 val1 = geometry_msgs.msg.Point() 00200 _x = val1 00201 start = end 00202 end += 24 00203 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00204 self.mesh.vertices.append(val1) 00205 _x = self 00206 start = end 00207 end += 12 00208 (_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00209 start = end 00210 end += 4 00211 (length,) = _struct_I.unpack(str[start:end]) 00212 start = end 00213 end += length 00214 self.pose.header.frame_id = str[start:end] 00215 _x = self 00216 start = end 00217 end += 56 00218 (_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]) 00219 return self 00220 except struct.error as e: 00221 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00222 00223 00224 def serialize_numpy(self, buff, numpy): 00225 """ 00226 serialize message with numpy array types into buffer 00227 @param buff: buffer 00228 @type buff: StringIO 00229 @param numpy: numpy python module 00230 @type numpy module 00231 """ 00232 try: 00233 buff.write(_struct_b.pack(self.mesh.type)) 00234 length = len(self.mesh.dimensions) 00235 buff.write(_struct_I.pack(length)) 00236 pattern = '<%sd'%length 00237 buff.write(self.mesh.dimensions.tostring()) 00238 length = len(self.mesh.triangles) 00239 buff.write(_struct_I.pack(length)) 00240 pattern = '<%si'%length 00241 buff.write(self.mesh.triangles.tostring()) 00242 length = len(self.mesh.vertices) 00243 buff.write(_struct_I.pack(length)) 00244 for val1 in self.mesh.vertices: 00245 _x = val1 00246 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00247 _x = self 00248 buff.write(_struct_3I.pack(_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs)) 00249 _x = self.pose.header.frame_id 00250 length = len(_x) 00251 buff.write(struct.pack('<I%ss'%length, length, _x)) 00252 _x = self 00253 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)) 00254 except struct.error as se: self._check_types(se) 00255 except TypeError as te: self._check_types(te) 00256 00257 def deserialize_numpy(self, str, numpy): 00258 """ 00259 unpack serialized message in str into this message instance using numpy for array types 00260 @param str: byte array of serialized message 00261 @type str: str 00262 @param numpy: numpy python module 00263 @type numpy: module 00264 """ 00265 try: 00266 if self.mesh is None: 00267 self.mesh = arm_navigation_msgs.msg.Shape() 00268 if self.pose is None: 00269 self.pose = geometry_msgs.msg.PoseStamped() 00270 end = 0 00271 start = end 00272 end += 1 00273 (self.mesh.type,) = _struct_b.unpack(str[start:end]) 00274 start = end 00275 end += 4 00276 (length,) = _struct_I.unpack(str[start:end]) 00277 pattern = '<%sd'%length 00278 start = end 00279 end += struct.calcsize(pattern) 00280 self.mesh.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00281 start = end 00282 end += 4 00283 (length,) = _struct_I.unpack(str[start:end]) 00284 pattern = '<%si'%length 00285 start = end 00286 end += struct.calcsize(pattern) 00287 self.mesh.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 00288 start = end 00289 end += 4 00290 (length,) = _struct_I.unpack(str[start:end]) 00291 self.mesh.vertices = [] 00292 for i in range(0, length): 00293 val1 = geometry_msgs.msg.Point() 00294 _x = val1 00295 start = end 00296 end += 24 00297 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00298 self.mesh.vertices.append(val1) 00299 _x = self 00300 start = end 00301 end += 12 00302 (_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00303 start = end 00304 end += 4 00305 (length,) = _struct_I.unpack(str[start:end]) 00306 start = end 00307 end += length 00308 self.pose.header.frame_id = str[start:end] 00309 _x = self 00310 start = end 00311 end += 56 00312 (_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]) 00313 return self 00314 except struct.error as e: 00315 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00316 00317 _struct_I = roslib.message.struct_I 00318 _struct_3I = struct.Struct("<3I") 00319 _struct_b = struct.Struct("<b") 00320 _struct_7d = struct.Struct("<7d") 00321 _struct_3d = struct.Struct("<3d")