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