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