_EECartImpedActionFeedback.py
Go to the documentation of this file.
00001 """autogenerated by genpy from ee_cart_imped_msgs/EECartImpedActionFeedback.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 ee_cart_imped_msgs.msg
00008 import geometry_msgs.msg
00009 import genpy
00010 import actionlib_msgs.msg
00011 import std_msgs.msg
00012 
00013 class EECartImpedActionFeedback(genpy.Message):
00014   _md5sum = "cf14a7f10d332262a83da91f99884b31"
00015   _type = "ee_cart_imped_msgs/EECartImpedActionFeedback"
00016   _has_header = True #flag to mark the presence of a Header object
00017   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018 
00019 Header header
00020 actionlib_msgs/GoalStatus status
00021 EECartImpedFeedback feedback
00022 
00023 ================================================================================
00024 MSG: std_msgs/Header
00025 # Standard metadata for higher-level stamped data types.
00026 # This is generally used to communicate timestamped data 
00027 # in a particular coordinate frame.
00028 # 
00029 # sequence ID: consecutively increasing ID 
00030 uint32 seq
00031 #Two-integer timestamp that is expressed as:
00032 # * stamp.secs: seconds (stamp_secs) since epoch
00033 # * stamp.nsecs: nanoseconds since stamp_secs
00034 # time-handling sugar is provided by the client library
00035 time stamp
00036 #Frame this data is associated with
00037 # 0: no frame
00038 # 1: global frame
00039 string frame_id
00040 
00041 ================================================================================
00042 MSG: actionlib_msgs/GoalStatus
00043 GoalID goal_id
00044 uint8 status
00045 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00046 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00047 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00048                             #   and has since completed its execution (Terminal State)
00049 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00050 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00051                             #    to some failure (Terminal State)
00052 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00053                             #    because the goal was unattainable or invalid (Terminal State)
00054 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00055                             #    and has not yet completed execution
00056 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00057                             #    but the action server has not yet confirmed that the goal is canceled
00058 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00059                             #    and was successfully cancelled (Terminal State)
00060 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00061                             #    sent over the wire by an action server
00062 
00063 #Allow for the user to associate a string with GoalStatus for debugging
00064 string text
00065 
00066 
00067 ================================================================================
00068 MSG: actionlib_msgs/GoalID
00069 # The stamp should store the time at which this goal was requested.
00070 # It is used by an action server when it tries to preempt all
00071 # goals that were requested before a certain time
00072 time stamp
00073 
00074 # The id provides a way to associate feedback and
00075 # result message with specific goal requests. The id
00076 # specified must be unique.
00077 string id
00078 
00079 
00080 ================================================================================
00081 MSG: ee_cart_imped_msgs/EECartImpedFeedback
00082 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00083 #feedback
00084 #current pose and squared error in force 
00085 #and the running time of this goal so far
00086 Header header
00087 ee_cart_imped_msgs/StiffPoint[] goal
00088 ee_cart_imped_msgs/StiffPoint initial_point
00089 ee_cart_imped_msgs/StiffPoint desired
00090 ee_cart_imped_msgs/StiffPoint actual_pose
00091 float64 effort_sq_error
00092 float64[] requested_joint_efforts
00093 float64[] actual_joint_efforts
00094 duration running_time
00095 
00096 
00097 
00098 ================================================================================
00099 MSG: ee_cart_imped_msgs/StiffPoint
00100 Header header
00101 #The pose to achieve in the stiffness directions
00102 geometry_msgs/Pose pose
00103 #Wrench or stiffness for each dimension
00104 geometry_msgs/Wrench wrench_or_stiffness
00105 #The following are True if a force/torque should
00106 #be exerted and False if a stiffness should be used.
00107 bool isForceX
00108 bool isForceY
00109 bool isForceZ
00110 bool isTorqueX
00111 bool isTorqueY
00112 bool isTorqueZ
00113 #The time from the start of the trajectory that this
00114 #point should be achieved.
00115 duration time_from_start
00116 ================================================================================
00117 MSG: geometry_msgs/Pose
00118 # A representation of pose in free space, composed of postion and orientation. 
00119 Point position
00120 Quaternion orientation
00121 
00122 ================================================================================
00123 MSG: geometry_msgs/Point
00124 # This contains the position of a point in free space
00125 float64 x
00126 float64 y
00127 float64 z
00128 
00129 ================================================================================
00130 MSG: geometry_msgs/Quaternion
00131 # This represents an orientation in free space in quaternion form.
00132 
00133 float64 x
00134 float64 y
00135 float64 z
00136 float64 w
00137 
00138 ================================================================================
00139 MSG: geometry_msgs/Wrench
00140 # This represents force in free space, seperated into 
00141 # it's linear and angular parts.  
00142 Vector3  force
00143 Vector3  torque
00144 
00145 ================================================================================
00146 MSG: geometry_msgs/Vector3
00147 # This represents a vector in free space. 
00148 
00149 float64 x
00150 float64 y
00151 float64 z
00152 """
00153   __slots__ = ['header','status','feedback']
00154   _slot_types = ['std_msgs/Header','actionlib_msgs/GoalStatus','ee_cart_imped_msgs/EECartImpedFeedback']
00155 
00156   def __init__(self, *args, **kwds):
00157     """
00158     Constructor. Any message fields that are implicitly/explicitly
00159     set to None will be assigned a default value. The recommend
00160     use is keyword arguments as this is more robust to future message
00161     changes.  You cannot mix in-order arguments and keyword arguments.
00162 
00163     The available fields are:
00164        header,status,feedback
00165 
00166     :param args: complete set of field values, in .msg order
00167     :param kwds: use keyword arguments corresponding to message field names
00168     to set specific fields.
00169     """
00170     if args or kwds:
00171       super(EECartImpedActionFeedback, self).__init__(*args, **kwds)
00172       #message fields cannot be None, assign default values for those that are
00173       if self.header is None:
00174         self.header = std_msgs.msg.Header()
00175       if self.status is None:
00176         self.status = actionlib_msgs.msg.GoalStatus()
00177       if self.feedback is None:
00178         self.feedback = ee_cart_imped_msgs.msg.EECartImpedFeedback()
00179     else:
00180       self.header = std_msgs.msg.Header()
00181       self.status = actionlib_msgs.msg.GoalStatus()
00182       self.feedback = ee_cart_imped_msgs.msg.EECartImpedFeedback()
00183 
00184   def _get_types(self):
00185     """
00186     internal API method
00187     """
00188     return self._slot_types
00189 
00190   def serialize(self, buff):
00191     """
00192     serialize message into buffer
00193     :param buff: buffer, ``StringIO``
00194     """
00195     try:
00196       _x = self
00197       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00198       _x = self.header.frame_id
00199       length = len(_x)
00200       if python3 or type(_x) == unicode:
00201         _x = _x.encode('utf-8')
00202         length = len(_x)
00203       buff.write(struct.pack('<I%ss'%length, length, _x))
00204       _x = self
00205       buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00206       _x = self.status.goal_id.id
00207       length = len(_x)
00208       if python3 or type(_x) == unicode:
00209         _x = _x.encode('utf-8')
00210         length = len(_x)
00211       buff.write(struct.pack('<I%ss'%length, length, _x))
00212       buff.write(_struct_B.pack(self.status.status))
00213       _x = self.status.text
00214       length = len(_x)
00215       if python3 or type(_x) == unicode:
00216         _x = _x.encode('utf-8')
00217         length = len(_x)
00218       buff.write(struct.pack('<I%ss'%length, length, _x))
00219       _x = self
00220       buff.write(_struct_3I.pack(_x.feedback.header.seq, _x.feedback.header.stamp.secs, _x.feedback.header.stamp.nsecs))
00221       _x = self.feedback.header.frame_id
00222       length = len(_x)
00223       if python3 or type(_x) == unicode:
00224         _x = _x.encode('utf-8')
00225         length = len(_x)
00226       buff.write(struct.pack('<I%ss'%length, length, _x))
00227       length = len(self.feedback.goal)
00228       buff.write(_struct_I.pack(length))
00229       for val1 in self.feedback.goal:
00230         _v1 = val1.header
00231         buff.write(_struct_I.pack(_v1.seq))
00232         _v2 = _v1.stamp
00233         _x = _v2
00234         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00235         _x = _v1.frame_id
00236         length = len(_x)
00237         if python3 or type(_x) == unicode:
00238           _x = _x.encode('utf-8')
00239           length = len(_x)
00240         buff.write(struct.pack('<I%ss'%length, length, _x))
00241         _v3 = val1.pose
00242         _v4 = _v3.position
00243         _x = _v4
00244         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00245         _v5 = _v3.orientation
00246         _x = _v5
00247         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00248         _v6 = val1.wrench_or_stiffness
00249         _v7 = _v6.force
00250         _x = _v7
00251         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00252         _v8 = _v6.torque
00253         _x = _v8
00254         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00255         _x = val1
00256         buff.write(_struct_6B.pack(_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ))
00257         _v9 = val1.time_from_start
00258         _x = _v9
00259         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00260       _x = self
00261       buff.write(_struct_3I.pack(_x.feedback.initial_point.header.seq, _x.feedback.initial_point.header.stamp.secs, _x.feedback.initial_point.header.stamp.nsecs))
00262       _x = self.feedback.initial_point.header.frame_id
00263       length = len(_x)
00264       if python3 or type(_x) == unicode:
00265         _x = _x.encode('utf-8')
00266         length = len(_x)
00267       buff.write(struct.pack('<I%ss'%length, length, _x))
00268       _x = self
00269       buff.write(_struct_13d6B2i3I.pack(_x.feedback.initial_point.pose.position.x, _x.feedback.initial_point.pose.position.y, _x.feedback.initial_point.pose.position.z, _x.feedback.initial_point.pose.orientation.x, _x.feedback.initial_point.pose.orientation.y, _x.feedback.initial_point.pose.orientation.z, _x.feedback.initial_point.pose.orientation.w, _x.feedback.initial_point.wrench_or_stiffness.force.x, _x.feedback.initial_point.wrench_or_stiffness.force.y, _x.feedback.initial_point.wrench_or_stiffness.force.z, _x.feedback.initial_point.wrench_or_stiffness.torque.x, _x.feedback.initial_point.wrench_or_stiffness.torque.y, _x.feedback.initial_point.wrench_or_stiffness.torque.z, _x.feedback.initial_point.isForceX, _x.feedback.initial_point.isForceY, _x.feedback.initial_point.isForceZ, _x.feedback.initial_point.isTorqueX, _x.feedback.initial_point.isTorqueY, _x.feedback.initial_point.isTorqueZ, _x.feedback.initial_point.time_from_start.secs, _x.feedback.initial_point.time_from_start.nsecs, _x.feedback.desired.header.seq, _x.feedback.desired.header.stamp.secs, _x.feedback.desired.header.stamp.nsecs))
00270       _x = self.feedback.desired.header.frame_id
00271       length = len(_x)
00272       if python3 or type(_x) == unicode:
00273         _x = _x.encode('utf-8')
00274         length = len(_x)
00275       buff.write(struct.pack('<I%ss'%length, length, _x))
00276       _x = self
00277       buff.write(_struct_13d6B2i3I.pack(_x.feedback.desired.pose.position.x, _x.feedback.desired.pose.position.y, _x.feedback.desired.pose.position.z, _x.feedback.desired.pose.orientation.x, _x.feedback.desired.pose.orientation.y, _x.feedback.desired.pose.orientation.z, _x.feedback.desired.pose.orientation.w, _x.feedback.desired.wrench_or_stiffness.force.x, _x.feedback.desired.wrench_or_stiffness.force.y, _x.feedback.desired.wrench_or_stiffness.force.z, _x.feedback.desired.wrench_or_stiffness.torque.x, _x.feedback.desired.wrench_or_stiffness.torque.y, _x.feedback.desired.wrench_or_stiffness.torque.z, _x.feedback.desired.isForceX, _x.feedback.desired.isForceY, _x.feedback.desired.isForceZ, _x.feedback.desired.isTorqueX, _x.feedback.desired.isTorqueY, _x.feedback.desired.isTorqueZ, _x.feedback.desired.time_from_start.secs, _x.feedback.desired.time_from_start.nsecs, _x.feedback.actual_pose.header.seq, _x.feedback.actual_pose.header.stamp.secs, _x.feedback.actual_pose.header.stamp.nsecs))
00278       _x = self.feedback.actual_pose.header.frame_id
00279       length = len(_x)
00280       if python3 or type(_x) == unicode:
00281         _x = _x.encode('utf-8')
00282         length = len(_x)
00283       buff.write(struct.pack('<I%ss'%length, length, _x))
00284       _x = self
00285       buff.write(_struct_13d6B2id.pack(_x.feedback.actual_pose.pose.position.x, _x.feedback.actual_pose.pose.position.y, _x.feedback.actual_pose.pose.position.z, _x.feedback.actual_pose.pose.orientation.x, _x.feedback.actual_pose.pose.orientation.y, _x.feedback.actual_pose.pose.orientation.z, _x.feedback.actual_pose.pose.orientation.w, _x.feedback.actual_pose.wrench_or_stiffness.force.x, _x.feedback.actual_pose.wrench_or_stiffness.force.y, _x.feedback.actual_pose.wrench_or_stiffness.force.z, _x.feedback.actual_pose.wrench_or_stiffness.torque.x, _x.feedback.actual_pose.wrench_or_stiffness.torque.y, _x.feedback.actual_pose.wrench_or_stiffness.torque.z, _x.feedback.actual_pose.isForceX, _x.feedback.actual_pose.isForceY, _x.feedback.actual_pose.isForceZ, _x.feedback.actual_pose.isTorqueX, _x.feedback.actual_pose.isTorqueY, _x.feedback.actual_pose.isTorqueZ, _x.feedback.actual_pose.time_from_start.secs, _x.feedback.actual_pose.time_from_start.nsecs, _x.feedback.effort_sq_error))
00286       length = len(self.feedback.requested_joint_efforts)
00287       buff.write(_struct_I.pack(length))
00288       pattern = '<%sd'%length
00289       buff.write(struct.pack(pattern, *self.feedback.requested_joint_efforts))
00290       length = len(self.feedback.actual_joint_efforts)
00291       buff.write(_struct_I.pack(length))
00292       pattern = '<%sd'%length
00293       buff.write(struct.pack(pattern, *self.feedback.actual_joint_efforts))
00294       _x = self
00295       buff.write(_struct_2i.pack(_x.feedback.running_time.secs, _x.feedback.running_time.nsecs))
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, ``str``
00303     """
00304     try:
00305       if self.header is None:
00306         self.header = std_msgs.msg.Header()
00307       if self.status is None:
00308         self.status = actionlib_msgs.msg.GoalStatus()
00309       if self.feedback is None:
00310         self.feedback = ee_cart_imped_msgs.msg.EECartImpedFeedback()
00311       end = 0
00312       _x = self
00313       start = end
00314       end += 12
00315       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00316       start = end
00317       end += 4
00318       (length,) = _struct_I.unpack(str[start:end])
00319       start = end
00320       end += length
00321       if python3:
00322         self.header.frame_id = str[start:end].decode('utf-8')
00323       else:
00324         self.header.frame_id = str[start:end]
00325       _x = self
00326       start = end
00327       end += 8
00328       (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00329       start = end
00330       end += 4
00331       (length,) = _struct_I.unpack(str[start:end])
00332       start = end
00333       end += length
00334       if python3:
00335         self.status.goal_id.id = str[start:end].decode('utf-8')
00336       else:
00337         self.status.goal_id.id = str[start:end]
00338       start = end
00339       end += 1
00340       (self.status.status,) = _struct_B.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       if python3:
00347         self.status.text = str[start:end].decode('utf-8')
00348       else:
00349         self.status.text = str[start:end]
00350       _x = self
00351       start = end
00352       end += 12
00353       (_x.feedback.header.seq, _x.feedback.header.stamp.secs, _x.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00354       start = end
00355       end += 4
00356       (length,) = _struct_I.unpack(str[start:end])
00357       start = end
00358       end += length
00359       if python3:
00360         self.feedback.header.frame_id = str[start:end].decode('utf-8')
00361       else:
00362         self.feedback.header.frame_id = str[start:end]
00363       start = end
00364       end += 4
00365       (length,) = _struct_I.unpack(str[start:end])
00366       self.feedback.goal = []
00367       for i in range(0, length):
00368         val1 = ee_cart_imped_msgs.msg.StiffPoint()
00369         _v10 = val1.header
00370         start = end
00371         end += 4
00372         (_v10.seq,) = _struct_I.unpack(str[start:end])
00373         _v11 = _v10.stamp
00374         _x = _v11
00375         start = end
00376         end += 8
00377         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00378         start = end
00379         end += 4
00380         (length,) = _struct_I.unpack(str[start:end])
00381         start = end
00382         end += length
00383         if python3:
00384           _v10.frame_id = str[start:end].decode('utf-8')
00385         else:
00386           _v10.frame_id = str[start:end]
00387         _v12 = val1.pose
00388         _v13 = _v12.position
00389         _x = _v13
00390         start = end
00391         end += 24
00392         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00393         _v14 = _v12.orientation
00394         _x = _v14
00395         start = end
00396         end += 32
00397         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00398         _v15 = val1.wrench_or_stiffness
00399         _v16 = _v15.force
00400         _x = _v16
00401         start = end
00402         end += 24
00403         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00404         _v17 = _v15.torque
00405         _x = _v17
00406         start = end
00407         end += 24
00408         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00409         _x = val1
00410         start = end
00411         end += 6
00412         (_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ,) = _struct_6B.unpack(str[start:end])
00413         val1.isForceX = bool(val1.isForceX)
00414         val1.isForceY = bool(val1.isForceY)
00415         val1.isForceZ = bool(val1.isForceZ)
00416         val1.isTorqueX = bool(val1.isTorqueX)
00417         val1.isTorqueY = bool(val1.isTorqueY)
00418         val1.isTorqueZ = bool(val1.isTorqueZ)
00419         _v18 = val1.time_from_start
00420         _x = _v18
00421         start = end
00422         end += 8
00423         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00424         self.feedback.goal.append(val1)
00425       _x = self
00426       start = end
00427       end += 12
00428       (_x.feedback.initial_point.header.seq, _x.feedback.initial_point.header.stamp.secs, _x.feedback.initial_point.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00429       start = end
00430       end += 4
00431       (length,) = _struct_I.unpack(str[start:end])
00432       start = end
00433       end += length
00434       if python3:
00435         self.feedback.initial_point.header.frame_id = str[start:end].decode('utf-8')
00436       else:
00437         self.feedback.initial_point.header.frame_id = str[start:end]
00438       _x = self
00439       start = end
00440       end += 130
00441       (_x.feedback.initial_point.pose.position.x, _x.feedback.initial_point.pose.position.y, _x.feedback.initial_point.pose.position.z, _x.feedback.initial_point.pose.orientation.x, _x.feedback.initial_point.pose.orientation.y, _x.feedback.initial_point.pose.orientation.z, _x.feedback.initial_point.pose.orientation.w, _x.feedback.initial_point.wrench_or_stiffness.force.x, _x.feedback.initial_point.wrench_or_stiffness.force.y, _x.feedback.initial_point.wrench_or_stiffness.force.z, _x.feedback.initial_point.wrench_or_stiffness.torque.x, _x.feedback.initial_point.wrench_or_stiffness.torque.y, _x.feedback.initial_point.wrench_or_stiffness.torque.z, _x.feedback.initial_point.isForceX, _x.feedback.initial_point.isForceY, _x.feedback.initial_point.isForceZ, _x.feedback.initial_point.isTorqueX, _x.feedback.initial_point.isTorqueY, _x.feedback.initial_point.isTorqueZ, _x.feedback.initial_point.time_from_start.secs, _x.feedback.initial_point.time_from_start.nsecs, _x.feedback.desired.header.seq, _x.feedback.desired.header.stamp.secs, _x.feedback.desired.header.stamp.nsecs,) = _struct_13d6B2i3I.unpack(str[start:end])
00442       self.feedback.initial_point.isForceX = bool(self.feedback.initial_point.isForceX)
00443       self.feedback.initial_point.isForceY = bool(self.feedback.initial_point.isForceY)
00444       self.feedback.initial_point.isForceZ = bool(self.feedback.initial_point.isForceZ)
00445       self.feedback.initial_point.isTorqueX = bool(self.feedback.initial_point.isTorqueX)
00446       self.feedback.initial_point.isTorqueY = bool(self.feedback.initial_point.isTorqueY)
00447       self.feedback.initial_point.isTorqueZ = bool(self.feedback.initial_point.isTorqueZ)
00448       start = end
00449       end += 4
00450       (length,) = _struct_I.unpack(str[start:end])
00451       start = end
00452       end += length
00453       if python3:
00454         self.feedback.desired.header.frame_id = str[start:end].decode('utf-8')
00455       else:
00456         self.feedback.desired.header.frame_id = str[start:end]
00457       _x = self
00458       start = end
00459       end += 130
00460       (_x.feedback.desired.pose.position.x, _x.feedback.desired.pose.position.y, _x.feedback.desired.pose.position.z, _x.feedback.desired.pose.orientation.x, _x.feedback.desired.pose.orientation.y, _x.feedback.desired.pose.orientation.z, _x.feedback.desired.pose.orientation.w, _x.feedback.desired.wrench_or_stiffness.force.x, _x.feedback.desired.wrench_or_stiffness.force.y, _x.feedback.desired.wrench_or_stiffness.force.z, _x.feedback.desired.wrench_or_stiffness.torque.x, _x.feedback.desired.wrench_or_stiffness.torque.y, _x.feedback.desired.wrench_or_stiffness.torque.z, _x.feedback.desired.isForceX, _x.feedback.desired.isForceY, _x.feedback.desired.isForceZ, _x.feedback.desired.isTorqueX, _x.feedback.desired.isTorqueY, _x.feedback.desired.isTorqueZ, _x.feedback.desired.time_from_start.secs, _x.feedback.desired.time_from_start.nsecs, _x.feedback.actual_pose.header.seq, _x.feedback.actual_pose.header.stamp.secs, _x.feedback.actual_pose.header.stamp.nsecs,) = _struct_13d6B2i3I.unpack(str[start:end])
00461       self.feedback.desired.isForceX = bool(self.feedback.desired.isForceX)
00462       self.feedback.desired.isForceY = bool(self.feedback.desired.isForceY)
00463       self.feedback.desired.isForceZ = bool(self.feedback.desired.isForceZ)
00464       self.feedback.desired.isTorqueX = bool(self.feedback.desired.isTorqueX)
00465       self.feedback.desired.isTorqueY = bool(self.feedback.desired.isTorqueY)
00466       self.feedback.desired.isTorqueZ = bool(self.feedback.desired.isTorqueZ)
00467       start = end
00468       end += 4
00469       (length,) = _struct_I.unpack(str[start:end])
00470       start = end
00471       end += length
00472       if python3:
00473         self.feedback.actual_pose.header.frame_id = str[start:end].decode('utf-8')
00474       else:
00475         self.feedback.actual_pose.header.frame_id = str[start:end]
00476       _x = self
00477       start = end
00478       end += 126
00479       (_x.feedback.actual_pose.pose.position.x, _x.feedback.actual_pose.pose.position.y, _x.feedback.actual_pose.pose.position.z, _x.feedback.actual_pose.pose.orientation.x, _x.feedback.actual_pose.pose.orientation.y, _x.feedback.actual_pose.pose.orientation.z, _x.feedback.actual_pose.pose.orientation.w, _x.feedback.actual_pose.wrench_or_stiffness.force.x, _x.feedback.actual_pose.wrench_or_stiffness.force.y, _x.feedback.actual_pose.wrench_or_stiffness.force.z, _x.feedback.actual_pose.wrench_or_stiffness.torque.x, _x.feedback.actual_pose.wrench_or_stiffness.torque.y, _x.feedback.actual_pose.wrench_or_stiffness.torque.z, _x.feedback.actual_pose.isForceX, _x.feedback.actual_pose.isForceY, _x.feedback.actual_pose.isForceZ, _x.feedback.actual_pose.isTorqueX, _x.feedback.actual_pose.isTorqueY, _x.feedback.actual_pose.isTorqueZ, _x.feedback.actual_pose.time_from_start.secs, _x.feedback.actual_pose.time_from_start.nsecs, _x.feedback.effort_sq_error,) = _struct_13d6B2id.unpack(str[start:end])
00480       self.feedback.actual_pose.isForceX = bool(self.feedback.actual_pose.isForceX)
00481       self.feedback.actual_pose.isForceY = bool(self.feedback.actual_pose.isForceY)
00482       self.feedback.actual_pose.isForceZ = bool(self.feedback.actual_pose.isForceZ)
00483       self.feedback.actual_pose.isTorqueX = bool(self.feedback.actual_pose.isTorqueX)
00484       self.feedback.actual_pose.isTorqueY = bool(self.feedback.actual_pose.isTorqueY)
00485       self.feedback.actual_pose.isTorqueZ = bool(self.feedback.actual_pose.isTorqueZ)
00486       start = end
00487       end += 4
00488       (length,) = _struct_I.unpack(str[start:end])
00489       pattern = '<%sd'%length
00490       start = end
00491       end += struct.calcsize(pattern)
00492       self.feedback.requested_joint_efforts = struct.unpack(pattern, str[start:end])
00493       start = end
00494       end += 4
00495       (length,) = _struct_I.unpack(str[start:end])
00496       pattern = '<%sd'%length
00497       start = end
00498       end += struct.calcsize(pattern)
00499       self.feedback.actual_joint_efforts = struct.unpack(pattern, str[start:end])
00500       _x = self
00501       start = end
00502       end += 8
00503       (_x.feedback.running_time.secs, _x.feedback.running_time.nsecs,) = _struct_2i.unpack(str[start:end])
00504       return self
00505     except struct.error as e:
00506       raise genpy.DeserializationError(e) #most likely buffer underfill
00507 
00508 
00509   def serialize_numpy(self, buff, numpy):
00510     """
00511     serialize message with numpy array types into buffer
00512     :param buff: buffer, ``StringIO``
00513     :param numpy: numpy python module
00514     """
00515     try:
00516       _x = self
00517       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00518       _x = self.header.frame_id
00519       length = len(_x)
00520       if python3 or type(_x) == unicode:
00521         _x = _x.encode('utf-8')
00522         length = len(_x)
00523       buff.write(struct.pack('<I%ss'%length, length, _x))
00524       _x = self
00525       buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00526       _x = self.status.goal_id.id
00527       length = len(_x)
00528       if python3 or type(_x) == unicode:
00529         _x = _x.encode('utf-8')
00530         length = len(_x)
00531       buff.write(struct.pack('<I%ss'%length, length, _x))
00532       buff.write(_struct_B.pack(self.status.status))
00533       _x = self.status.text
00534       length = len(_x)
00535       if python3 or type(_x) == unicode:
00536         _x = _x.encode('utf-8')
00537         length = len(_x)
00538       buff.write(struct.pack('<I%ss'%length, length, _x))
00539       _x = self
00540       buff.write(_struct_3I.pack(_x.feedback.header.seq, _x.feedback.header.stamp.secs, _x.feedback.header.stamp.nsecs))
00541       _x = self.feedback.header.frame_id
00542       length = len(_x)
00543       if python3 or type(_x) == unicode:
00544         _x = _x.encode('utf-8')
00545         length = len(_x)
00546       buff.write(struct.pack('<I%ss'%length, length, _x))
00547       length = len(self.feedback.goal)
00548       buff.write(_struct_I.pack(length))
00549       for val1 in self.feedback.goal:
00550         _v19 = val1.header
00551         buff.write(_struct_I.pack(_v19.seq))
00552         _v20 = _v19.stamp
00553         _x = _v20
00554         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00555         _x = _v19.frame_id
00556         length = len(_x)
00557         if python3 or type(_x) == unicode:
00558           _x = _x.encode('utf-8')
00559           length = len(_x)
00560         buff.write(struct.pack('<I%ss'%length, length, _x))
00561         _v21 = val1.pose
00562         _v22 = _v21.position
00563         _x = _v22
00564         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00565         _v23 = _v21.orientation
00566         _x = _v23
00567         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00568         _v24 = val1.wrench_or_stiffness
00569         _v25 = _v24.force
00570         _x = _v25
00571         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00572         _v26 = _v24.torque
00573         _x = _v26
00574         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00575         _x = val1
00576         buff.write(_struct_6B.pack(_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ))
00577         _v27 = val1.time_from_start
00578         _x = _v27
00579         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00580       _x = self
00581       buff.write(_struct_3I.pack(_x.feedback.initial_point.header.seq, _x.feedback.initial_point.header.stamp.secs, _x.feedback.initial_point.header.stamp.nsecs))
00582       _x = self.feedback.initial_point.header.frame_id
00583       length = len(_x)
00584       if python3 or type(_x) == unicode:
00585         _x = _x.encode('utf-8')
00586         length = len(_x)
00587       buff.write(struct.pack('<I%ss'%length, length, _x))
00588       _x = self
00589       buff.write(_struct_13d6B2i3I.pack(_x.feedback.initial_point.pose.position.x, _x.feedback.initial_point.pose.position.y, _x.feedback.initial_point.pose.position.z, _x.feedback.initial_point.pose.orientation.x, _x.feedback.initial_point.pose.orientation.y, _x.feedback.initial_point.pose.orientation.z, _x.feedback.initial_point.pose.orientation.w, _x.feedback.initial_point.wrench_or_stiffness.force.x, _x.feedback.initial_point.wrench_or_stiffness.force.y, _x.feedback.initial_point.wrench_or_stiffness.force.z, _x.feedback.initial_point.wrench_or_stiffness.torque.x, _x.feedback.initial_point.wrench_or_stiffness.torque.y, _x.feedback.initial_point.wrench_or_stiffness.torque.z, _x.feedback.initial_point.isForceX, _x.feedback.initial_point.isForceY, _x.feedback.initial_point.isForceZ, _x.feedback.initial_point.isTorqueX, _x.feedback.initial_point.isTorqueY, _x.feedback.initial_point.isTorqueZ, _x.feedback.initial_point.time_from_start.secs, _x.feedback.initial_point.time_from_start.nsecs, _x.feedback.desired.header.seq, _x.feedback.desired.header.stamp.secs, _x.feedback.desired.header.stamp.nsecs))
00590       _x = self.feedback.desired.header.frame_id
00591       length = len(_x)
00592       if python3 or type(_x) == unicode:
00593         _x = _x.encode('utf-8')
00594         length = len(_x)
00595       buff.write(struct.pack('<I%ss'%length, length, _x))
00596       _x = self
00597       buff.write(_struct_13d6B2i3I.pack(_x.feedback.desired.pose.position.x, _x.feedback.desired.pose.position.y, _x.feedback.desired.pose.position.z, _x.feedback.desired.pose.orientation.x, _x.feedback.desired.pose.orientation.y, _x.feedback.desired.pose.orientation.z, _x.feedback.desired.pose.orientation.w, _x.feedback.desired.wrench_or_stiffness.force.x, _x.feedback.desired.wrench_or_stiffness.force.y, _x.feedback.desired.wrench_or_stiffness.force.z, _x.feedback.desired.wrench_or_stiffness.torque.x, _x.feedback.desired.wrench_or_stiffness.torque.y, _x.feedback.desired.wrench_or_stiffness.torque.z, _x.feedback.desired.isForceX, _x.feedback.desired.isForceY, _x.feedback.desired.isForceZ, _x.feedback.desired.isTorqueX, _x.feedback.desired.isTorqueY, _x.feedback.desired.isTorqueZ, _x.feedback.desired.time_from_start.secs, _x.feedback.desired.time_from_start.nsecs, _x.feedback.actual_pose.header.seq, _x.feedback.actual_pose.header.stamp.secs, _x.feedback.actual_pose.header.stamp.nsecs))
00598       _x = self.feedback.actual_pose.header.frame_id
00599       length = len(_x)
00600       if python3 or type(_x) == unicode:
00601         _x = _x.encode('utf-8')
00602         length = len(_x)
00603       buff.write(struct.pack('<I%ss'%length, length, _x))
00604       _x = self
00605       buff.write(_struct_13d6B2id.pack(_x.feedback.actual_pose.pose.position.x, _x.feedback.actual_pose.pose.position.y, _x.feedback.actual_pose.pose.position.z, _x.feedback.actual_pose.pose.orientation.x, _x.feedback.actual_pose.pose.orientation.y, _x.feedback.actual_pose.pose.orientation.z, _x.feedback.actual_pose.pose.orientation.w, _x.feedback.actual_pose.wrench_or_stiffness.force.x, _x.feedback.actual_pose.wrench_or_stiffness.force.y, _x.feedback.actual_pose.wrench_or_stiffness.force.z, _x.feedback.actual_pose.wrench_or_stiffness.torque.x, _x.feedback.actual_pose.wrench_or_stiffness.torque.y, _x.feedback.actual_pose.wrench_or_stiffness.torque.z, _x.feedback.actual_pose.isForceX, _x.feedback.actual_pose.isForceY, _x.feedback.actual_pose.isForceZ, _x.feedback.actual_pose.isTorqueX, _x.feedback.actual_pose.isTorqueY, _x.feedback.actual_pose.isTorqueZ, _x.feedback.actual_pose.time_from_start.secs, _x.feedback.actual_pose.time_from_start.nsecs, _x.feedback.effort_sq_error))
00606       length = len(self.feedback.requested_joint_efforts)
00607       buff.write(_struct_I.pack(length))
00608       pattern = '<%sd'%length
00609       buff.write(self.feedback.requested_joint_efforts.tostring())
00610       length = len(self.feedback.actual_joint_efforts)
00611       buff.write(_struct_I.pack(length))
00612       pattern = '<%sd'%length
00613       buff.write(self.feedback.actual_joint_efforts.tostring())
00614       _x = self
00615       buff.write(_struct_2i.pack(_x.feedback.running_time.secs, _x.feedback.running_time.nsecs))
00616     except struct.error as se: self._check_types(se)
00617     except TypeError as te: self._check_types(te)
00618 
00619   def deserialize_numpy(self, str, numpy):
00620     """
00621     unpack serialized message in str into this message instance using numpy for array types
00622     :param str: byte array of serialized message, ``str``
00623     :param numpy: numpy python module
00624     """
00625     try:
00626       if self.header is None:
00627         self.header = std_msgs.msg.Header()
00628       if self.status is None:
00629         self.status = actionlib_msgs.msg.GoalStatus()
00630       if self.feedback is None:
00631         self.feedback = ee_cart_imped_msgs.msg.EECartImpedFeedback()
00632       end = 0
00633       _x = self
00634       start = end
00635       end += 12
00636       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00637       start = end
00638       end += 4
00639       (length,) = _struct_I.unpack(str[start:end])
00640       start = end
00641       end += length
00642       if python3:
00643         self.header.frame_id = str[start:end].decode('utf-8')
00644       else:
00645         self.header.frame_id = str[start:end]
00646       _x = self
00647       start = end
00648       end += 8
00649       (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00650       start = end
00651       end += 4
00652       (length,) = _struct_I.unpack(str[start:end])
00653       start = end
00654       end += length
00655       if python3:
00656         self.status.goal_id.id = str[start:end].decode('utf-8')
00657       else:
00658         self.status.goal_id.id = str[start:end]
00659       start = end
00660       end += 1
00661       (self.status.status,) = _struct_B.unpack(str[start:end])
00662       start = end
00663       end += 4
00664       (length,) = _struct_I.unpack(str[start:end])
00665       start = end
00666       end += length
00667       if python3:
00668         self.status.text = str[start:end].decode('utf-8')
00669       else:
00670         self.status.text = str[start:end]
00671       _x = self
00672       start = end
00673       end += 12
00674       (_x.feedback.header.seq, _x.feedback.header.stamp.secs, _x.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00675       start = end
00676       end += 4
00677       (length,) = _struct_I.unpack(str[start:end])
00678       start = end
00679       end += length
00680       if python3:
00681         self.feedback.header.frame_id = str[start:end].decode('utf-8')
00682       else:
00683         self.feedback.header.frame_id = str[start:end]
00684       start = end
00685       end += 4
00686       (length,) = _struct_I.unpack(str[start:end])
00687       self.feedback.goal = []
00688       for i in range(0, length):
00689         val1 = ee_cart_imped_msgs.msg.StiffPoint()
00690         _v28 = val1.header
00691         start = end
00692         end += 4
00693         (_v28.seq,) = _struct_I.unpack(str[start:end])
00694         _v29 = _v28.stamp
00695         _x = _v29
00696         start = end
00697         end += 8
00698         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00699         start = end
00700         end += 4
00701         (length,) = _struct_I.unpack(str[start:end])
00702         start = end
00703         end += length
00704         if python3:
00705           _v28.frame_id = str[start:end].decode('utf-8')
00706         else:
00707           _v28.frame_id = str[start:end]
00708         _v30 = val1.pose
00709         _v31 = _v30.position
00710         _x = _v31
00711         start = end
00712         end += 24
00713         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00714         _v32 = _v30.orientation
00715         _x = _v32
00716         start = end
00717         end += 32
00718         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00719         _v33 = val1.wrench_or_stiffness
00720         _v34 = _v33.force
00721         _x = _v34
00722         start = end
00723         end += 24
00724         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00725         _v35 = _v33.torque
00726         _x = _v35
00727         start = end
00728         end += 24
00729         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00730         _x = val1
00731         start = end
00732         end += 6
00733         (_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ,) = _struct_6B.unpack(str[start:end])
00734         val1.isForceX = bool(val1.isForceX)
00735         val1.isForceY = bool(val1.isForceY)
00736         val1.isForceZ = bool(val1.isForceZ)
00737         val1.isTorqueX = bool(val1.isTorqueX)
00738         val1.isTorqueY = bool(val1.isTorqueY)
00739         val1.isTorqueZ = bool(val1.isTorqueZ)
00740         _v36 = val1.time_from_start
00741         _x = _v36
00742         start = end
00743         end += 8
00744         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00745         self.feedback.goal.append(val1)
00746       _x = self
00747       start = end
00748       end += 12
00749       (_x.feedback.initial_point.header.seq, _x.feedback.initial_point.header.stamp.secs, _x.feedback.initial_point.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00750       start = end
00751       end += 4
00752       (length,) = _struct_I.unpack(str[start:end])
00753       start = end
00754       end += length
00755       if python3:
00756         self.feedback.initial_point.header.frame_id = str[start:end].decode('utf-8')
00757       else:
00758         self.feedback.initial_point.header.frame_id = str[start:end]
00759       _x = self
00760       start = end
00761       end += 130
00762       (_x.feedback.initial_point.pose.position.x, _x.feedback.initial_point.pose.position.y, _x.feedback.initial_point.pose.position.z, _x.feedback.initial_point.pose.orientation.x, _x.feedback.initial_point.pose.orientation.y, _x.feedback.initial_point.pose.orientation.z, _x.feedback.initial_point.pose.orientation.w, _x.feedback.initial_point.wrench_or_stiffness.force.x, _x.feedback.initial_point.wrench_or_stiffness.force.y, _x.feedback.initial_point.wrench_or_stiffness.force.z, _x.feedback.initial_point.wrench_or_stiffness.torque.x, _x.feedback.initial_point.wrench_or_stiffness.torque.y, _x.feedback.initial_point.wrench_or_stiffness.torque.z, _x.feedback.initial_point.isForceX, _x.feedback.initial_point.isForceY, _x.feedback.initial_point.isForceZ, _x.feedback.initial_point.isTorqueX, _x.feedback.initial_point.isTorqueY, _x.feedback.initial_point.isTorqueZ, _x.feedback.initial_point.time_from_start.secs, _x.feedback.initial_point.time_from_start.nsecs, _x.feedback.desired.header.seq, _x.feedback.desired.header.stamp.secs, _x.feedback.desired.header.stamp.nsecs,) = _struct_13d6B2i3I.unpack(str[start:end])
00763       self.feedback.initial_point.isForceX = bool(self.feedback.initial_point.isForceX)
00764       self.feedback.initial_point.isForceY = bool(self.feedback.initial_point.isForceY)
00765       self.feedback.initial_point.isForceZ = bool(self.feedback.initial_point.isForceZ)
00766       self.feedback.initial_point.isTorqueX = bool(self.feedback.initial_point.isTorqueX)
00767       self.feedback.initial_point.isTorqueY = bool(self.feedback.initial_point.isTorqueY)
00768       self.feedback.initial_point.isTorqueZ = bool(self.feedback.initial_point.isTorqueZ)
00769       start = end
00770       end += 4
00771       (length,) = _struct_I.unpack(str[start:end])
00772       start = end
00773       end += length
00774       if python3:
00775         self.feedback.desired.header.frame_id = str[start:end].decode('utf-8')
00776       else:
00777         self.feedback.desired.header.frame_id = str[start:end]
00778       _x = self
00779       start = end
00780       end += 130
00781       (_x.feedback.desired.pose.position.x, _x.feedback.desired.pose.position.y, _x.feedback.desired.pose.position.z, _x.feedback.desired.pose.orientation.x, _x.feedback.desired.pose.orientation.y, _x.feedback.desired.pose.orientation.z, _x.feedback.desired.pose.orientation.w, _x.feedback.desired.wrench_or_stiffness.force.x, _x.feedback.desired.wrench_or_stiffness.force.y, _x.feedback.desired.wrench_or_stiffness.force.z, _x.feedback.desired.wrench_or_stiffness.torque.x, _x.feedback.desired.wrench_or_stiffness.torque.y, _x.feedback.desired.wrench_or_stiffness.torque.z, _x.feedback.desired.isForceX, _x.feedback.desired.isForceY, _x.feedback.desired.isForceZ, _x.feedback.desired.isTorqueX, _x.feedback.desired.isTorqueY, _x.feedback.desired.isTorqueZ, _x.feedback.desired.time_from_start.secs, _x.feedback.desired.time_from_start.nsecs, _x.feedback.actual_pose.header.seq, _x.feedback.actual_pose.header.stamp.secs, _x.feedback.actual_pose.header.stamp.nsecs,) = _struct_13d6B2i3I.unpack(str[start:end])
00782       self.feedback.desired.isForceX = bool(self.feedback.desired.isForceX)
00783       self.feedback.desired.isForceY = bool(self.feedback.desired.isForceY)
00784       self.feedback.desired.isForceZ = bool(self.feedback.desired.isForceZ)
00785       self.feedback.desired.isTorqueX = bool(self.feedback.desired.isTorqueX)
00786       self.feedback.desired.isTorqueY = bool(self.feedback.desired.isTorqueY)
00787       self.feedback.desired.isTorqueZ = bool(self.feedback.desired.isTorqueZ)
00788       start = end
00789       end += 4
00790       (length,) = _struct_I.unpack(str[start:end])
00791       start = end
00792       end += length
00793       if python3:
00794         self.feedback.actual_pose.header.frame_id = str[start:end].decode('utf-8')
00795       else:
00796         self.feedback.actual_pose.header.frame_id = str[start:end]
00797       _x = self
00798       start = end
00799       end += 126
00800       (_x.feedback.actual_pose.pose.position.x, _x.feedback.actual_pose.pose.position.y, _x.feedback.actual_pose.pose.position.z, _x.feedback.actual_pose.pose.orientation.x, _x.feedback.actual_pose.pose.orientation.y, _x.feedback.actual_pose.pose.orientation.z, _x.feedback.actual_pose.pose.orientation.w, _x.feedback.actual_pose.wrench_or_stiffness.force.x, _x.feedback.actual_pose.wrench_or_stiffness.force.y, _x.feedback.actual_pose.wrench_or_stiffness.force.z, _x.feedback.actual_pose.wrench_or_stiffness.torque.x, _x.feedback.actual_pose.wrench_or_stiffness.torque.y, _x.feedback.actual_pose.wrench_or_stiffness.torque.z, _x.feedback.actual_pose.isForceX, _x.feedback.actual_pose.isForceY, _x.feedback.actual_pose.isForceZ, _x.feedback.actual_pose.isTorqueX, _x.feedback.actual_pose.isTorqueY, _x.feedback.actual_pose.isTorqueZ, _x.feedback.actual_pose.time_from_start.secs, _x.feedback.actual_pose.time_from_start.nsecs, _x.feedback.effort_sq_error,) = _struct_13d6B2id.unpack(str[start:end])
00801       self.feedback.actual_pose.isForceX = bool(self.feedback.actual_pose.isForceX)
00802       self.feedback.actual_pose.isForceY = bool(self.feedback.actual_pose.isForceY)
00803       self.feedback.actual_pose.isForceZ = bool(self.feedback.actual_pose.isForceZ)
00804       self.feedback.actual_pose.isTorqueX = bool(self.feedback.actual_pose.isTorqueX)
00805       self.feedback.actual_pose.isTorqueY = bool(self.feedback.actual_pose.isTorqueY)
00806       self.feedback.actual_pose.isTorqueZ = bool(self.feedback.actual_pose.isTorqueZ)
00807       start = end
00808       end += 4
00809       (length,) = _struct_I.unpack(str[start:end])
00810       pattern = '<%sd'%length
00811       start = end
00812       end += struct.calcsize(pattern)
00813       self.feedback.requested_joint_efforts = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00814       start = end
00815       end += 4
00816       (length,) = _struct_I.unpack(str[start:end])
00817       pattern = '<%sd'%length
00818       start = end
00819       end += struct.calcsize(pattern)
00820       self.feedback.actual_joint_efforts = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00821       _x = self
00822       start = end
00823       end += 8
00824       (_x.feedback.running_time.secs, _x.feedback.running_time.nsecs,) = _struct_2i.unpack(str[start:end])
00825       return self
00826     except struct.error as e:
00827       raise genpy.DeserializationError(e) #most likely buffer underfill
00828 
00829 _struct_I = genpy.struct_I
00830 _struct_6B = struct.Struct("<6B")
00831 _struct_B = struct.Struct("<B")
00832 _struct_13d6B2id = struct.Struct("<13d6B2id")
00833 _struct_2i = struct.Struct("<2i")
00834 _struct_3I = struct.Struct("<3I")
00835 _struct_13d6B2i3I = struct.Struct("<13d6B2i3I")
00836 _struct_4d = struct.Struct("<4d")
00837 _struct_2I = struct.Struct("<2I")
00838 _struct_3d = struct.Struct("<3d")


ee_cart_imped_msgs
Author(s): Jenny Barry, Mario Bollini, and Huan Liu
autogenerated on Sun Jan 5 2014 11:14:34