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