_JinvTeleopControllerState.py
Go to the documentation of this file.
00001 """autogenerated by genpy from pr2_manipulation_controllers/JinvTeleopControllerState.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 std_msgs.msg
00009 
00010 class JinvTeleopControllerState(genpy.Message):
00011   _md5sum = "1456444fe71f72390283aef7aca2934d"
00012   _type = "pr2_manipulation_controllers/JinvTeleopControllerState"
00013   _has_header = True #flag to mark the presence of a Header object
00014   _full_text = """Header header
00015 geometry_msgs/PoseStamped x
00016 geometry_msgs/PoseStamped x_desi
00017 geometry_msgs/PoseStamped x_desi_filtered
00018 geometry_msgs/Twist x_err
00019 geometry_msgs/Twist xd
00020 geometry_msgs/Twist xd_desi
00021 geometry_msgs/Wrench F
00022 float64[] q_proxy
00023 float64[] qd_pose
00024 float64[] qd_posture
00025 float64[] qd_posture_raw
00026 float64[] qd_desi
00027 float64[] tau
00028 std_msgs/Float64MultiArray J
00029 std_msgs/Float64MultiArray N
00030 
00031 # Environmental stiffness
00032 float64 df
00033 float64 dx
00034 float64 Df
00035 float64 Dx
00036 float64 stiffness
00037 float64 compliance
00038 
00039 ================================================================================
00040 MSG: std_msgs/Header
00041 # Standard metadata for higher-level stamped data types.
00042 # This is generally used to communicate timestamped data 
00043 # in a particular coordinate frame.
00044 # 
00045 # sequence ID: consecutively increasing ID 
00046 uint32 seq
00047 #Two-integer timestamp that is expressed as:
00048 # * stamp.secs: seconds (stamp_secs) since epoch
00049 # * stamp.nsecs: nanoseconds since stamp_secs
00050 # time-handling sugar is provided by the client library
00051 time stamp
00052 #Frame this data is associated with
00053 # 0: no frame
00054 # 1: global frame
00055 string frame_id
00056 
00057 ================================================================================
00058 MSG: geometry_msgs/PoseStamped
00059 # A Pose with reference coordinate frame and timestamp
00060 Header header
00061 Pose pose
00062 
00063 ================================================================================
00064 MSG: geometry_msgs/Pose
00065 # A representation of pose in free space, composed of postion and orientation. 
00066 Point position
00067 Quaternion orientation
00068 
00069 ================================================================================
00070 MSG: geometry_msgs/Point
00071 # This contains the position of a point in free space
00072 float64 x
00073 float64 y
00074 float64 z
00075 
00076 ================================================================================
00077 MSG: geometry_msgs/Quaternion
00078 # This represents an orientation in free space in quaternion form.
00079 
00080 float64 x
00081 float64 y
00082 float64 z
00083 float64 w
00084 
00085 ================================================================================
00086 MSG: geometry_msgs/Twist
00087 # This expresses velocity in free space broken into it's linear and angular parts. 
00088 Vector3  linear
00089 Vector3  angular
00090 
00091 ================================================================================
00092 MSG: geometry_msgs/Vector3
00093 # This represents a vector in free space. 
00094 
00095 float64 x
00096 float64 y
00097 float64 z
00098 ================================================================================
00099 MSG: geometry_msgs/Wrench
00100 # This represents force in free space, seperated into 
00101 # it's linear and angular parts.  
00102 Vector3  force
00103 Vector3  torque
00104 
00105 ================================================================================
00106 MSG: std_msgs/Float64MultiArray
00107 # Please look at the MultiArrayLayout message definition for
00108 # documentation on all multiarrays.
00109 
00110 MultiArrayLayout  layout        # specification of data layout
00111 float64[]         data          # array of data
00112 
00113 
00114 ================================================================================
00115 MSG: std_msgs/MultiArrayLayout
00116 # The multiarray declares a generic multi-dimensional array of a
00117 # particular data type.  Dimensions are ordered from outer most
00118 # to inner most.
00119 
00120 MultiArrayDimension[] dim # Array of dimension properties
00121 uint32 data_offset        # padding bytes at front of data
00122 
00123 # Accessors should ALWAYS be written in terms of dimension stride
00124 # and specified outer-most dimension first.
00125 # 
00126 # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]
00127 #
00128 # A standard, 3-channel 640x480 image with interleaved color channels
00129 # would be specified as:
00130 #
00131 # dim[0].label  = "height"
00132 # dim[0].size   = 480
00133 # dim[0].stride = 3*640*480 = 921600  (note dim[0] stride is just size of image)
00134 # dim[1].label  = "width"
00135 # dim[1].size   = 640
00136 # dim[1].stride = 3*640 = 1920
00137 # dim[2].label  = "channel"
00138 # dim[2].size   = 3
00139 # dim[2].stride = 3
00140 #
00141 # multiarray(i,j,k) refers to the ith row, jth column, and kth channel.
00142 ================================================================================
00143 MSG: std_msgs/MultiArrayDimension
00144 string label   # label of given dimension
00145 uint32 size    # size of given dimension (in type units)
00146 uint32 stride  # stride of given dimension
00147 """
00148   __slots__ = ['header','x','x_desi','x_desi_filtered','x_err','xd','xd_desi','F','q_proxy','qd_pose','qd_posture','qd_posture_raw','qd_desi','tau','J','N','df','dx','Df','Dx','stiffness','compliance']
00149   _slot_types = ['std_msgs/Header','geometry_msgs/PoseStamped','geometry_msgs/PoseStamped','geometry_msgs/PoseStamped','geometry_msgs/Twist','geometry_msgs/Twist','geometry_msgs/Twist','geometry_msgs/Wrench','float64[]','float64[]','float64[]','float64[]','float64[]','float64[]','std_msgs/Float64MultiArray','std_msgs/Float64MultiArray','float64','float64','float64','float64','float64','float64']
00150 
00151   def __init__(self, *args, **kwds):
00152     """
00153     Constructor. Any message fields that are implicitly/explicitly
00154     set to None will be assigned a default value. The recommend
00155     use is keyword arguments as this is more robust to future message
00156     changes.  You cannot mix in-order arguments and keyword arguments.
00157 
00158     The available fields are:
00159        header,x,x_desi,x_desi_filtered,x_err,xd,xd_desi,F,q_proxy,qd_pose,qd_posture,qd_posture_raw,qd_desi,tau,J,N,df,dx,Df,Dx,stiffness,compliance
00160 
00161     :param args: complete set of field values, in .msg order
00162     :param kwds: use keyword arguments corresponding to message field names
00163     to set specific fields.
00164     """
00165     if args or kwds:
00166       super(JinvTeleopControllerState, self).__init__(*args, **kwds)
00167       #message fields cannot be None, assign default values for those that are
00168       if self.header is None:
00169         self.header = std_msgs.msg.Header()
00170       if self.x is None:
00171         self.x = geometry_msgs.msg.PoseStamped()
00172       if self.x_desi is None:
00173         self.x_desi = geometry_msgs.msg.PoseStamped()
00174       if self.x_desi_filtered is None:
00175         self.x_desi_filtered = geometry_msgs.msg.PoseStamped()
00176       if self.x_err is None:
00177         self.x_err = geometry_msgs.msg.Twist()
00178       if self.xd is None:
00179         self.xd = geometry_msgs.msg.Twist()
00180       if self.xd_desi is None:
00181         self.xd_desi = geometry_msgs.msg.Twist()
00182       if self.F is None:
00183         self.F = geometry_msgs.msg.Wrench()
00184       if self.q_proxy is None:
00185         self.q_proxy = []
00186       if self.qd_pose is None:
00187         self.qd_pose = []
00188       if self.qd_posture is None:
00189         self.qd_posture = []
00190       if self.qd_posture_raw is None:
00191         self.qd_posture_raw = []
00192       if self.qd_desi is None:
00193         self.qd_desi = []
00194       if self.tau is None:
00195         self.tau = []
00196       if self.J is None:
00197         self.J = std_msgs.msg.Float64MultiArray()
00198       if self.N is None:
00199         self.N = std_msgs.msg.Float64MultiArray()
00200       if self.df is None:
00201         self.df = 0.
00202       if self.dx is None:
00203         self.dx = 0.
00204       if self.Df is None:
00205         self.Df = 0.
00206       if self.Dx is None:
00207         self.Dx = 0.
00208       if self.stiffness is None:
00209         self.stiffness = 0.
00210       if self.compliance is None:
00211         self.compliance = 0.
00212     else:
00213       self.header = std_msgs.msg.Header()
00214       self.x = geometry_msgs.msg.PoseStamped()
00215       self.x_desi = geometry_msgs.msg.PoseStamped()
00216       self.x_desi_filtered = geometry_msgs.msg.PoseStamped()
00217       self.x_err = geometry_msgs.msg.Twist()
00218       self.xd = geometry_msgs.msg.Twist()
00219       self.xd_desi = geometry_msgs.msg.Twist()
00220       self.F = geometry_msgs.msg.Wrench()
00221       self.q_proxy = []
00222       self.qd_pose = []
00223       self.qd_posture = []
00224       self.qd_posture_raw = []
00225       self.qd_desi = []
00226       self.tau = []
00227       self.J = std_msgs.msg.Float64MultiArray()
00228       self.N = std_msgs.msg.Float64MultiArray()
00229       self.df = 0.
00230       self.dx = 0.
00231       self.Df = 0.
00232       self.Dx = 0.
00233       self.stiffness = 0.
00234       self.compliance = 0.
00235 
00236   def _get_types(self):
00237     """
00238     internal API method
00239     """
00240     return self._slot_types
00241 
00242   def serialize(self, buff):
00243     """
00244     serialize message into buffer
00245     :param buff: buffer, ``StringIO``
00246     """
00247     try:
00248       _x = self
00249       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00250       _x = self.header.frame_id
00251       length = len(_x)
00252       if python3 or type(_x) == unicode:
00253         _x = _x.encode('utf-8')
00254         length = len(_x)
00255       buff.write(struct.pack('<I%ss'%length, length, _x))
00256       _x = self
00257       buff.write(_struct_3I.pack(_x.x.header.seq, _x.x.header.stamp.secs, _x.x.header.stamp.nsecs))
00258       _x = self.x.header.frame_id
00259       length = len(_x)
00260       if python3 or type(_x) == unicode:
00261         _x = _x.encode('utf-8')
00262         length = len(_x)
00263       buff.write(struct.pack('<I%ss'%length, length, _x))
00264       _x = self
00265       buff.write(_struct_7d3I.pack(_x.x.pose.position.x, _x.x.pose.position.y, _x.x.pose.position.z, _x.x.pose.orientation.x, _x.x.pose.orientation.y, _x.x.pose.orientation.z, _x.x.pose.orientation.w, _x.x_desi.header.seq, _x.x_desi.header.stamp.secs, _x.x_desi.header.stamp.nsecs))
00266       _x = self.x_desi.header.frame_id
00267       length = len(_x)
00268       if python3 or type(_x) == unicode:
00269         _x = _x.encode('utf-8')
00270         length = len(_x)
00271       buff.write(struct.pack('<I%ss'%length, length, _x))
00272       _x = self
00273       buff.write(_struct_7d3I.pack(_x.x_desi.pose.position.x, _x.x_desi.pose.position.y, _x.x_desi.pose.position.z, _x.x_desi.pose.orientation.x, _x.x_desi.pose.orientation.y, _x.x_desi.pose.orientation.z, _x.x_desi.pose.orientation.w, _x.x_desi_filtered.header.seq, _x.x_desi_filtered.header.stamp.secs, _x.x_desi_filtered.header.stamp.nsecs))
00274       _x = self.x_desi_filtered.header.frame_id
00275       length = len(_x)
00276       if python3 or type(_x) == unicode:
00277         _x = _x.encode('utf-8')
00278         length = len(_x)
00279       buff.write(struct.pack('<I%ss'%length, length, _x))
00280       _x = self
00281       buff.write(_struct_31d.pack(_x.x_desi_filtered.pose.position.x, _x.x_desi_filtered.pose.position.y, _x.x_desi_filtered.pose.position.z, _x.x_desi_filtered.pose.orientation.x, _x.x_desi_filtered.pose.orientation.y, _x.x_desi_filtered.pose.orientation.z, _x.x_desi_filtered.pose.orientation.w, _x.x_err.linear.x, _x.x_err.linear.y, _x.x_err.linear.z, _x.x_err.angular.x, _x.x_err.angular.y, _x.x_err.angular.z, _x.xd.linear.x, _x.xd.linear.y, _x.xd.linear.z, _x.xd.angular.x, _x.xd.angular.y, _x.xd.angular.z, _x.xd_desi.linear.x, _x.xd_desi.linear.y, _x.xd_desi.linear.z, _x.xd_desi.angular.x, _x.xd_desi.angular.y, _x.xd_desi.angular.z, _x.F.force.x, _x.F.force.y, _x.F.force.z, _x.F.torque.x, _x.F.torque.y, _x.F.torque.z))
00282       length = len(self.q_proxy)
00283       buff.write(_struct_I.pack(length))
00284       pattern = '<%sd'%length
00285       buff.write(struct.pack(pattern, *self.q_proxy))
00286       length = len(self.qd_pose)
00287       buff.write(_struct_I.pack(length))
00288       pattern = '<%sd'%length
00289       buff.write(struct.pack(pattern, *self.qd_pose))
00290       length = len(self.qd_posture)
00291       buff.write(_struct_I.pack(length))
00292       pattern = '<%sd'%length
00293       buff.write(struct.pack(pattern, *self.qd_posture))
00294       length = len(self.qd_posture_raw)
00295       buff.write(_struct_I.pack(length))
00296       pattern = '<%sd'%length
00297       buff.write(struct.pack(pattern, *self.qd_posture_raw))
00298       length = len(self.qd_desi)
00299       buff.write(_struct_I.pack(length))
00300       pattern = '<%sd'%length
00301       buff.write(struct.pack(pattern, *self.qd_desi))
00302       length = len(self.tau)
00303       buff.write(_struct_I.pack(length))
00304       pattern = '<%sd'%length
00305       buff.write(struct.pack(pattern, *self.tau))
00306       length = len(self.J.layout.dim)
00307       buff.write(_struct_I.pack(length))
00308       for val1 in self.J.layout.dim:
00309         _x = val1.label
00310         length = len(_x)
00311         if python3 or type(_x) == unicode:
00312           _x = _x.encode('utf-8')
00313           length = len(_x)
00314         buff.write(struct.pack('<I%ss'%length, length, _x))
00315         _x = val1
00316         buff.write(_struct_2I.pack(_x.size, _x.stride))
00317       buff.write(_struct_I.pack(self.J.layout.data_offset))
00318       length = len(self.J.data)
00319       buff.write(_struct_I.pack(length))
00320       pattern = '<%sd'%length
00321       buff.write(struct.pack(pattern, *self.J.data))
00322       length = len(self.N.layout.dim)
00323       buff.write(_struct_I.pack(length))
00324       for val1 in self.N.layout.dim:
00325         _x = val1.label
00326         length = len(_x)
00327         if python3 or type(_x) == unicode:
00328           _x = _x.encode('utf-8')
00329           length = len(_x)
00330         buff.write(struct.pack('<I%ss'%length, length, _x))
00331         _x = val1
00332         buff.write(_struct_2I.pack(_x.size, _x.stride))
00333       buff.write(_struct_I.pack(self.N.layout.data_offset))
00334       length = len(self.N.data)
00335       buff.write(_struct_I.pack(length))
00336       pattern = '<%sd'%length
00337       buff.write(struct.pack(pattern, *self.N.data))
00338       _x = self
00339       buff.write(_struct_6d.pack(_x.df, _x.dx, _x.Df, _x.Dx, _x.stiffness, _x.compliance))
00340     except struct.error as se: self._check_types(se)
00341     except TypeError as te: self._check_types(te)
00342 
00343   def deserialize(self, str):
00344     """
00345     unpack serialized message in str into this message instance
00346     :param str: byte array of serialized message, ``str``
00347     """
00348     try:
00349       if self.header is None:
00350         self.header = std_msgs.msg.Header()
00351       if self.x is None:
00352         self.x = geometry_msgs.msg.PoseStamped()
00353       if self.x_desi is None:
00354         self.x_desi = geometry_msgs.msg.PoseStamped()
00355       if self.x_desi_filtered is None:
00356         self.x_desi_filtered = geometry_msgs.msg.PoseStamped()
00357       if self.x_err is None:
00358         self.x_err = geometry_msgs.msg.Twist()
00359       if self.xd is None:
00360         self.xd = geometry_msgs.msg.Twist()
00361       if self.xd_desi is None:
00362         self.xd_desi = geometry_msgs.msg.Twist()
00363       if self.F is None:
00364         self.F = geometry_msgs.msg.Wrench()
00365       if self.J is None:
00366         self.J = std_msgs.msg.Float64MultiArray()
00367       if self.N is None:
00368         self.N = std_msgs.msg.Float64MultiArray()
00369       end = 0
00370       _x = self
00371       start = end
00372       end += 12
00373       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00374       start = end
00375       end += 4
00376       (length,) = _struct_I.unpack(str[start:end])
00377       start = end
00378       end += length
00379       if python3:
00380         self.header.frame_id = str[start:end].decode('utf-8')
00381       else:
00382         self.header.frame_id = str[start:end]
00383       _x = self
00384       start = end
00385       end += 12
00386       (_x.x.header.seq, _x.x.header.stamp.secs, _x.x.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       if python3:
00393         self.x.header.frame_id = str[start:end].decode('utf-8')
00394       else:
00395         self.x.header.frame_id = str[start:end]
00396       _x = self
00397       start = end
00398       end += 68
00399       (_x.x.pose.position.x, _x.x.pose.position.y, _x.x.pose.position.z, _x.x.pose.orientation.x, _x.x.pose.orientation.y, _x.x.pose.orientation.z, _x.x.pose.orientation.w, _x.x_desi.header.seq, _x.x_desi.header.stamp.secs, _x.x_desi.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00400       start = end
00401       end += 4
00402       (length,) = _struct_I.unpack(str[start:end])
00403       start = end
00404       end += length
00405       if python3:
00406         self.x_desi.header.frame_id = str[start:end].decode('utf-8')
00407       else:
00408         self.x_desi.header.frame_id = str[start:end]
00409       _x = self
00410       start = end
00411       end += 68
00412       (_x.x_desi.pose.position.x, _x.x_desi.pose.position.y, _x.x_desi.pose.position.z, _x.x_desi.pose.orientation.x, _x.x_desi.pose.orientation.y, _x.x_desi.pose.orientation.z, _x.x_desi.pose.orientation.w, _x.x_desi_filtered.header.seq, _x.x_desi_filtered.header.stamp.secs, _x.x_desi_filtered.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00413       start = end
00414       end += 4
00415       (length,) = _struct_I.unpack(str[start:end])
00416       start = end
00417       end += length
00418       if python3:
00419         self.x_desi_filtered.header.frame_id = str[start:end].decode('utf-8')
00420       else:
00421         self.x_desi_filtered.header.frame_id = str[start:end]
00422       _x = self
00423       start = end
00424       end += 248
00425       (_x.x_desi_filtered.pose.position.x, _x.x_desi_filtered.pose.position.y, _x.x_desi_filtered.pose.position.z, _x.x_desi_filtered.pose.orientation.x, _x.x_desi_filtered.pose.orientation.y, _x.x_desi_filtered.pose.orientation.z, _x.x_desi_filtered.pose.orientation.w, _x.x_err.linear.x, _x.x_err.linear.y, _x.x_err.linear.z, _x.x_err.angular.x, _x.x_err.angular.y, _x.x_err.angular.z, _x.xd.linear.x, _x.xd.linear.y, _x.xd.linear.z, _x.xd.angular.x, _x.xd.angular.y, _x.xd.angular.z, _x.xd_desi.linear.x, _x.xd_desi.linear.y, _x.xd_desi.linear.z, _x.xd_desi.angular.x, _x.xd_desi.angular.y, _x.xd_desi.angular.z, _x.F.force.x, _x.F.force.y, _x.F.force.z, _x.F.torque.x, _x.F.torque.y, _x.F.torque.z,) = _struct_31d.unpack(str[start:end])
00426       start = end
00427       end += 4
00428       (length,) = _struct_I.unpack(str[start:end])
00429       pattern = '<%sd'%length
00430       start = end
00431       end += struct.calcsize(pattern)
00432       self.q_proxy = struct.unpack(pattern, str[start:end])
00433       start = end
00434       end += 4
00435       (length,) = _struct_I.unpack(str[start:end])
00436       pattern = '<%sd'%length
00437       start = end
00438       end += struct.calcsize(pattern)
00439       self.qd_pose = struct.unpack(pattern, str[start:end])
00440       start = end
00441       end += 4
00442       (length,) = _struct_I.unpack(str[start:end])
00443       pattern = '<%sd'%length
00444       start = end
00445       end += struct.calcsize(pattern)
00446       self.qd_posture = struct.unpack(pattern, str[start:end])
00447       start = end
00448       end += 4
00449       (length,) = _struct_I.unpack(str[start:end])
00450       pattern = '<%sd'%length
00451       start = end
00452       end += struct.calcsize(pattern)
00453       self.qd_posture_raw = struct.unpack(pattern, str[start:end])
00454       start = end
00455       end += 4
00456       (length,) = _struct_I.unpack(str[start:end])
00457       pattern = '<%sd'%length
00458       start = end
00459       end += struct.calcsize(pattern)
00460       self.qd_desi = struct.unpack(pattern, str[start:end])
00461       start = end
00462       end += 4
00463       (length,) = _struct_I.unpack(str[start:end])
00464       pattern = '<%sd'%length
00465       start = end
00466       end += struct.calcsize(pattern)
00467       self.tau = struct.unpack(pattern, str[start:end])
00468       start = end
00469       end += 4
00470       (length,) = _struct_I.unpack(str[start:end])
00471       self.J.layout.dim = []
00472       for i in range(0, length):
00473         val1 = std_msgs.msg.MultiArrayDimension()
00474         start = end
00475         end += 4
00476         (length,) = _struct_I.unpack(str[start:end])
00477         start = end
00478         end += length
00479         if python3:
00480           val1.label = str[start:end].decode('utf-8')
00481         else:
00482           val1.label = str[start:end]
00483         _x = val1
00484         start = end
00485         end += 8
00486         (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end])
00487         self.J.layout.dim.append(val1)
00488       start = end
00489       end += 4
00490       (self.J.layout.data_offset,) = _struct_I.unpack(str[start:end])
00491       start = end
00492       end += 4
00493       (length,) = _struct_I.unpack(str[start:end])
00494       pattern = '<%sd'%length
00495       start = end
00496       end += struct.calcsize(pattern)
00497       self.J.data = struct.unpack(pattern, str[start:end])
00498       start = end
00499       end += 4
00500       (length,) = _struct_I.unpack(str[start:end])
00501       self.N.layout.dim = []
00502       for i in range(0, length):
00503         val1 = std_msgs.msg.MultiArrayDimension()
00504         start = end
00505         end += 4
00506         (length,) = _struct_I.unpack(str[start:end])
00507         start = end
00508         end += length
00509         if python3:
00510           val1.label = str[start:end].decode('utf-8')
00511         else:
00512           val1.label = str[start:end]
00513         _x = val1
00514         start = end
00515         end += 8
00516         (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end])
00517         self.N.layout.dim.append(val1)
00518       start = end
00519       end += 4
00520       (self.N.layout.data_offset,) = _struct_I.unpack(str[start:end])
00521       start = end
00522       end += 4
00523       (length,) = _struct_I.unpack(str[start:end])
00524       pattern = '<%sd'%length
00525       start = end
00526       end += struct.calcsize(pattern)
00527       self.N.data = struct.unpack(pattern, str[start:end])
00528       _x = self
00529       start = end
00530       end += 48
00531       (_x.df, _x.dx, _x.Df, _x.Dx, _x.stiffness, _x.compliance,) = _struct_6d.unpack(str[start:end])
00532       return self
00533     except struct.error as e:
00534       raise genpy.DeserializationError(e) #most likely buffer underfill
00535 
00536 
00537   def serialize_numpy(self, buff, numpy):
00538     """
00539     serialize message with numpy array types into buffer
00540     :param buff: buffer, ``StringIO``
00541     :param numpy: numpy python module
00542     """
00543     try:
00544       _x = self
00545       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00546       _x = self.header.frame_id
00547       length = len(_x)
00548       if python3 or type(_x) == unicode:
00549         _x = _x.encode('utf-8')
00550         length = len(_x)
00551       buff.write(struct.pack('<I%ss'%length, length, _x))
00552       _x = self
00553       buff.write(_struct_3I.pack(_x.x.header.seq, _x.x.header.stamp.secs, _x.x.header.stamp.nsecs))
00554       _x = self.x.header.frame_id
00555       length = len(_x)
00556       if python3 or type(_x) == unicode:
00557         _x = _x.encode('utf-8')
00558         length = len(_x)
00559       buff.write(struct.pack('<I%ss'%length, length, _x))
00560       _x = self
00561       buff.write(_struct_7d3I.pack(_x.x.pose.position.x, _x.x.pose.position.y, _x.x.pose.position.z, _x.x.pose.orientation.x, _x.x.pose.orientation.y, _x.x.pose.orientation.z, _x.x.pose.orientation.w, _x.x_desi.header.seq, _x.x_desi.header.stamp.secs, _x.x_desi.header.stamp.nsecs))
00562       _x = self.x_desi.header.frame_id
00563       length = len(_x)
00564       if python3 or type(_x) == unicode:
00565         _x = _x.encode('utf-8')
00566         length = len(_x)
00567       buff.write(struct.pack('<I%ss'%length, length, _x))
00568       _x = self
00569       buff.write(_struct_7d3I.pack(_x.x_desi.pose.position.x, _x.x_desi.pose.position.y, _x.x_desi.pose.position.z, _x.x_desi.pose.orientation.x, _x.x_desi.pose.orientation.y, _x.x_desi.pose.orientation.z, _x.x_desi.pose.orientation.w, _x.x_desi_filtered.header.seq, _x.x_desi_filtered.header.stamp.secs, _x.x_desi_filtered.header.stamp.nsecs))
00570       _x = self.x_desi_filtered.header.frame_id
00571       length = len(_x)
00572       if python3 or type(_x) == unicode:
00573         _x = _x.encode('utf-8')
00574         length = len(_x)
00575       buff.write(struct.pack('<I%ss'%length, length, _x))
00576       _x = self
00577       buff.write(_struct_31d.pack(_x.x_desi_filtered.pose.position.x, _x.x_desi_filtered.pose.position.y, _x.x_desi_filtered.pose.position.z, _x.x_desi_filtered.pose.orientation.x, _x.x_desi_filtered.pose.orientation.y, _x.x_desi_filtered.pose.orientation.z, _x.x_desi_filtered.pose.orientation.w, _x.x_err.linear.x, _x.x_err.linear.y, _x.x_err.linear.z, _x.x_err.angular.x, _x.x_err.angular.y, _x.x_err.angular.z, _x.xd.linear.x, _x.xd.linear.y, _x.xd.linear.z, _x.xd.angular.x, _x.xd.angular.y, _x.xd.angular.z, _x.xd_desi.linear.x, _x.xd_desi.linear.y, _x.xd_desi.linear.z, _x.xd_desi.angular.x, _x.xd_desi.angular.y, _x.xd_desi.angular.z, _x.F.force.x, _x.F.force.y, _x.F.force.z, _x.F.torque.x, _x.F.torque.y, _x.F.torque.z))
00578       length = len(self.q_proxy)
00579       buff.write(_struct_I.pack(length))
00580       pattern = '<%sd'%length
00581       buff.write(self.q_proxy.tostring())
00582       length = len(self.qd_pose)
00583       buff.write(_struct_I.pack(length))
00584       pattern = '<%sd'%length
00585       buff.write(self.qd_pose.tostring())
00586       length = len(self.qd_posture)
00587       buff.write(_struct_I.pack(length))
00588       pattern = '<%sd'%length
00589       buff.write(self.qd_posture.tostring())
00590       length = len(self.qd_posture_raw)
00591       buff.write(_struct_I.pack(length))
00592       pattern = '<%sd'%length
00593       buff.write(self.qd_posture_raw.tostring())
00594       length = len(self.qd_desi)
00595       buff.write(_struct_I.pack(length))
00596       pattern = '<%sd'%length
00597       buff.write(self.qd_desi.tostring())
00598       length = len(self.tau)
00599       buff.write(_struct_I.pack(length))
00600       pattern = '<%sd'%length
00601       buff.write(self.tau.tostring())
00602       length = len(self.J.layout.dim)
00603       buff.write(_struct_I.pack(length))
00604       for val1 in self.J.layout.dim:
00605         _x = val1.label
00606         length = len(_x)
00607         if python3 or type(_x) == unicode:
00608           _x = _x.encode('utf-8')
00609           length = len(_x)
00610         buff.write(struct.pack('<I%ss'%length, length, _x))
00611         _x = val1
00612         buff.write(_struct_2I.pack(_x.size, _x.stride))
00613       buff.write(_struct_I.pack(self.J.layout.data_offset))
00614       length = len(self.J.data)
00615       buff.write(_struct_I.pack(length))
00616       pattern = '<%sd'%length
00617       buff.write(self.J.data.tostring())
00618       length = len(self.N.layout.dim)
00619       buff.write(_struct_I.pack(length))
00620       for val1 in self.N.layout.dim:
00621         _x = val1.label
00622         length = len(_x)
00623         if python3 or type(_x) == unicode:
00624           _x = _x.encode('utf-8')
00625           length = len(_x)
00626         buff.write(struct.pack('<I%ss'%length, length, _x))
00627         _x = val1
00628         buff.write(_struct_2I.pack(_x.size, _x.stride))
00629       buff.write(_struct_I.pack(self.N.layout.data_offset))
00630       length = len(self.N.data)
00631       buff.write(_struct_I.pack(length))
00632       pattern = '<%sd'%length
00633       buff.write(self.N.data.tostring())
00634       _x = self
00635       buff.write(_struct_6d.pack(_x.df, _x.dx, _x.Df, _x.Dx, _x.stiffness, _x.compliance))
00636     except struct.error as se: self._check_types(se)
00637     except TypeError as te: self._check_types(te)
00638 
00639   def deserialize_numpy(self, str, numpy):
00640     """
00641     unpack serialized message in str into this message instance using numpy for array types
00642     :param str: byte array of serialized message, ``str``
00643     :param numpy: numpy python module
00644     """
00645     try:
00646       if self.header is None:
00647         self.header = std_msgs.msg.Header()
00648       if self.x is None:
00649         self.x = geometry_msgs.msg.PoseStamped()
00650       if self.x_desi is None:
00651         self.x_desi = geometry_msgs.msg.PoseStamped()
00652       if self.x_desi_filtered is None:
00653         self.x_desi_filtered = geometry_msgs.msg.PoseStamped()
00654       if self.x_err is None:
00655         self.x_err = geometry_msgs.msg.Twist()
00656       if self.xd is None:
00657         self.xd = geometry_msgs.msg.Twist()
00658       if self.xd_desi is None:
00659         self.xd_desi = geometry_msgs.msg.Twist()
00660       if self.F is None:
00661         self.F = geometry_msgs.msg.Wrench()
00662       if self.J is None:
00663         self.J = std_msgs.msg.Float64MultiArray()
00664       if self.N is None:
00665         self.N = std_msgs.msg.Float64MultiArray()
00666       end = 0
00667       _x = self
00668       start = end
00669       end += 12
00670       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00671       start = end
00672       end += 4
00673       (length,) = _struct_I.unpack(str[start:end])
00674       start = end
00675       end += length
00676       if python3:
00677         self.header.frame_id = str[start:end].decode('utf-8')
00678       else:
00679         self.header.frame_id = str[start:end]
00680       _x = self
00681       start = end
00682       end += 12
00683       (_x.x.header.seq, _x.x.header.stamp.secs, _x.x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00684       start = end
00685       end += 4
00686       (length,) = _struct_I.unpack(str[start:end])
00687       start = end
00688       end += length
00689       if python3:
00690         self.x.header.frame_id = str[start:end].decode('utf-8')
00691       else:
00692         self.x.header.frame_id = str[start:end]
00693       _x = self
00694       start = end
00695       end += 68
00696       (_x.x.pose.position.x, _x.x.pose.position.y, _x.x.pose.position.z, _x.x.pose.orientation.x, _x.x.pose.orientation.y, _x.x.pose.orientation.z, _x.x.pose.orientation.w, _x.x_desi.header.seq, _x.x_desi.header.stamp.secs, _x.x_desi.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00697       start = end
00698       end += 4
00699       (length,) = _struct_I.unpack(str[start:end])
00700       start = end
00701       end += length
00702       if python3:
00703         self.x_desi.header.frame_id = str[start:end].decode('utf-8')
00704       else:
00705         self.x_desi.header.frame_id = str[start:end]
00706       _x = self
00707       start = end
00708       end += 68
00709       (_x.x_desi.pose.position.x, _x.x_desi.pose.position.y, _x.x_desi.pose.position.z, _x.x_desi.pose.orientation.x, _x.x_desi.pose.orientation.y, _x.x_desi.pose.orientation.z, _x.x_desi.pose.orientation.w, _x.x_desi_filtered.header.seq, _x.x_desi_filtered.header.stamp.secs, _x.x_desi_filtered.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00710       start = end
00711       end += 4
00712       (length,) = _struct_I.unpack(str[start:end])
00713       start = end
00714       end += length
00715       if python3:
00716         self.x_desi_filtered.header.frame_id = str[start:end].decode('utf-8')
00717       else:
00718         self.x_desi_filtered.header.frame_id = str[start:end]
00719       _x = self
00720       start = end
00721       end += 248
00722       (_x.x_desi_filtered.pose.position.x, _x.x_desi_filtered.pose.position.y, _x.x_desi_filtered.pose.position.z, _x.x_desi_filtered.pose.orientation.x, _x.x_desi_filtered.pose.orientation.y, _x.x_desi_filtered.pose.orientation.z, _x.x_desi_filtered.pose.orientation.w, _x.x_err.linear.x, _x.x_err.linear.y, _x.x_err.linear.z, _x.x_err.angular.x, _x.x_err.angular.y, _x.x_err.angular.z, _x.xd.linear.x, _x.xd.linear.y, _x.xd.linear.z, _x.xd.angular.x, _x.xd.angular.y, _x.xd.angular.z, _x.xd_desi.linear.x, _x.xd_desi.linear.y, _x.xd_desi.linear.z, _x.xd_desi.angular.x, _x.xd_desi.angular.y, _x.xd_desi.angular.z, _x.F.force.x, _x.F.force.y, _x.F.force.z, _x.F.torque.x, _x.F.torque.y, _x.F.torque.z,) = _struct_31d.unpack(str[start:end])
00723       start = end
00724       end += 4
00725       (length,) = _struct_I.unpack(str[start:end])
00726       pattern = '<%sd'%length
00727       start = end
00728       end += struct.calcsize(pattern)
00729       self.q_proxy = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00730       start = end
00731       end += 4
00732       (length,) = _struct_I.unpack(str[start:end])
00733       pattern = '<%sd'%length
00734       start = end
00735       end += struct.calcsize(pattern)
00736       self.qd_pose = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00737       start = end
00738       end += 4
00739       (length,) = _struct_I.unpack(str[start:end])
00740       pattern = '<%sd'%length
00741       start = end
00742       end += struct.calcsize(pattern)
00743       self.qd_posture = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00744       start = end
00745       end += 4
00746       (length,) = _struct_I.unpack(str[start:end])
00747       pattern = '<%sd'%length
00748       start = end
00749       end += struct.calcsize(pattern)
00750       self.qd_posture_raw = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00751       start = end
00752       end += 4
00753       (length,) = _struct_I.unpack(str[start:end])
00754       pattern = '<%sd'%length
00755       start = end
00756       end += struct.calcsize(pattern)
00757       self.qd_desi = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00758       start = end
00759       end += 4
00760       (length,) = _struct_I.unpack(str[start:end])
00761       pattern = '<%sd'%length
00762       start = end
00763       end += struct.calcsize(pattern)
00764       self.tau = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00765       start = end
00766       end += 4
00767       (length,) = _struct_I.unpack(str[start:end])
00768       self.J.layout.dim = []
00769       for i in range(0, length):
00770         val1 = std_msgs.msg.MultiArrayDimension()
00771         start = end
00772         end += 4
00773         (length,) = _struct_I.unpack(str[start:end])
00774         start = end
00775         end += length
00776         if python3:
00777           val1.label = str[start:end].decode('utf-8')
00778         else:
00779           val1.label = str[start:end]
00780         _x = val1
00781         start = end
00782         end += 8
00783         (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end])
00784         self.J.layout.dim.append(val1)
00785       start = end
00786       end += 4
00787       (self.J.layout.data_offset,) = _struct_I.unpack(str[start:end])
00788       start = end
00789       end += 4
00790       (length,) = _struct_I.unpack(str[start:end])
00791       pattern = '<%sd'%length
00792       start = end
00793       end += struct.calcsize(pattern)
00794       self.J.data = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00795       start = end
00796       end += 4
00797       (length,) = _struct_I.unpack(str[start:end])
00798       self.N.layout.dim = []
00799       for i in range(0, length):
00800         val1 = std_msgs.msg.MultiArrayDimension()
00801         start = end
00802         end += 4
00803         (length,) = _struct_I.unpack(str[start:end])
00804         start = end
00805         end += length
00806         if python3:
00807           val1.label = str[start:end].decode('utf-8')
00808         else:
00809           val1.label = str[start:end]
00810         _x = val1
00811         start = end
00812         end += 8
00813         (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end])
00814         self.N.layout.dim.append(val1)
00815       start = end
00816       end += 4
00817       (self.N.layout.data_offset,) = _struct_I.unpack(str[start:end])
00818       start = end
00819       end += 4
00820       (length,) = _struct_I.unpack(str[start:end])
00821       pattern = '<%sd'%length
00822       start = end
00823       end += struct.calcsize(pattern)
00824       self.N.data = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00825       _x = self
00826       start = end
00827       end += 48
00828       (_x.df, _x.dx, _x.Df, _x.Dx, _x.stiffness, _x.compliance,) = _struct_6d.unpack(str[start:end])
00829       return self
00830     except struct.error as e:
00831       raise genpy.DeserializationError(e) #most likely buffer underfill
00832 
00833 _struct_I = genpy.struct_I
00834 _struct_6d = struct.Struct("<6d")
00835 _struct_2I = struct.Struct("<2I")
00836 _struct_3I = struct.Struct("<3I")
00837 _struct_7d3I = struct.Struct("<7d3I")
00838 _struct_31d = struct.Struct("<31d")


pr2_manipulation_controllers
Author(s): Kaijen Hsiao, Stu Glaser, Adam Leeper
autogenerated on Fri Jan 3 2014 11:51:13