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