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


ethzasl_icp_mapper
Author(s): François Pomerleau and Stéphane Magnenat
autogenerated on Thu Jan 2 2014 11:16:21