_GetRobotTrajectory.py
Go to the documentation of this file.
00001 """autogenerated by genpy from hector_nav_msgs/GetRobotTrajectoryRequest.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006 
00007 
00008 class GetRobotTrajectoryRequest(genpy.Message):
00009   _md5sum = "d41d8cd98f00b204e9800998ecf8427e"
00010   _type = "hector_nav_msgs/GetRobotTrajectoryRequest"
00011   _has_header = False #flag to mark the presence of a Header object
00012   _full_text = """
00013 
00014 
00015 
00016 
00017 
00018 """
00019   __slots__ = []
00020   _slot_types = []
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        
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(GetRobotTrajectoryRequest, self).__init__(*args, **kwds)
00038 
00039   def _get_types(self):
00040     """
00041     internal API method
00042     """
00043     return self._slot_types
00044 
00045   def serialize(self, buff):
00046     """
00047     serialize message into buffer
00048     :param buff: buffer, ``StringIO``
00049     """
00050     try:
00051       pass
00052     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00053     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00054 
00055   def deserialize(self, str):
00056     """
00057     unpack serialized message in str into this message instance
00058     :param str: byte array of serialized message, ``str``
00059     """
00060     try:
00061       end = 0
00062       return self
00063     except struct.error as e:
00064       raise genpy.DeserializationError(e) #most likely buffer underfill
00065 
00066 
00067   def serialize_numpy(self, buff, numpy):
00068     """
00069     serialize message with numpy array types into buffer
00070     :param buff: buffer, ``StringIO``
00071     :param numpy: numpy python module
00072     """
00073     try:
00074       pass
00075     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00076     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00077 
00078   def deserialize_numpy(self, str, numpy):
00079     """
00080     unpack serialized message in str into this message instance using numpy for array types
00081     :param str: byte array of serialized message, ``str``
00082     :param numpy: numpy python module
00083     """
00084     try:
00085       end = 0
00086       return self
00087     except struct.error as e:
00088       raise genpy.DeserializationError(e) #most likely buffer underfill
00089 
00090 _struct_I = genpy.struct_I
00091 """autogenerated by genpy from hector_nav_msgs/GetRobotTrajectoryResponse.msg. Do not edit."""
00092 import sys
00093 python3 = True if sys.hexversion > 0x03000000 else False
00094 import genpy
00095 import struct
00096 
00097 import geometry_msgs.msg
00098 import nav_msgs.msg
00099 import std_msgs.msg
00100 
00101 class GetRobotTrajectoryResponse(genpy.Message):
00102   _md5sum = "c7bd40129c5786fc26351edbd33b8d33"
00103   _type = "hector_nav_msgs/GetRobotTrajectoryResponse"
00104   _has_header = False #flag to mark the presence of a Header object
00105   _full_text = """nav_msgs/Path trajectory
00106 
00107 
00108 
00109 ================================================================================
00110 MSG: nav_msgs/Path
00111 #An array of poses that represents a Path for a robot to follow
00112 Header header
00113 geometry_msgs/PoseStamped[] poses
00114 
00115 ================================================================================
00116 MSG: std_msgs/Header
00117 # Standard metadata for higher-level stamped data types.
00118 # This is generally used to communicate timestamped data 
00119 # in a particular coordinate frame.
00120 # 
00121 # sequence ID: consecutively increasing ID 
00122 uint32 seq
00123 #Two-integer timestamp that is expressed as:
00124 # * stamp.secs: seconds (stamp_secs) since epoch
00125 # * stamp.nsecs: nanoseconds since stamp_secs
00126 # time-handling sugar is provided by the client library
00127 time stamp
00128 #Frame this data is associated with
00129 # 0: no frame
00130 # 1: global frame
00131 string frame_id
00132 
00133 ================================================================================
00134 MSG: geometry_msgs/PoseStamped
00135 # A Pose with reference coordinate frame and timestamp
00136 Header header
00137 Pose pose
00138 
00139 ================================================================================
00140 MSG: geometry_msgs/Pose
00141 # A representation of pose in free space, composed of postion and orientation. 
00142 Point position
00143 Quaternion orientation
00144 
00145 ================================================================================
00146 MSG: geometry_msgs/Point
00147 # This contains the position of a point in free space
00148 float64 x
00149 float64 y
00150 float64 z
00151 
00152 ================================================================================
00153 MSG: geometry_msgs/Quaternion
00154 # This represents an orientation in free space in quaternion form.
00155 
00156 float64 x
00157 float64 y
00158 float64 z
00159 float64 w
00160 
00161 """
00162   __slots__ = ['trajectory']
00163   _slot_types = ['nav_msgs/Path']
00164 
00165   def __init__(self, *args, **kwds):
00166     """
00167     Constructor. Any message fields that are implicitly/explicitly
00168     set to None will be assigned a default value. The recommend
00169     use is keyword arguments as this is more robust to future message
00170     changes.  You cannot mix in-order arguments and keyword arguments.
00171 
00172     The available fields are:
00173        trajectory
00174 
00175     :param args: complete set of field values, in .msg order
00176     :param kwds: use keyword arguments corresponding to message field names
00177     to set specific fields.
00178     """
00179     if args or kwds:
00180       super(GetRobotTrajectoryResponse, self).__init__(*args, **kwds)
00181       #message fields cannot be None, assign default values for those that are
00182       if self.trajectory is None:
00183         self.trajectory = nav_msgs.msg.Path()
00184     else:
00185       self.trajectory = nav_msgs.msg.Path()
00186 
00187   def _get_types(self):
00188     """
00189     internal API method
00190     """
00191     return self._slot_types
00192 
00193   def serialize(self, buff):
00194     """
00195     serialize message into buffer
00196     :param buff: buffer, ``StringIO``
00197     """
00198     try:
00199       _x = self
00200       buff.write(_struct_3I.pack(_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs))
00201       _x = self.trajectory.header.frame_id
00202       length = len(_x)
00203       if python3 or type(_x) == unicode:
00204         _x = _x.encode('utf-8')
00205         length = len(_x)
00206       buff.write(struct.pack('<I%ss'%length, length, _x))
00207       length = len(self.trajectory.poses)
00208       buff.write(_struct_I.pack(length))
00209       for val1 in self.trajectory.poses:
00210         _v1 = val1.header
00211         buff.write(_struct_I.pack(_v1.seq))
00212         _v2 = _v1.stamp
00213         _x = _v2
00214         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00215         _x = _v1.frame_id
00216         length = len(_x)
00217         if python3 or type(_x) == unicode:
00218           _x = _x.encode('utf-8')
00219           length = len(_x)
00220         buff.write(struct.pack('<I%ss'%length, length, _x))
00221         _v3 = val1.pose
00222         _v4 = _v3.position
00223         _x = _v4
00224         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00225         _v5 = _v3.orientation
00226         _x = _v5
00227         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00228     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00229     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00230 
00231   def deserialize(self, str):
00232     """
00233     unpack serialized message in str into this message instance
00234     :param str: byte array of serialized message, ``str``
00235     """
00236     try:
00237       if self.trajectory is None:
00238         self.trajectory = nav_msgs.msg.Path()
00239       end = 0
00240       _x = self
00241       start = end
00242       end += 12
00243       (_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00244       start = end
00245       end += 4
00246       (length,) = _struct_I.unpack(str[start:end])
00247       start = end
00248       end += length
00249       if python3:
00250         self.trajectory.header.frame_id = str[start:end].decode('utf-8')
00251       else:
00252         self.trajectory.header.frame_id = str[start:end]
00253       start = end
00254       end += 4
00255       (length,) = _struct_I.unpack(str[start:end])
00256       self.trajectory.poses = []
00257       for i in range(0, length):
00258         val1 = geometry_msgs.msg.PoseStamped()
00259         _v6 = val1.header
00260         start = end
00261         end += 4
00262         (_v6.seq,) = _struct_I.unpack(str[start:end])
00263         _v7 = _v6.stamp
00264         _x = _v7
00265         start = end
00266         end += 8
00267         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00268         start = end
00269         end += 4
00270         (length,) = _struct_I.unpack(str[start:end])
00271         start = end
00272         end += length
00273         if python3:
00274           _v6.frame_id = str[start:end].decode('utf-8')
00275         else:
00276           _v6.frame_id = str[start:end]
00277         _v8 = val1.pose
00278         _v9 = _v8.position
00279         _x = _v9
00280         start = end
00281         end += 24
00282         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00283         _v10 = _v8.orientation
00284         _x = _v10
00285         start = end
00286         end += 32
00287         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00288         self.trajectory.poses.append(val1)
00289       return self
00290     except struct.error as e:
00291       raise genpy.DeserializationError(e) #most likely buffer underfill
00292 
00293 
00294   def serialize_numpy(self, buff, numpy):
00295     """
00296     serialize message with numpy array types into buffer
00297     :param buff: buffer, ``StringIO``
00298     :param numpy: numpy python module
00299     """
00300     try:
00301       _x = self
00302       buff.write(_struct_3I.pack(_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs))
00303       _x = self.trajectory.header.frame_id
00304       length = len(_x)
00305       if python3 or type(_x) == unicode:
00306         _x = _x.encode('utf-8')
00307         length = len(_x)
00308       buff.write(struct.pack('<I%ss'%length, length, _x))
00309       length = len(self.trajectory.poses)
00310       buff.write(_struct_I.pack(length))
00311       for val1 in self.trajectory.poses:
00312         _v11 = val1.header
00313         buff.write(_struct_I.pack(_v11.seq))
00314         _v12 = _v11.stamp
00315         _x = _v12
00316         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00317         _x = _v11.frame_id
00318         length = len(_x)
00319         if python3 or type(_x) == unicode:
00320           _x = _x.encode('utf-8')
00321           length = len(_x)
00322         buff.write(struct.pack('<I%ss'%length, length, _x))
00323         _v13 = val1.pose
00324         _v14 = _v13.position
00325         _x = _v14
00326         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00327         _v15 = _v13.orientation
00328         _x = _v15
00329         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00330     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00331     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00332 
00333   def deserialize_numpy(self, str, numpy):
00334     """
00335     unpack serialized message in str into this message instance using numpy for array types
00336     :param str: byte array of serialized message, ``str``
00337     :param numpy: numpy python module
00338     """
00339     try:
00340       if self.trajectory is None:
00341         self.trajectory = nav_msgs.msg.Path()
00342       end = 0
00343       _x = self
00344       start = end
00345       end += 12
00346       (_x.trajectory.header.seq, _x.trajectory.header.stamp.secs, _x.trajectory.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00347       start = end
00348       end += 4
00349       (length,) = _struct_I.unpack(str[start:end])
00350       start = end
00351       end += length
00352       if python3:
00353         self.trajectory.header.frame_id = str[start:end].decode('utf-8')
00354       else:
00355         self.trajectory.header.frame_id = str[start:end]
00356       start = end
00357       end += 4
00358       (length,) = _struct_I.unpack(str[start:end])
00359       self.trajectory.poses = []
00360       for i in range(0, length):
00361         val1 = geometry_msgs.msg.PoseStamped()
00362         _v16 = val1.header
00363         start = end
00364         end += 4
00365         (_v16.seq,) = _struct_I.unpack(str[start:end])
00366         _v17 = _v16.stamp
00367         _x = _v17
00368         start = end
00369         end += 8
00370         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00371         start = end
00372         end += 4
00373         (length,) = _struct_I.unpack(str[start:end])
00374         start = end
00375         end += length
00376         if python3:
00377           _v16.frame_id = str[start:end].decode('utf-8')
00378         else:
00379           _v16.frame_id = str[start:end]
00380         _v18 = val1.pose
00381         _v19 = _v18.position
00382         _x = _v19
00383         start = end
00384         end += 24
00385         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00386         _v20 = _v18.orientation
00387         _x = _v20
00388         start = end
00389         end += 32
00390         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00391         self.trajectory.poses.append(val1)
00392       return self
00393     except struct.error as e:
00394       raise genpy.DeserializationError(e) #most likely buffer underfill
00395 
00396 _struct_I = genpy.struct_I
00397 _struct_4d = struct.Struct("<4d")
00398 _struct_3I = struct.Struct("<3I")
00399 _struct_2I = struct.Struct("<2I")
00400 _struct_3d = struct.Struct("<3d")
00401 class GetRobotTrajectory(object):
00402   _type          = 'hector_nav_msgs/GetRobotTrajectory'
00403   _md5sum = 'c7bd40129c5786fc26351edbd33b8d33'
00404   _request_class  = GetRobotTrajectoryRequest
00405   _response_class = GetRobotTrajectoryResponse


hector_nav_msgs
Author(s): Stefan Kohlbrecher
autogenerated on Mon Oct 6 2014 00:33:16