$search
00001 """autogenerated by genmsg_py from AddObjectRequest.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 import worldmodel_msgs.msg 00007 import std_msgs.msg 00008 00009 class AddObjectRequest(roslib.message.Message): 00010 _md5sum = "4603616bc15dac0227cf1b52be1571c7" 00011 _type = "worldmodel_msgs/AddObjectRequest" 00012 _has_header = False #flag to mark the presence of a Header object 00013 _full_text = """ 00014 00015 00016 Object object 00017 00018 00019 bool map_to_next_obstacle 00020 00021 ================================================================================ 00022 MSG: worldmodel_msgs/Object 00023 # This message represents an estimate of an object's pose and identity. 00024 00025 # The header. 00026 # stamp: Timestamp of last update. 00027 # frame_id: Coordinate frame, in which the pose is given 00028 Header header 00029 00030 # The pose 00031 geometry_msgs/PoseWithCovariance pose 00032 00033 # Further information about the object 00034 ObjectInfo info 00035 00036 # The tracked state of the object 00037 ObjectState state 00038 00039 ================================================================================ 00040 MSG: std_msgs/Header 00041 # Standard metadata for higher-level stamped data types. 00042 # This is generally used to communicate timestamped data 00043 # in a particular coordinate frame. 00044 # 00045 # sequence ID: consecutively increasing ID 00046 uint32 seq 00047 #Two-integer timestamp that is expressed as: 00048 # * stamp.secs: seconds (stamp_secs) since epoch 00049 # * stamp.nsecs: nanoseconds since stamp_secs 00050 # time-handling sugar is provided by the client library 00051 time stamp 00052 #Frame this data is associated with 00053 # 0: no frame 00054 # 1: global frame 00055 string frame_id 00056 00057 ================================================================================ 00058 MSG: geometry_msgs/PoseWithCovariance 00059 # This represents a pose in free space with uncertainty. 00060 00061 Pose pose 00062 00063 # Row-major representation of the 6x6 covariance matrix 00064 # The orientation parameters use a fixed-axis representation. 00065 # In order, the parameters are: 00066 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 00067 float64[36] covariance 00068 00069 ================================================================================ 00070 MSG: geometry_msgs/Pose 00071 # A representation of pose in free space, composed of postion and orientation. 00072 Point position 00073 Quaternion orientation 00074 00075 ================================================================================ 00076 MSG: geometry_msgs/Point 00077 # This contains the position of a point in free space 00078 float64 x 00079 float64 y 00080 float64 z 00081 00082 ================================================================================ 00083 MSG: geometry_msgs/Quaternion 00084 # This represents an orientation in free space in quaternion form. 00085 00086 float64 x 00087 float64 y 00088 float64 z 00089 float64 w 00090 00091 ================================================================================ 00092 MSG: worldmodel_msgs/ObjectInfo 00093 # This message contains information about the estimated class affiliation, object id and corresponding support 00094 00095 # A string identifying the object's class (all objects of a class look the same) 00096 string class_id 00097 00098 # A string identifying the specific object 00099 string object_id 00100 00101 # A string that contains the name or a description of the specific object 00102 string name 00103 00104 # The support (degree of belief) of the object's presence given as log odd ratio 00105 float32 support 00106 00107 00108 ================================================================================ 00109 MSG: worldmodel_msgs/ObjectState 00110 # The state of an object estimate used to track 00111 # states smaller than 0 disable all updates 00112 00113 int8 UNKNOWN = 0 00114 int8 PENDING = 1 00115 int8 ACTIVE = 2 00116 int8 CONFIRMED = -1 00117 int8 DISCARDED = -2 00118 int8 APPROACHING = -3 00119 00120 int8 state 00121 00122 """ 00123 __slots__ = ['object','map_to_next_obstacle'] 00124 _slot_types = ['worldmodel_msgs/Object','bool'] 00125 00126 def __init__(self, *args, **kwds): 00127 """ 00128 Constructor. Any message fields that are implicitly/explicitly 00129 set to None will be assigned a default value. The recommend 00130 use is keyword arguments as this is more robust to future message 00131 changes. You cannot mix in-order arguments and keyword arguments. 00132 00133 The available fields are: 00134 object,map_to_next_obstacle 00135 00136 @param args: complete set of field values, in .msg order 00137 @param kwds: use keyword arguments corresponding to message field names 00138 to set specific fields. 00139 """ 00140 if args or kwds: 00141 super(AddObjectRequest, self).__init__(*args, **kwds) 00142 #message fields cannot be None, assign default values for those that are 00143 if self.object is None: 00144 self.object = worldmodel_msgs.msg.Object() 00145 if self.map_to_next_obstacle is None: 00146 self.map_to_next_obstacle = False 00147 else: 00148 self.object = worldmodel_msgs.msg.Object() 00149 self.map_to_next_obstacle = False 00150 00151 def _get_types(self): 00152 """ 00153 internal API method 00154 """ 00155 return self._slot_types 00156 00157 def serialize(self, buff): 00158 """ 00159 serialize message into buffer 00160 @param buff: buffer 00161 @type buff: StringIO 00162 """ 00163 try: 00164 _x = self 00165 buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs)) 00166 _x = self.object.header.frame_id 00167 length = len(_x) 00168 buff.write(struct.pack('<I%ss'%length, length, _x)) 00169 _x = self 00170 buff.write(_struct_7d.pack(_x.object.pose.pose.position.x, _x.object.pose.pose.position.y, _x.object.pose.pose.position.z, _x.object.pose.pose.orientation.x, _x.object.pose.pose.orientation.y, _x.object.pose.pose.orientation.z, _x.object.pose.pose.orientation.w)) 00171 buff.write(_struct_36d.pack(*self.object.pose.covariance)) 00172 _x = self.object.info.class_id 00173 length = len(_x) 00174 buff.write(struct.pack('<I%ss'%length, length, _x)) 00175 _x = self.object.info.object_id 00176 length = len(_x) 00177 buff.write(struct.pack('<I%ss'%length, length, _x)) 00178 _x = self.object.info.name 00179 length = len(_x) 00180 buff.write(struct.pack('<I%ss'%length, length, _x)) 00181 _x = self 00182 buff.write(_struct_fbB.pack(_x.object.info.support, _x.object.state.state, _x.map_to_next_obstacle)) 00183 except struct.error as se: self._check_types(se) 00184 except TypeError as te: self._check_types(te) 00185 00186 def deserialize(self, str): 00187 """ 00188 unpack serialized message in str into this message instance 00189 @param str: byte array of serialized message 00190 @type str: str 00191 """ 00192 try: 00193 if self.object is None: 00194 self.object = worldmodel_msgs.msg.Object() 00195 end = 0 00196 _x = self 00197 start = end 00198 end += 12 00199 (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00200 start = end 00201 end += 4 00202 (length,) = _struct_I.unpack(str[start:end]) 00203 start = end 00204 end += length 00205 self.object.header.frame_id = str[start:end] 00206 _x = self 00207 start = end 00208 end += 56 00209 (_x.object.pose.pose.position.x, _x.object.pose.pose.position.y, _x.object.pose.pose.position.z, _x.object.pose.pose.orientation.x, _x.object.pose.pose.orientation.y, _x.object.pose.pose.orientation.z, _x.object.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end]) 00210 start = end 00211 end += 288 00212 self.object.pose.covariance = _struct_36d.unpack(str[start:end]) 00213 start = end 00214 end += 4 00215 (length,) = _struct_I.unpack(str[start:end]) 00216 start = end 00217 end += length 00218 self.object.info.class_id = str[start:end] 00219 start = end 00220 end += 4 00221 (length,) = _struct_I.unpack(str[start:end]) 00222 start = end 00223 end += length 00224 self.object.info.object_id = str[start:end] 00225 start = end 00226 end += 4 00227 (length,) = _struct_I.unpack(str[start:end]) 00228 start = end 00229 end += length 00230 self.object.info.name = str[start:end] 00231 _x = self 00232 start = end 00233 end += 6 00234 (_x.object.info.support, _x.object.state.state, _x.map_to_next_obstacle,) = _struct_fbB.unpack(str[start:end]) 00235 self.map_to_next_obstacle = bool(self.map_to_next_obstacle) 00236 return self 00237 except struct.error as e: 00238 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00239 00240 00241 def serialize_numpy(self, buff, numpy): 00242 """ 00243 serialize message with numpy array types into buffer 00244 @param buff: buffer 00245 @type buff: StringIO 00246 @param numpy: numpy python module 00247 @type numpy module 00248 """ 00249 try: 00250 _x = self 00251 buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs)) 00252 _x = self.object.header.frame_id 00253 length = len(_x) 00254 buff.write(struct.pack('<I%ss'%length, length, _x)) 00255 _x = self 00256 buff.write(_struct_7d.pack(_x.object.pose.pose.position.x, _x.object.pose.pose.position.y, _x.object.pose.pose.position.z, _x.object.pose.pose.orientation.x, _x.object.pose.pose.orientation.y, _x.object.pose.pose.orientation.z, _x.object.pose.pose.orientation.w)) 00257 buff.write(self.object.pose.covariance.tostring()) 00258 _x = self.object.info.class_id 00259 length = len(_x) 00260 buff.write(struct.pack('<I%ss'%length, length, _x)) 00261 _x = self.object.info.object_id 00262 length = len(_x) 00263 buff.write(struct.pack('<I%ss'%length, length, _x)) 00264 _x = self.object.info.name 00265 length = len(_x) 00266 buff.write(struct.pack('<I%ss'%length, length, _x)) 00267 _x = self 00268 buff.write(_struct_fbB.pack(_x.object.info.support, _x.object.state.state, _x.map_to_next_obstacle)) 00269 except struct.error as se: self._check_types(se) 00270 except TypeError as te: self._check_types(te) 00271 00272 def deserialize_numpy(self, str, numpy): 00273 """ 00274 unpack serialized message in str into this message instance using numpy for array types 00275 @param str: byte array of serialized message 00276 @type str: str 00277 @param numpy: numpy python module 00278 @type numpy: module 00279 """ 00280 try: 00281 if self.object is None: 00282 self.object = worldmodel_msgs.msg.Object() 00283 end = 0 00284 _x = self 00285 start = end 00286 end += 12 00287 (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.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 self.object.header.frame_id = str[start:end] 00294 _x = self 00295 start = end 00296 end += 56 00297 (_x.object.pose.pose.position.x, _x.object.pose.pose.position.y, _x.object.pose.pose.position.z, _x.object.pose.pose.orientation.x, _x.object.pose.pose.orientation.y, _x.object.pose.pose.orientation.z, _x.object.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end]) 00298 start = end 00299 end += 288 00300 self.object.pose.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36) 00301 start = end 00302 end += 4 00303 (length,) = _struct_I.unpack(str[start:end]) 00304 start = end 00305 end += length 00306 self.object.info.class_id = str[start:end] 00307 start = end 00308 end += 4 00309 (length,) = _struct_I.unpack(str[start:end]) 00310 start = end 00311 end += length 00312 self.object.info.object_id = str[start:end] 00313 start = end 00314 end += 4 00315 (length,) = _struct_I.unpack(str[start:end]) 00316 start = end 00317 end += length 00318 self.object.info.name = str[start:end] 00319 _x = self 00320 start = end 00321 end += 6 00322 (_x.object.info.support, _x.object.state.state, _x.map_to_next_obstacle,) = _struct_fbB.unpack(str[start:end]) 00323 self.map_to_next_obstacle = bool(self.map_to_next_obstacle) 00324 return self 00325 except struct.error as e: 00326 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00327 00328 _struct_I = roslib.message.struct_I 00329 _struct_fbB = struct.Struct("<fbB") 00330 _struct_3I = struct.Struct("<3I") 00331 _struct_7d = struct.Struct("<7d") 00332 _struct_36d = struct.Struct("<36d") 00333 """autogenerated by genmsg_py from AddObjectResponse.msg. Do not edit.""" 00334 import roslib.message 00335 import struct 00336 00337 import geometry_msgs.msg 00338 import worldmodel_msgs.msg 00339 import std_msgs.msg 00340 00341 class AddObjectResponse(roslib.message.Message): 00342 _md5sum = "e65ba63f3546a39c3273849a44bd4c52" 00343 _type = "worldmodel_msgs/AddObjectResponse" 00344 _has_header = False #flag to mark the presence of a Header object 00345 _full_text = """ 00346 Object object 00347 00348 00349 ================================================================================ 00350 MSG: worldmodel_msgs/Object 00351 # This message represents an estimate of an object's pose and identity. 00352 00353 # The header. 00354 # stamp: Timestamp of last update. 00355 # frame_id: Coordinate frame, in which the pose is given 00356 Header header 00357 00358 # The pose 00359 geometry_msgs/PoseWithCovariance pose 00360 00361 # Further information about the object 00362 ObjectInfo info 00363 00364 # The tracked state of the object 00365 ObjectState state 00366 00367 ================================================================================ 00368 MSG: std_msgs/Header 00369 # Standard metadata for higher-level stamped data types. 00370 # This is generally used to communicate timestamped data 00371 # in a particular coordinate frame. 00372 # 00373 # sequence ID: consecutively increasing ID 00374 uint32 seq 00375 #Two-integer timestamp that is expressed as: 00376 # * stamp.secs: seconds (stamp_secs) since epoch 00377 # * stamp.nsecs: nanoseconds since stamp_secs 00378 # time-handling sugar is provided by the client library 00379 time stamp 00380 #Frame this data is associated with 00381 # 0: no frame 00382 # 1: global frame 00383 string frame_id 00384 00385 ================================================================================ 00386 MSG: geometry_msgs/PoseWithCovariance 00387 # This represents a pose in free space with uncertainty. 00388 00389 Pose pose 00390 00391 # Row-major representation of the 6x6 covariance matrix 00392 # The orientation parameters use a fixed-axis representation. 00393 # In order, the parameters are: 00394 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 00395 float64[36] covariance 00396 00397 ================================================================================ 00398 MSG: geometry_msgs/Pose 00399 # A representation of pose in free space, composed of postion and orientation. 00400 Point position 00401 Quaternion orientation 00402 00403 ================================================================================ 00404 MSG: geometry_msgs/Point 00405 # This contains the position of a point in free space 00406 float64 x 00407 float64 y 00408 float64 z 00409 00410 ================================================================================ 00411 MSG: geometry_msgs/Quaternion 00412 # This represents an orientation in free space in quaternion form. 00413 00414 float64 x 00415 float64 y 00416 float64 z 00417 float64 w 00418 00419 ================================================================================ 00420 MSG: worldmodel_msgs/ObjectInfo 00421 # This message contains information about the estimated class affiliation, object id and corresponding support 00422 00423 # A string identifying the object's class (all objects of a class look the same) 00424 string class_id 00425 00426 # A string identifying the specific object 00427 string object_id 00428 00429 # A string that contains the name or a description of the specific object 00430 string name 00431 00432 # The support (degree of belief) of the object's presence given as log odd ratio 00433 float32 support 00434 00435 00436 ================================================================================ 00437 MSG: worldmodel_msgs/ObjectState 00438 # The state of an object estimate used to track 00439 # states smaller than 0 disable all updates 00440 00441 int8 UNKNOWN = 0 00442 int8 PENDING = 1 00443 int8 ACTIVE = 2 00444 int8 CONFIRMED = -1 00445 int8 DISCARDED = -2 00446 int8 APPROACHING = -3 00447 00448 int8 state 00449 00450 """ 00451 __slots__ = ['object'] 00452 _slot_types = ['worldmodel_msgs/Object'] 00453 00454 def __init__(self, *args, **kwds): 00455 """ 00456 Constructor. Any message fields that are implicitly/explicitly 00457 set to None will be assigned a default value. The recommend 00458 use is keyword arguments as this is more robust to future message 00459 changes. You cannot mix in-order arguments and keyword arguments. 00460 00461 The available fields are: 00462 object 00463 00464 @param args: complete set of field values, in .msg order 00465 @param kwds: use keyword arguments corresponding to message field names 00466 to set specific fields. 00467 """ 00468 if args or kwds: 00469 super(AddObjectResponse, self).__init__(*args, **kwds) 00470 #message fields cannot be None, assign default values for those that are 00471 if self.object is None: 00472 self.object = worldmodel_msgs.msg.Object() 00473 else: 00474 self.object = worldmodel_msgs.msg.Object() 00475 00476 def _get_types(self): 00477 """ 00478 internal API method 00479 """ 00480 return self._slot_types 00481 00482 def serialize(self, buff): 00483 """ 00484 serialize message into buffer 00485 @param buff: buffer 00486 @type buff: StringIO 00487 """ 00488 try: 00489 _x = self 00490 buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs)) 00491 _x = self.object.header.frame_id 00492 length = len(_x) 00493 buff.write(struct.pack('<I%ss'%length, length, _x)) 00494 _x = self 00495 buff.write(_struct_7d.pack(_x.object.pose.pose.position.x, _x.object.pose.pose.position.y, _x.object.pose.pose.position.z, _x.object.pose.pose.orientation.x, _x.object.pose.pose.orientation.y, _x.object.pose.pose.orientation.z, _x.object.pose.pose.orientation.w)) 00496 buff.write(_struct_36d.pack(*self.object.pose.covariance)) 00497 _x = self.object.info.class_id 00498 length = len(_x) 00499 buff.write(struct.pack('<I%ss'%length, length, _x)) 00500 _x = self.object.info.object_id 00501 length = len(_x) 00502 buff.write(struct.pack('<I%ss'%length, length, _x)) 00503 _x = self.object.info.name 00504 length = len(_x) 00505 buff.write(struct.pack('<I%ss'%length, length, _x)) 00506 _x = self 00507 buff.write(_struct_fb.pack(_x.object.info.support, _x.object.state.state)) 00508 except struct.error as se: self._check_types(se) 00509 except TypeError as te: self._check_types(te) 00510 00511 def deserialize(self, str): 00512 """ 00513 unpack serialized message in str into this message instance 00514 @param str: byte array of serialized message 00515 @type str: str 00516 """ 00517 try: 00518 if self.object is None: 00519 self.object = worldmodel_msgs.msg.Object() 00520 end = 0 00521 _x = self 00522 start = end 00523 end += 12 00524 (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00525 start = end 00526 end += 4 00527 (length,) = _struct_I.unpack(str[start:end]) 00528 start = end 00529 end += length 00530 self.object.header.frame_id = str[start:end] 00531 _x = self 00532 start = end 00533 end += 56 00534 (_x.object.pose.pose.position.x, _x.object.pose.pose.position.y, _x.object.pose.pose.position.z, _x.object.pose.pose.orientation.x, _x.object.pose.pose.orientation.y, _x.object.pose.pose.orientation.z, _x.object.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end]) 00535 start = end 00536 end += 288 00537 self.object.pose.covariance = _struct_36d.unpack(str[start:end]) 00538 start = end 00539 end += 4 00540 (length,) = _struct_I.unpack(str[start:end]) 00541 start = end 00542 end += length 00543 self.object.info.class_id = str[start:end] 00544 start = end 00545 end += 4 00546 (length,) = _struct_I.unpack(str[start:end]) 00547 start = end 00548 end += length 00549 self.object.info.object_id = str[start:end] 00550 start = end 00551 end += 4 00552 (length,) = _struct_I.unpack(str[start:end]) 00553 start = end 00554 end += length 00555 self.object.info.name = str[start:end] 00556 _x = self 00557 start = end 00558 end += 5 00559 (_x.object.info.support, _x.object.state.state,) = _struct_fb.unpack(str[start:end]) 00560 return self 00561 except struct.error as e: 00562 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00563 00564 00565 def serialize_numpy(self, buff, numpy): 00566 """ 00567 serialize message with numpy array types into buffer 00568 @param buff: buffer 00569 @type buff: StringIO 00570 @param numpy: numpy python module 00571 @type numpy module 00572 """ 00573 try: 00574 _x = self 00575 buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs)) 00576 _x = self.object.header.frame_id 00577 length = len(_x) 00578 buff.write(struct.pack('<I%ss'%length, length, _x)) 00579 _x = self 00580 buff.write(_struct_7d.pack(_x.object.pose.pose.position.x, _x.object.pose.pose.position.y, _x.object.pose.pose.position.z, _x.object.pose.pose.orientation.x, _x.object.pose.pose.orientation.y, _x.object.pose.pose.orientation.z, _x.object.pose.pose.orientation.w)) 00581 buff.write(self.object.pose.covariance.tostring()) 00582 _x = self.object.info.class_id 00583 length = len(_x) 00584 buff.write(struct.pack('<I%ss'%length, length, _x)) 00585 _x = self.object.info.object_id 00586 length = len(_x) 00587 buff.write(struct.pack('<I%ss'%length, length, _x)) 00588 _x = self.object.info.name 00589 length = len(_x) 00590 buff.write(struct.pack('<I%ss'%length, length, _x)) 00591 _x = self 00592 buff.write(_struct_fb.pack(_x.object.info.support, _x.object.state.state)) 00593 except struct.error as se: self._check_types(se) 00594 except TypeError as te: self._check_types(te) 00595 00596 def deserialize_numpy(self, str, numpy): 00597 """ 00598 unpack serialized message in str into this message instance using numpy for array types 00599 @param str: byte array of serialized message 00600 @type str: str 00601 @param numpy: numpy python module 00602 @type numpy: module 00603 """ 00604 try: 00605 if self.object is None: 00606 self.object = worldmodel_msgs.msg.Object() 00607 end = 0 00608 _x = self 00609 start = end 00610 end += 12 00611 (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00612 start = end 00613 end += 4 00614 (length,) = _struct_I.unpack(str[start:end]) 00615 start = end 00616 end += length 00617 self.object.header.frame_id = str[start:end] 00618 _x = self 00619 start = end 00620 end += 56 00621 (_x.object.pose.pose.position.x, _x.object.pose.pose.position.y, _x.object.pose.pose.position.z, _x.object.pose.pose.orientation.x, _x.object.pose.pose.orientation.y, _x.object.pose.pose.orientation.z, _x.object.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end]) 00622 start = end 00623 end += 288 00624 self.object.pose.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36) 00625 start = end 00626 end += 4 00627 (length,) = _struct_I.unpack(str[start:end]) 00628 start = end 00629 end += length 00630 self.object.info.class_id = str[start:end] 00631 start = end 00632 end += 4 00633 (length,) = _struct_I.unpack(str[start:end]) 00634 start = end 00635 end += length 00636 self.object.info.object_id = str[start:end] 00637 start = end 00638 end += 4 00639 (length,) = _struct_I.unpack(str[start:end]) 00640 start = end 00641 end += length 00642 self.object.info.name = str[start:end] 00643 _x = self 00644 start = end 00645 end += 5 00646 (_x.object.info.support, _x.object.state.state,) = _struct_fb.unpack(str[start:end]) 00647 return self 00648 except struct.error as e: 00649 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00650 00651 _struct_I = roslib.message.struct_I 00652 _struct_fb = struct.Struct("<fb") 00653 _struct_3I = struct.Struct("<3I") 00654 _struct_7d = struct.Struct("<7d") 00655 _struct_36d = struct.Struct("<36d") 00656 class AddObject(roslib.message.ServiceDefinition): 00657 _type = 'worldmodel_msgs/AddObject' 00658 _md5sum = '8438366343e0924102cedddd9ee5b307' 00659 _request_class = AddObjectRequest 00660 _response_class = AddObjectResponse