00001 """autogenerated by genmsg_py from GetRecoveryInfoRequest.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import roslib.rostime
00006
00007 class GetRecoveryInfoRequest(roslib.message.Message):
00008 _md5sum = "3916a0c55958d5dd43204cd2fe5608f6"
00009 _type = "hector_nav_msgs/GetRecoveryInfoRequest"
00010 _has_header = False
00011 _full_text = """
00012
00013
00014
00015 time request_time
00016 float64 request_radius
00017
00018 """
00019 __slots__ = ['request_time','request_radius']
00020 _slot_types = ['time','float64']
00021
00022 def __init__(self, *args, **kwds):
00023 """
00024 Constructor. Any message fields that are implicitly/explicitly
00025 set to None will be assigned a default value. The recommend
00026 use is keyword arguments as this is more robust to future message
00027 changes. You cannot mix in-order arguments and keyword arguments.
00028
00029 The available fields are:
00030 request_time,request_radius
00031
00032 @param args: complete set of field values, in .msg order
00033 @param kwds: use keyword arguments corresponding to message field names
00034 to set specific fields.
00035 """
00036 if args or kwds:
00037 super(GetRecoveryInfoRequest, self).__init__(*args, **kwds)
00038
00039 if self.request_time is None:
00040 self.request_time = roslib.rostime.Time()
00041 if self.request_radius is None:
00042 self.request_radius = 0.
00043 else:
00044 self.request_time = roslib.rostime.Time()
00045 self.request_radius = 0.
00046
00047 def _get_types(self):
00048 """
00049 internal API method
00050 """
00051 return self._slot_types
00052
00053 def serialize(self, buff):
00054 """
00055 serialize message into buffer
00056 @param buff: buffer
00057 @type buff: StringIO
00058 """
00059 try:
00060 _x = self
00061 buff.write(_struct_2Id.pack(_x.request_time.secs, _x.request_time.nsecs, _x.request_radius))
00062 except struct.error as se: self._check_types(se)
00063 except TypeError as te: self._check_types(te)
00064
00065 def deserialize(self, str):
00066 """
00067 unpack serialized message in str into this message instance
00068 @param str: byte array of serialized message
00069 @type str: str
00070 """
00071 try:
00072 if self.request_time is None:
00073 self.request_time = roslib.rostime.Time()
00074 end = 0
00075 _x = self
00076 start = end
00077 end += 16
00078 (_x.request_time.secs, _x.request_time.nsecs, _x.request_radius,) = _struct_2Id.unpack(str[start:end])
00079 self.request_time.canon()
00080 return self
00081 except struct.error as e:
00082 raise roslib.message.DeserializationError(e)
00083
00084
00085 def serialize_numpy(self, buff, numpy):
00086 """
00087 serialize message with numpy array types into buffer
00088 @param buff: buffer
00089 @type buff: StringIO
00090 @param numpy: numpy python module
00091 @type numpy module
00092 """
00093 try:
00094 _x = self
00095 buff.write(_struct_2Id.pack(_x.request_time.secs, _x.request_time.nsecs, _x.request_radius))
00096 except struct.error as se: self._check_types(se)
00097 except TypeError as te: self._check_types(te)
00098
00099 def deserialize_numpy(self, str, numpy):
00100 """
00101 unpack serialized message in str into this message instance using numpy for array types
00102 @param str: byte array of serialized message
00103 @type str: str
00104 @param numpy: numpy python module
00105 @type numpy: module
00106 """
00107 try:
00108 if self.request_time is None:
00109 self.request_time = roslib.rostime.Time()
00110 end = 0
00111 _x = self
00112 start = end
00113 end += 16
00114 (_x.request_time.secs, _x.request_time.nsecs, _x.request_radius,) = _struct_2Id.unpack(str[start:end])
00115 self.request_time.canon()
00116 return self
00117 except struct.error as e:
00118 raise roslib.message.DeserializationError(e)
00119
00120 _struct_I = roslib.message.struct_I
00121 _struct_2Id = struct.Struct("<2Id")
00122 """autogenerated by genmsg_py from GetRecoveryInfoResponse.msg. Do not edit."""
00123 import roslib.message
00124 import struct
00125
00126 import geometry_msgs.msg
00127 import nav_msgs.msg
00128 import std_msgs.msg
00129
00130 class GetRecoveryInfoResponse(roslib.message.Message):
00131 _md5sum = "a93581be8e34e3c09aeafc6b9b990ad5"
00132 _type = "hector_nav_msgs/GetRecoveryInfoResponse"
00133 _has_header = False
00134 _full_text = """nav_msgs/Path trajectory_radius_entry_pose_to_req_pose
00135 geometry_msgs/PoseStamped radius_entry_pose
00136 geometry_msgs/PoseStamped req_pose
00137
00138
00139
00140 ================================================================================
00141 MSG: nav_msgs/Path
00142 #An array of poses that represents a Path for a robot to follow
00143 Header header
00144 geometry_msgs/PoseStamped[] poses
00145
00146 ================================================================================
00147 MSG: std_msgs/Header
00148 # Standard metadata for higher-level stamped data types.
00149 # This is generally used to communicate timestamped data
00150 # in a particular coordinate frame.
00151 #
00152 # sequence ID: consecutively increasing ID
00153 uint32 seq
00154 #Two-integer timestamp that is expressed as:
00155 # * stamp.secs: seconds (stamp_secs) since epoch
00156 # * stamp.nsecs: nanoseconds since stamp_secs
00157 # time-handling sugar is provided by the client library
00158 time stamp
00159 #Frame this data is associated with
00160 # 0: no frame
00161 # 1: global frame
00162 string frame_id
00163
00164 ================================================================================
00165 MSG: geometry_msgs/PoseStamped
00166 # A Pose with reference coordinate frame and timestamp
00167 Header header
00168 Pose pose
00169
00170 ================================================================================
00171 MSG: geometry_msgs/Pose
00172 # A representation of pose in free space, composed of postion and orientation.
00173 Point position
00174 Quaternion orientation
00175
00176 ================================================================================
00177 MSG: geometry_msgs/Point
00178 # This contains the position of a point in free space
00179 float64 x
00180 float64 y
00181 float64 z
00182
00183 ================================================================================
00184 MSG: geometry_msgs/Quaternion
00185 # This represents an orientation in free space in quaternion form.
00186
00187 float64 x
00188 float64 y
00189 float64 z
00190 float64 w
00191
00192 """
00193 __slots__ = ['trajectory_radius_entry_pose_to_req_pose','radius_entry_pose','req_pose']
00194 _slot_types = ['nav_msgs/Path','geometry_msgs/PoseStamped','geometry_msgs/PoseStamped']
00195
00196 def __init__(self, *args, **kwds):
00197 """
00198 Constructor. Any message fields that are implicitly/explicitly
00199 set to None will be assigned a default value. The recommend
00200 use is keyword arguments as this is more robust to future message
00201 changes. You cannot mix in-order arguments and keyword arguments.
00202
00203 The available fields are:
00204 trajectory_radius_entry_pose_to_req_pose,radius_entry_pose,req_pose
00205
00206 @param args: complete set of field values, in .msg order
00207 @param kwds: use keyword arguments corresponding to message field names
00208 to set specific fields.
00209 """
00210 if args or kwds:
00211 super(GetRecoveryInfoResponse, self).__init__(*args, **kwds)
00212
00213 if self.trajectory_radius_entry_pose_to_req_pose is None:
00214 self.trajectory_radius_entry_pose_to_req_pose = nav_msgs.msg.Path()
00215 if self.radius_entry_pose is None:
00216 self.radius_entry_pose = geometry_msgs.msg.PoseStamped()
00217 if self.req_pose is None:
00218 self.req_pose = geometry_msgs.msg.PoseStamped()
00219 else:
00220 self.trajectory_radius_entry_pose_to_req_pose = nav_msgs.msg.Path()
00221 self.radius_entry_pose = geometry_msgs.msg.PoseStamped()
00222 self.req_pose = geometry_msgs.msg.PoseStamped()
00223
00224 def _get_types(self):
00225 """
00226 internal API method
00227 """
00228 return self._slot_types
00229
00230 def serialize(self, buff):
00231 """
00232 serialize message into buffer
00233 @param buff: buffer
00234 @type buff: StringIO
00235 """
00236 try:
00237 _x = self
00238 buff.write(_struct_3I.pack(_x.trajectory_radius_entry_pose_to_req_pose.header.seq, _x.trajectory_radius_entry_pose_to_req_pose.header.stamp.secs, _x.trajectory_radius_entry_pose_to_req_pose.header.stamp.nsecs))
00239 _x = self.trajectory_radius_entry_pose_to_req_pose.header.frame_id
00240 length = len(_x)
00241 buff.write(struct.pack('<I%ss'%length, length, _x))
00242 length = len(self.trajectory_radius_entry_pose_to_req_pose.poses)
00243 buff.write(_struct_I.pack(length))
00244 for val1 in self.trajectory_radius_entry_pose_to_req_pose.poses:
00245 _v1 = val1.header
00246 buff.write(_struct_I.pack(_v1.seq))
00247 _v2 = _v1.stamp
00248 _x = _v2
00249 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00250 _x = _v1.frame_id
00251 length = len(_x)
00252 buff.write(struct.pack('<I%ss'%length, length, _x))
00253 _v3 = val1.pose
00254 _v4 = _v3.position
00255 _x = _v4
00256 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00257 _v5 = _v3.orientation
00258 _x = _v5
00259 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00260 _x = self
00261 buff.write(_struct_3I.pack(_x.radius_entry_pose.header.seq, _x.radius_entry_pose.header.stamp.secs, _x.radius_entry_pose.header.stamp.nsecs))
00262 _x = self.radius_entry_pose.header.frame_id
00263 length = len(_x)
00264 buff.write(struct.pack('<I%ss'%length, length, _x))
00265 _x = self
00266 buff.write(_struct_7d3I.pack(_x.radius_entry_pose.pose.position.x, _x.radius_entry_pose.pose.position.y, _x.radius_entry_pose.pose.position.z, _x.radius_entry_pose.pose.orientation.x, _x.radius_entry_pose.pose.orientation.y, _x.radius_entry_pose.pose.orientation.z, _x.radius_entry_pose.pose.orientation.w, _x.req_pose.header.seq, _x.req_pose.header.stamp.secs, _x.req_pose.header.stamp.nsecs))
00267 _x = self.req_pose.header.frame_id
00268 length = len(_x)
00269 buff.write(struct.pack('<I%ss'%length, length, _x))
00270 _x = self
00271 buff.write(_struct_7d.pack(_x.req_pose.pose.position.x, _x.req_pose.pose.position.y, _x.req_pose.pose.position.z, _x.req_pose.pose.orientation.x, _x.req_pose.pose.orientation.y, _x.req_pose.pose.orientation.z, _x.req_pose.pose.orientation.w))
00272 except struct.error as se: self._check_types(se)
00273 except TypeError as te: self._check_types(te)
00274
00275 def deserialize(self, str):
00276 """
00277 unpack serialized message in str into this message instance
00278 @param str: byte array of serialized message
00279 @type str: str
00280 """
00281 try:
00282 if self.trajectory_radius_entry_pose_to_req_pose is None:
00283 self.trajectory_radius_entry_pose_to_req_pose = nav_msgs.msg.Path()
00284 if self.radius_entry_pose is None:
00285 self.radius_entry_pose = geometry_msgs.msg.PoseStamped()
00286 if self.req_pose is None:
00287 self.req_pose = geometry_msgs.msg.PoseStamped()
00288 end = 0
00289 _x = self
00290 start = end
00291 end += 12
00292 (_x.trajectory_radius_entry_pose_to_req_pose.header.seq, _x.trajectory_radius_entry_pose_to_req_pose.header.stamp.secs, _x.trajectory_radius_entry_pose_to_req_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00293 start = end
00294 end += 4
00295 (length,) = _struct_I.unpack(str[start:end])
00296 start = end
00297 end += length
00298 self.trajectory_radius_entry_pose_to_req_pose.header.frame_id = str[start:end]
00299 start = end
00300 end += 4
00301 (length,) = _struct_I.unpack(str[start:end])
00302 self.trajectory_radius_entry_pose_to_req_pose.poses = []
00303 for i in range(0, length):
00304 val1 = geometry_msgs.msg.PoseStamped()
00305 _v6 = val1.header
00306 start = end
00307 end += 4
00308 (_v6.seq,) = _struct_I.unpack(str[start:end])
00309 _v7 = _v6.stamp
00310 _x = _v7
00311 start = end
00312 end += 8
00313 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00314 start = end
00315 end += 4
00316 (length,) = _struct_I.unpack(str[start:end])
00317 start = end
00318 end += length
00319 _v6.frame_id = str[start:end]
00320 _v8 = val1.pose
00321 _v9 = _v8.position
00322 _x = _v9
00323 start = end
00324 end += 24
00325 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00326 _v10 = _v8.orientation
00327 _x = _v10
00328 start = end
00329 end += 32
00330 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00331 self.trajectory_radius_entry_pose_to_req_pose.poses.append(val1)
00332 _x = self
00333 start = end
00334 end += 12
00335 (_x.radius_entry_pose.header.seq, _x.radius_entry_pose.header.stamp.secs, _x.radius_entry_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00336 start = end
00337 end += 4
00338 (length,) = _struct_I.unpack(str[start:end])
00339 start = end
00340 end += length
00341 self.radius_entry_pose.header.frame_id = str[start:end]
00342 _x = self
00343 start = end
00344 end += 68
00345 (_x.radius_entry_pose.pose.position.x, _x.radius_entry_pose.pose.position.y, _x.radius_entry_pose.pose.position.z, _x.radius_entry_pose.pose.orientation.x, _x.radius_entry_pose.pose.orientation.y, _x.radius_entry_pose.pose.orientation.z, _x.radius_entry_pose.pose.orientation.w, _x.req_pose.header.seq, _x.req_pose.header.stamp.secs, _x.req_pose.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00346 start = end
00347 end += 4
00348 (length,) = _struct_I.unpack(str[start:end])
00349 start = end
00350 end += length
00351 self.req_pose.header.frame_id = str[start:end]
00352 _x = self
00353 start = end
00354 end += 56
00355 (_x.req_pose.pose.position.x, _x.req_pose.pose.position.y, _x.req_pose.pose.position.z, _x.req_pose.pose.orientation.x, _x.req_pose.pose.orientation.y, _x.req_pose.pose.orientation.z, _x.req_pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00356 return self
00357 except struct.error as e:
00358 raise roslib.message.DeserializationError(e)
00359
00360
00361 def serialize_numpy(self, buff, numpy):
00362 """
00363 serialize message with numpy array types into buffer
00364 @param buff: buffer
00365 @type buff: StringIO
00366 @param numpy: numpy python module
00367 @type numpy module
00368 """
00369 try:
00370 _x = self
00371 buff.write(_struct_3I.pack(_x.trajectory_radius_entry_pose_to_req_pose.header.seq, _x.trajectory_radius_entry_pose_to_req_pose.header.stamp.secs, _x.trajectory_radius_entry_pose_to_req_pose.header.stamp.nsecs))
00372 _x = self.trajectory_radius_entry_pose_to_req_pose.header.frame_id
00373 length = len(_x)
00374 buff.write(struct.pack('<I%ss'%length, length, _x))
00375 length = len(self.trajectory_radius_entry_pose_to_req_pose.poses)
00376 buff.write(_struct_I.pack(length))
00377 for val1 in self.trajectory_radius_entry_pose_to_req_pose.poses:
00378 _v11 = val1.header
00379 buff.write(_struct_I.pack(_v11.seq))
00380 _v12 = _v11.stamp
00381 _x = _v12
00382 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00383 _x = _v11.frame_id
00384 length = len(_x)
00385 buff.write(struct.pack('<I%ss'%length, length, _x))
00386 _v13 = val1.pose
00387 _v14 = _v13.position
00388 _x = _v14
00389 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00390 _v15 = _v13.orientation
00391 _x = _v15
00392 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00393 _x = self
00394 buff.write(_struct_3I.pack(_x.radius_entry_pose.header.seq, _x.radius_entry_pose.header.stamp.secs, _x.radius_entry_pose.header.stamp.nsecs))
00395 _x = self.radius_entry_pose.header.frame_id
00396 length = len(_x)
00397 buff.write(struct.pack('<I%ss'%length, length, _x))
00398 _x = self
00399 buff.write(_struct_7d3I.pack(_x.radius_entry_pose.pose.position.x, _x.radius_entry_pose.pose.position.y, _x.radius_entry_pose.pose.position.z, _x.radius_entry_pose.pose.orientation.x, _x.radius_entry_pose.pose.orientation.y, _x.radius_entry_pose.pose.orientation.z, _x.radius_entry_pose.pose.orientation.w, _x.req_pose.header.seq, _x.req_pose.header.stamp.secs, _x.req_pose.header.stamp.nsecs))
00400 _x = self.req_pose.header.frame_id
00401 length = len(_x)
00402 buff.write(struct.pack('<I%ss'%length, length, _x))
00403 _x = self
00404 buff.write(_struct_7d.pack(_x.req_pose.pose.position.x, _x.req_pose.pose.position.y, _x.req_pose.pose.position.z, _x.req_pose.pose.orientation.x, _x.req_pose.pose.orientation.y, _x.req_pose.pose.orientation.z, _x.req_pose.pose.orientation.w))
00405 except struct.error as se: self._check_types(se)
00406 except TypeError as te: self._check_types(te)
00407
00408 def deserialize_numpy(self, str, numpy):
00409 """
00410 unpack serialized message in str into this message instance using numpy for array types
00411 @param str: byte array of serialized message
00412 @type str: str
00413 @param numpy: numpy python module
00414 @type numpy: module
00415 """
00416 try:
00417 if self.trajectory_radius_entry_pose_to_req_pose is None:
00418 self.trajectory_radius_entry_pose_to_req_pose = nav_msgs.msg.Path()
00419 if self.radius_entry_pose is None:
00420 self.radius_entry_pose = geometry_msgs.msg.PoseStamped()
00421 if self.req_pose is None:
00422 self.req_pose = geometry_msgs.msg.PoseStamped()
00423 end = 0
00424 _x = self
00425 start = end
00426 end += 12
00427 (_x.trajectory_radius_entry_pose_to_req_pose.header.seq, _x.trajectory_radius_entry_pose_to_req_pose.header.stamp.secs, _x.trajectory_radius_entry_pose_to_req_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00428 start = end
00429 end += 4
00430 (length,) = _struct_I.unpack(str[start:end])
00431 start = end
00432 end += length
00433 self.trajectory_radius_entry_pose_to_req_pose.header.frame_id = str[start:end]
00434 start = end
00435 end += 4
00436 (length,) = _struct_I.unpack(str[start:end])
00437 self.trajectory_radius_entry_pose_to_req_pose.poses = []
00438 for i in range(0, length):
00439 val1 = geometry_msgs.msg.PoseStamped()
00440 _v16 = val1.header
00441 start = end
00442 end += 4
00443 (_v16.seq,) = _struct_I.unpack(str[start:end])
00444 _v17 = _v16.stamp
00445 _x = _v17
00446 start = end
00447 end += 8
00448 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00449 start = end
00450 end += 4
00451 (length,) = _struct_I.unpack(str[start:end])
00452 start = end
00453 end += length
00454 _v16.frame_id = str[start:end]
00455 _v18 = val1.pose
00456 _v19 = _v18.position
00457 _x = _v19
00458 start = end
00459 end += 24
00460 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00461 _v20 = _v18.orientation
00462 _x = _v20
00463 start = end
00464 end += 32
00465 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00466 self.trajectory_radius_entry_pose_to_req_pose.poses.append(val1)
00467 _x = self
00468 start = end
00469 end += 12
00470 (_x.radius_entry_pose.header.seq, _x.radius_entry_pose.header.stamp.secs, _x.radius_entry_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00471 start = end
00472 end += 4
00473 (length,) = _struct_I.unpack(str[start:end])
00474 start = end
00475 end += length
00476 self.radius_entry_pose.header.frame_id = str[start:end]
00477 _x = self
00478 start = end
00479 end += 68
00480 (_x.radius_entry_pose.pose.position.x, _x.radius_entry_pose.pose.position.y, _x.radius_entry_pose.pose.position.z, _x.radius_entry_pose.pose.orientation.x, _x.radius_entry_pose.pose.orientation.y, _x.radius_entry_pose.pose.orientation.z, _x.radius_entry_pose.pose.orientation.w, _x.req_pose.header.seq, _x.req_pose.header.stamp.secs, _x.req_pose.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00481 start = end
00482 end += 4
00483 (length,) = _struct_I.unpack(str[start:end])
00484 start = end
00485 end += length
00486 self.req_pose.header.frame_id = str[start:end]
00487 _x = self
00488 start = end
00489 end += 56
00490 (_x.req_pose.pose.position.x, _x.req_pose.pose.position.y, _x.req_pose.pose.position.z, _x.req_pose.pose.orientation.x, _x.req_pose.pose.orientation.y, _x.req_pose.pose.orientation.z, _x.req_pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00491 return self
00492 except struct.error as e:
00493 raise roslib.message.DeserializationError(e)
00494
00495 _struct_I = roslib.message.struct_I
00496 _struct_7d = struct.Struct("<7d")
00497 _struct_7d3I = struct.Struct("<7d3I")
00498 _struct_3I = struct.Struct("<3I")
00499 _struct_4d = struct.Struct("<4d")
00500 _struct_2I = struct.Struct("<2I")
00501 _struct_3d = struct.Struct("<3d")
00502 class GetRecoveryInfo(roslib.message.ServiceDefinition):
00503 _type = 'hector_nav_msgs/GetRecoveryInfo'
00504 _md5sum = 'edd6e579a08e5c27f2b7fcfa4c39b7bb'
00505 _request_class = GetRecoveryInfoRequest
00506 _response_class = GetRecoveryInfoResponse