_EECartImpedAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from ee_cart_imped_msgs/EECartImpedAction.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 actionlib_msgs.msg
00008 import geometry_msgs.msg
00009 import genpy
00010 import ee_cart_imped_msgs.msg
00011 import std_msgs.msg
00012 
00013 class EECartImpedAction(genpy.Message):
00014   _md5sum = "363b9ba3af4663dbf9394e1ef0b84435"
00015   _type = "ee_cart_imped_msgs/EECartImpedAction"
00016   _has_header = False #flag to mark the presence of a Header object
00017   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018 
00019 EECartImpedActionGoal action_goal
00020 EECartImpedActionResult action_result
00021 EECartImpedActionFeedback action_feedback
00022 
00023 ================================================================================
00024 MSG: ee_cart_imped_msgs/EECartImpedActionGoal
00025 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00026 
00027 Header header
00028 actionlib_msgs/GoalID goal_id
00029 EECartImpedGoal goal
00030 
00031 ================================================================================
00032 MSG: std_msgs/Header
00033 # Standard metadata for higher-level stamped data types.
00034 # This is generally used to communicate timestamped data 
00035 # in a particular coordinate frame.
00036 # 
00037 # sequence ID: consecutively increasing ID 
00038 uint32 seq
00039 #Two-integer timestamp that is expressed as:
00040 # * stamp.secs: seconds (stamp_secs) since epoch
00041 # * stamp.nsecs: nanoseconds since stamp_secs
00042 # time-handling sugar is provided by the client library
00043 time stamp
00044 #Frame this data is associated with
00045 # 0: no frame
00046 # 1: global frame
00047 string frame_id
00048 
00049 ================================================================================
00050 MSG: actionlib_msgs/GoalID
00051 # The stamp should store the time at which this goal was requested.
00052 # It is used by an action server when it tries to preempt all
00053 # goals that were requested before a certain time
00054 time stamp
00055 
00056 # The id provides a way to associate feedback and
00057 # result message with specific goal requests. The id
00058 # specified must be unique.
00059 string id
00060 
00061 
00062 ================================================================================
00063 MSG: ee_cart_imped_msgs/EECartImpedGoal
00064 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00065 #goal definition
00066 Header header
00067 ee_cart_imped_msgs/StiffPoint[] trajectory
00068 
00069 ================================================================================
00070 MSG: ee_cart_imped_msgs/StiffPoint
00071 Header header
00072 #The pose to achieve in the stiffness directions
00073 geometry_msgs/Pose pose
00074 #Wrench or stiffness for each dimension
00075 geometry_msgs/Wrench wrench_or_stiffness
00076 #The following are True if a force/torque should
00077 #be exerted and False if a stiffness should be used.
00078 bool isForceX
00079 bool isForceY
00080 bool isForceZ
00081 bool isTorqueX
00082 bool isTorqueY
00083 bool isTorqueZ
00084 #The time from the start of the trajectory that this
00085 #point should be achieved.
00086 duration time_from_start
00087 ================================================================================
00088 MSG: geometry_msgs/Pose
00089 # A representation of pose in free space, composed of postion and orientation. 
00090 Point position
00091 Quaternion orientation
00092 
00093 ================================================================================
00094 MSG: geometry_msgs/Point
00095 # This contains the position of a point in free space
00096 float64 x
00097 float64 y
00098 float64 z
00099 
00100 ================================================================================
00101 MSG: geometry_msgs/Quaternion
00102 # This represents an orientation in free space in quaternion form.
00103 
00104 float64 x
00105 float64 y
00106 float64 z
00107 float64 w
00108 
00109 ================================================================================
00110 MSG: geometry_msgs/Wrench
00111 # This represents force in free space, seperated into 
00112 # it's linear and angular parts.  
00113 Vector3  force
00114 Vector3  torque
00115 
00116 ================================================================================
00117 MSG: geometry_msgs/Vector3
00118 # This represents a vector in free space. 
00119 
00120 float64 x
00121 float64 y
00122 float64 z
00123 ================================================================================
00124 MSG: ee_cart_imped_msgs/EECartImpedActionResult
00125 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00126 
00127 Header header
00128 actionlib_msgs/GoalStatus status
00129 EECartImpedResult result
00130 
00131 ================================================================================
00132 MSG: actionlib_msgs/GoalStatus
00133 GoalID goal_id
00134 uint8 status
00135 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00136 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00137 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00138                             #   and has since completed its execution (Terminal State)
00139 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00140 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00141                             #    to some failure (Terminal State)
00142 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00143                             #    because the goal was unattainable or invalid (Terminal State)
00144 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00145                             #    and has not yet completed execution
00146 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00147                             #    but the action server has not yet confirmed that the goal is canceled
00148 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00149                             #    and was successfully cancelled (Terminal State)
00150 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00151                             #    sent over the wire by an action server
00152 
00153 #Allow for the user to associate a string with GoalStatus for debugging
00154 string text
00155 
00156 
00157 ================================================================================
00158 MSG: ee_cart_imped_msgs/EECartImpedResult
00159 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00160 #result definition
00161 #whether it was successful
00162 #the pose and force we ended with
00163 Header header
00164 bool success
00165 ee_cart_imped_msgs/StiffPoint desired
00166 geometry_msgs/Pose actual_pose
00167 float64 effort_sq_error
00168 
00169 ================================================================================
00170 MSG: ee_cart_imped_msgs/EECartImpedActionFeedback
00171 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00172 
00173 Header header
00174 actionlib_msgs/GoalStatus status
00175 EECartImpedFeedback feedback
00176 
00177 ================================================================================
00178 MSG: ee_cart_imped_msgs/EECartImpedFeedback
00179 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00180 #feedback
00181 #current pose and squared error in force 
00182 #and the running time of this goal so far
00183 Header header
00184 ee_cart_imped_msgs/StiffPoint[] goal
00185 ee_cart_imped_msgs/StiffPoint initial_point
00186 ee_cart_imped_msgs/StiffPoint desired
00187 ee_cart_imped_msgs/StiffPoint actual_pose
00188 float64 effort_sq_error
00189 float64[] requested_joint_efforts
00190 float64[] actual_joint_efforts
00191 duration running_time
00192 
00193 
00194 
00195 """
00196   __slots__ = ['action_goal','action_result','action_feedback']
00197   _slot_types = ['ee_cart_imped_msgs/EECartImpedActionGoal','ee_cart_imped_msgs/EECartImpedActionResult','ee_cart_imped_msgs/EECartImpedActionFeedback']
00198 
00199   def __init__(self, *args, **kwds):
00200     """
00201     Constructor. Any message fields that are implicitly/explicitly
00202     set to None will be assigned a default value. The recommend
00203     use is keyword arguments as this is more robust to future message
00204     changes.  You cannot mix in-order arguments and keyword arguments.
00205 
00206     The available fields are:
00207        action_goal,action_result,action_feedback
00208 
00209     :param args: complete set of field values, in .msg order
00210     :param kwds: use keyword arguments corresponding to message field names
00211     to set specific fields.
00212     """
00213     if args or kwds:
00214       super(EECartImpedAction, self).__init__(*args, **kwds)
00215       #message fields cannot be None, assign default values for those that are
00216       if self.action_goal is None:
00217         self.action_goal = ee_cart_imped_msgs.msg.EECartImpedActionGoal()
00218       if self.action_result is None:
00219         self.action_result = ee_cart_imped_msgs.msg.EECartImpedActionResult()
00220       if self.action_feedback is None:
00221         self.action_feedback = ee_cart_imped_msgs.msg.EECartImpedActionFeedback()
00222     else:
00223       self.action_goal = ee_cart_imped_msgs.msg.EECartImpedActionGoal()
00224       self.action_result = ee_cart_imped_msgs.msg.EECartImpedActionResult()
00225       self.action_feedback = ee_cart_imped_msgs.msg.EECartImpedActionFeedback()
00226 
00227   def _get_types(self):
00228     """
00229     internal API method
00230     """
00231     return self._slot_types
00232 
00233   def serialize(self, buff):
00234     """
00235     serialize message into buffer
00236     :param buff: buffer, ``StringIO``
00237     """
00238     try:
00239       _x = self
00240       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00241       _x = self.action_goal.header.frame_id
00242       length = len(_x)
00243       if python3 or type(_x) == unicode:
00244         _x = _x.encode('utf-8')
00245         length = len(_x)
00246       buff.write(struct.pack('<I%ss'%length, length, _x))
00247       _x = self
00248       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00249       _x = self.action_goal.goal_id.id
00250       length = len(_x)
00251       if python3 or type(_x) == unicode:
00252         _x = _x.encode('utf-8')
00253         length = len(_x)
00254       buff.write(struct.pack('<I%ss'%length, length, _x))
00255       _x = self
00256       buff.write(_struct_3I.pack(_x.action_goal.goal.header.seq, _x.action_goal.goal.header.stamp.secs, _x.action_goal.goal.header.stamp.nsecs))
00257       _x = self.action_goal.goal.header.frame_id
00258       length = len(_x)
00259       if python3 or type(_x) == unicode:
00260         _x = _x.encode('utf-8')
00261         length = len(_x)
00262       buff.write(struct.pack('<I%ss'%length, length, _x))
00263       length = len(self.action_goal.goal.trajectory)
00264       buff.write(_struct_I.pack(length))
00265       for val1 in self.action_goal.goal.trajectory:
00266         _v1 = val1.header
00267         buff.write(_struct_I.pack(_v1.seq))
00268         _v2 = _v1.stamp
00269         _x = _v2
00270         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00271         _x = _v1.frame_id
00272         length = len(_x)
00273         if python3 or type(_x) == unicode:
00274           _x = _x.encode('utf-8')
00275           length = len(_x)
00276         buff.write(struct.pack('<I%ss'%length, length, _x))
00277         _v3 = val1.pose
00278         _v4 = _v3.position
00279         _x = _v4
00280         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00281         _v5 = _v3.orientation
00282         _x = _v5
00283         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00284         _v6 = val1.wrench_or_stiffness
00285         _v7 = _v6.force
00286         _x = _v7
00287         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00288         _v8 = _v6.torque
00289         _x = _v8
00290         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00291         _x = val1
00292         buff.write(_struct_6B.pack(_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ))
00293         _v9 = val1.time_from_start
00294         _x = _v9
00295         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00296       _x = self
00297       buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00298       _x = self.action_result.header.frame_id
00299       length = len(_x)
00300       if python3 or type(_x) == unicode:
00301         _x = _x.encode('utf-8')
00302         length = len(_x)
00303       buff.write(struct.pack('<I%ss'%length, length, _x))
00304       _x = self
00305       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00306       _x = self.action_result.status.goal_id.id
00307       length = len(_x)
00308       if python3 or type(_x) == unicode:
00309         _x = _x.encode('utf-8')
00310         length = len(_x)
00311       buff.write(struct.pack('<I%ss'%length, length, _x))
00312       buff.write(_struct_B.pack(self.action_result.status.status))
00313       _x = self.action_result.status.text
00314       length = len(_x)
00315       if python3 or type(_x) == unicode:
00316         _x = _x.encode('utf-8')
00317         length = len(_x)
00318       buff.write(struct.pack('<I%ss'%length, length, _x))
00319       _x = self
00320       buff.write(_struct_3I.pack(_x.action_result.result.header.seq, _x.action_result.result.header.stamp.secs, _x.action_result.result.header.stamp.nsecs))
00321       _x = self.action_result.result.header.frame_id
00322       length = len(_x)
00323       if python3 or type(_x) == unicode:
00324         _x = _x.encode('utf-8')
00325         length = len(_x)
00326       buff.write(struct.pack('<I%ss'%length, length, _x))
00327       _x = self
00328       buff.write(_struct_B3I.pack(_x.action_result.result.success, _x.action_result.result.desired.header.seq, _x.action_result.result.desired.header.stamp.secs, _x.action_result.result.desired.header.stamp.nsecs))
00329       _x = self.action_result.result.desired.header.frame_id
00330       length = len(_x)
00331       if python3 or type(_x) == unicode:
00332         _x = _x.encode('utf-8')
00333         length = len(_x)
00334       buff.write(struct.pack('<I%ss'%length, length, _x))
00335       _x = self
00336       buff.write(_struct_13d6B2i8d3I.pack(_x.action_result.result.desired.pose.position.x, _x.action_result.result.desired.pose.position.y, _x.action_result.result.desired.pose.position.z, _x.action_result.result.desired.pose.orientation.x, _x.action_result.result.desired.pose.orientation.y, _x.action_result.result.desired.pose.orientation.z, _x.action_result.result.desired.pose.orientation.w, _x.action_result.result.desired.wrench_or_stiffness.force.x, _x.action_result.result.desired.wrench_or_stiffness.force.y, _x.action_result.result.desired.wrench_or_stiffness.force.z, _x.action_result.result.desired.wrench_or_stiffness.torque.x, _x.action_result.result.desired.wrench_or_stiffness.torque.y, _x.action_result.result.desired.wrench_or_stiffness.torque.z, _x.action_result.result.desired.isForceX, _x.action_result.result.desired.isForceY, _x.action_result.result.desired.isForceZ, _x.action_result.result.desired.isTorqueX, _x.action_result.result.desired.isTorqueY, _x.action_result.result.desired.isTorqueZ, _x.action_result.result.desired.time_from_start.secs, _x.action_result.result.desired.time_from_start.nsecs, _x.action_result.result.actual_pose.position.x, _x.action_result.result.actual_pose.position.y, _x.action_result.result.actual_pose.position.z, _x.action_result.result.actual_pose.orientation.x, _x.action_result.result.actual_pose.orientation.y, _x.action_result.result.actual_pose.orientation.z, _x.action_result.result.actual_pose.orientation.w, _x.action_result.result.effort_sq_error, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00337       _x = self.action_feedback.header.frame_id
00338       length = len(_x)
00339       if python3 or type(_x) == unicode:
00340         _x = _x.encode('utf-8')
00341         length = len(_x)
00342       buff.write(struct.pack('<I%ss'%length, length, _x))
00343       _x = self
00344       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00345       _x = self.action_feedback.status.goal_id.id
00346       length = len(_x)
00347       if python3 or type(_x) == unicode:
00348         _x = _x.encode('utf-8')
00349         length = len(_x)
00350       buff.write(struct.pack('<I%ss'%length, length, _x))
00351       buff.write(_struct_B.pack(self.action_feedback.status.status))
00352       _x = self.action_feedback.status.text
00353       length = len(_x)
00354       if python3 or type(_x) == unicode:
00355         _x = _x.encode('utf-8')
00356         length = len(_x)
00357       buff.write(struct.pack('<I%ss'%length, length, _x))
00358       _x = self
00359       buff.write(_struct_3I.pack(_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs))
00360       _x = self.action_feedback.feedback.header.frame_id
00361       length = len(_x)
00362       if python3 or type(_x) == unicode:
00363         _x = _x.encode('utf-8')
00364         length = len(_x)
00365       buff.write(struct.pack('<I%ss'%length, length, _x))
00366       length = len(self.action_feedback.feedback.goal)
00367       buff.write(_struct_I.pack(length))
00368       for val1 in self.action_feedback.feedback.goal:
00369         _v10 = val1.header
00370         buff.write(_struct_I.pack(_v10.seq))
00371         _v11 = _v10.stamp
00372         _x = _v11
00373         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00374         _x = _v10.frame_id
00375         length = len(_x)
00376         if python3 or type(_x) == unicode:
00377           _x = _x.encode('utf-8')
00378           length = len(_x)
00379         buff.write(struct.pack('<I%ss'%length, length, _x))
00380         _v12 = val1.pose
00381         _v13 = _v12.position
00382         _x = _v13
00383         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00384         _v14 = _v12.orientation
00385         _x = _v14
00386         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00387         _v15 = val1.wrench_or_stiffness
00388         _v16 = _v15.force
00389         _x = _v16
00390         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00391         _v17 = _v15.torque
00392         _x = _v17
00393         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00394         _x = val1
00395         buff.write(_struct_6B.pack(_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ))
00396         _v18 = val1.time_from_start
00397         _x = _v18
00398         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00399       _x = self
00400       buff.write(_struct_3I.pack(_x.action_feedback.feedback.initial_point.header.seq, _x.action_feedback.feedback.initial_point.header.stamp.secs, _x.action_feedback.feedback.initial_point.header.stamp.nsecs))
00401       _x = self.action_feedback.feedback.initial_point.header.frame_id
00402       length = len(_x)
00403       if python3 or type(_x) == unicode:
00404         _x = _x.encode('utf-8')
00405         length = len(_x)
00406       buff.write(struct.pack('<I%ss'%length, length, _x))
00407       _x = self
00408       buff.write(_struct_13d6B2i3I.pack(_x.action_feedback.feedback.initial_point.pose.position.x, _x.action_feedback.feedback.initial_point.pose.position.y, _x.action_feedback.feedback.initial_point.pose.position.z, _x.action_feedback.feedback.initial_point.pose.orientation.x, _x.action_feedback.feedback.initial_point.pose.orientation.y, _x.action_feedback.feedback.initial_point.pose.orientation.z, _x.action_feedback.feedback.initial_point.pose.orientation.w, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.x, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.y, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.z, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.initial_point.isForceX, _x.action_feedback.feedback.initial_point.isForceY, _x.action_feedback.feedback.initial_point.isForceZ, _x.action_feedback.feedback.initial_point.isTorqueX, _x.action_feedback.feedback.initial_point.isTorqueY, _x.action_feedback.feedback.initial_point.isTorqueZ, _x.action_feedback.feedback.initial_point.time_from_start.secs, _x.action_feedback.feedback.initial_point.time_from_start.nsecs, _x.action_feedback.feedback.desired.header.seq, _x.action_feedback.feedback.desired.header.stamp.secs, _x.action_feedback.feedback.desired.header.stamp.nsecs))
00409       _x = self.action_feedback.feedback.desired.header.frame_id
00410       length = len(_x)
00411       if python3 or type(_x) == unicode:
00412         _x = _x.encode('utf-8')
00413         length = len(_x)
00414       buff.write(struct.pack('<I%ss'%length, length, _x))
00415       _x = self
00416       buff.write(_struct_13d6B2i3I.pack(_x.action_feedback.feedback.desired.pose.position.x, _x.action_feedback.feedback.desired.pose.position.y, _x.action_feedback.feedback.desired.pose.position.z, _x.action_feedback.feedback.desired.pose.orientation.x, _x.action_feedback.feedback.desired.pose.orientation.y, _x.action_feedback.feedback.desired.pose.orientation.z, _x.action_feedback.feedback.desired.pose.orientation.w, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.x, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.y, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.z, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.desired.isForceX, _x.action_feedback.feedback.desired.isForceY, _x.action_feedback.feedback.desired.isForceZ, _x.action_feedback.feedback.desired.isTorqueX, _x.action_feedback.feedback.desired.isTorqueY, _x.action_feedback.feedback.desired.isTorqueZ, _x.action_feedback.feedback.desired.time_from_start.secs, _x.action_feedback.feedback.desired.time_from_start.nsecs, _x.action_feedback.feedback.actual_pose.header.seq, _x.action_feedback.feedback.actual_pose.header.stamp.secs, _x.action_feedback.feedback.actual_pose.header.stamp.nsecs))
00417       _x = self.action_feedback.feedback.actual_pose.header.frame_id
00418       length = len(_x)
00419       if python3 or type(_x) == unicode:
00420         _x = _x.encode('utf-8')
00421         length = len(_x)
00422       buff.write(struct.pack('<I%ss'%length, length, _x))
00423       _x = self
00424       buff.write(_struct_13d6B2id.pack(_x.action_feedback.feedback.actual_pose.pose.position.x, _x.action_feedback.feedback.actual_pose.pose.position.y, _x.action_feedback.feedback.actual_pose.pose.position.z, _x.action_feedback.feedback.actual_pose.pose.orientation.x, _x.action_feedback.feedback.actual_pose.pose.orientation.y, _x.action_feedback.feedback.actual_pose.pose.orientation.z, _x.action_feedback.feedback.actual_pose.pose.orientation.w, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.x, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.y, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.z, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.actual_pose.isForceX, _x.action_feedback.feedback.actual_pose.isForceY, _x.action_feedback.feedback.actual_pose.isForceZ, _x.action_feedback.feedback.actual_pose.isTorqueX, _x.action_feedback.feedback.actual_pose.isTorqueY, _x.action_feedback.feedback.actual_pose.isTorqueZ, _x.action_feedback.feedback.actual_pose.time_from_start.secs, _x.action_feedback.feedback.actual_pose.time_from_start.nsecs, _x.action_feedback.feedback.effort_sq_error))
00425       length = len(self.action_feedback.feedback.requested_joint_efforts)
00426       buff.write(_struct_I.pack(length))
00427       pattern = '<%sd'%length
00428       buff.write(struct.pack(pattern, *self.action_feedback.feedback.requested_joint_efforts))
00429       length = len(self.action_feedback.feedback.actual_joint_efforts)
00430       buff.write(_struct_I.pack(length))
00431       pattern = '<%sd'%length
00432       buff.write(struct.pack(pattern, *self.action_feedback.feedback.actual_joint_efforts))
00433       _x = self
00434       buff.write(_struct_2i.pack(_x.action_feedback.feedback.running_time.secs, _x.action_feedback.feedback.running_time.nsecs))
00435     except struct.error as se: self._check_types(se)
00436     except TypeError as te: self._check_types(te)
00437 
00438   def deserialize(self, str):
00439     """
00440     unpack serialized message in str into this message instance
00441     :param str: byte array of serialized message, ``str``
00442     """
00443     try:
00444       if self.action_goal is None:
00445         self.action_goal = ee_cart_imped_msgs.msg.EECartImpedActionGoal()
00446       if self.action_result is None:
00447         self.action_result = ee_cart_imped_msgs.msg.EECartImpedActionResult()
00448       if self.action_feedback is None:
00449         self.action_feedback = ee_cart_imped_msgs.msg.EECartImpedActionFeedback()
00450       end = 0
00451       _x = self
00452       start = end
00453       end += 12
00454       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00455       start = end
00456       end += 4
00457       (length,) = _struct_I.unpack(str[start:end])
00458       start = end
00459       end += length
00460       if python3:
00461         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00462       else:
00463         self.action_goal.header.frame_id = str[start:end]
00464       _x = self
00465       start = end
00466       end += 8
00467       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00468       start = end
00469       end += 4
00470       (length,) = _struct_I.unpack(str[start:end])
00471       start = end
00472       end += length
00473       if python3:
00474         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00475       else:
00476         self.action_goal.goal_id.id = str[start:end]
00477       _x = self
00478       start = end
00479       end += 12
00480       (_x.action_goal.goal.header.seq, _x.action_goal.goal.header.stamp.secs, _x.action_goal.goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00481       start = end
00482       end += 4
00483       (length,) = _struct_I.unpack(str[start:end])
00484       start = end
00485       end += length
00486       if python3:
00487         self.action_goal.goal.header.frame_id = str[start:end].decode('utf-8')
00488       else:
00489         self.action_goal.goal.header.frame_id = str[start:end]
00490       start = end
00491       end += 4
00492       (length,) = _struct_I.unpack(str[start:end])
00493       self.action_goal.goal.trajectory = []
00494       for i in range(0, length):
00495         val1 = ee_cart_imped_msgs.msg.StiffPoint()
00496         _v19 = val1.header
00497         start = end
00498         end += 4
00499         (_v19.seq,) = _struct_I.unpack(str[start:end])
00500         _v20 = _v19.stamp
00501         _x = _v20
00502         start = end
00503         end += 8
00504         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00505         start = end
00506         end += 4
00507         (length,) = _struct_I.unpack(str[start:end])
00508         start = end
00509         end += length
00510         if python3:
00511           _v19.frame_id = str[start:end].decode('utf-8')
00512         else:
00513           _v19.frame_id = str[start:end]
00514         _v21 = val1.pose
00515         _v22 = _v21.position
00516         _x = _v22
00517         start = end
00518         end += 24
00519         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00520         _v23 = _v21.orientation
00521         _x = _v23
00522         start = end
00523         end += 32
00524         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00525         _v24 = val1.wrench_or_stiffness
00526         _v25 = _v24.force
00527         _x = _v25
00528         start = end
00529         end += 24
00530         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00531         _v26 = _v24.torque
00532         _x = _v26
00533         start = end
00534         end += 24
00535         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00536         _x = val1
00537         start = end
00538         end += 6
00539         (_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ,) = _struct_6B.unpack(str[start:end])
00540         val1.isForceX = bool(val1.isForceX)
00541         val1.isForceY = bool(val1.isForceY)
00542         val1.isForceZ = bool(val1.isForceZ)
00543         val1.isTorqueX = bool(val1.isTorqueX)
00544         val1.isTorqueY = bool(val1.isTorqueY)
00545         val1.isTorqueZ = bool(val1.isTorqueZ)
00546         _v27 = val1.time_from_start
00547         _x = _v27
00548         start = end
00549         end += 8
00550         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00551         self.action_goal.goal.trajectory.append(val1)
00552       _x = self
00553       start = end
00554       end += 12
00555       (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00556       start = end
00557       end += 4
00558       (length,) = _struct_I.unpack(str[start:end])
00559       start = end
00560       end += length
00561       if python3:
00562         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00563       else:
00564         self.action_result.header.frame_id = str[start:end]
00565       _x = self
00566       start = end
00567       end += 8
00568       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00569       start = end
00570       end += 4
00571       (length,) = _struct_I.unpack(str[start:end])
00572       start = end
00573       end += length
00574       if python3:
00575         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00576       else:
00577         self.action_result.status.goal_id.id = str[start:end]
00578       start = end
00579       end += 1
00580       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00581       start = end
00582       end += 4
00583       (length,) = _struct_I.unpack(str[start:end])
00584       start = end
00585       end += length
00586       if python3:
00587         self.action_result.status.text = str[start:end].decode('utf-8')
00588       else:
00589         self.action_result.status.text = str[start:end]
00590       _x = self
00591       start = end
00592       end += 12
00593       (_x.action_result.result.header.seq, _x.action_result.result.header.stamp.secs, _x.action_result.result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00594       start = end
00595       end += 4
00596       (length,) = _struct_I.unpack(str[start:end])
00597       start = end
00598       end += length
00599       if python3:
00600         self.action_result.result.header.frame_id = str[start:end].decode('utf-8')
00601       else:
00602         self.action_result.result.header.frame_id = str[start:end]
00603       _x = self
00604       start = end
00605       end += 13
00606       (_x.action_result.result.success, _x.action_result.result.desired.header.seq, _x.action_result.result.desired.header.stamp.secs, _x.action_result.result.desired.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
00607       self.action_result.result.success = bool(self.action_result.result.success)
00608       start = end
00609       end += 4
00610       (length,) = _struct_I.unpack(str[start:end])
00611       start = end
00612       end += length
00613       if python3:
00614         self.action_result.result.desired.header.frame_id = str[start:end].decode('utf-8')
00615       else:
00616         self.action_result.result.desired.header.frame_id = str[start:end]
00617       _x = self
00618       start = end
00619       end += 194
00620       (_x.action_result.result.desired.pose.position.x, _x.action_result.result.desired.pose.position.y, _x.action_result.result.desired.pose.position.z, _x.action_result.result.desired.pose.orientation.x, _x.action_result.result.desired.pose.orientation.y, _x.action_result.result.desired.pose.orientation.z, _x.action_result.result.desired.pose.orientation.w, _x.action_result.result.desired.wrench_or_stiffness.force.x, _x.action_result.result.desired.wrench_or_stiffness.force.y, _x.action_result.result.desired.wrench_or_stiffness.force.z, _x.action_result.result.desired.wrench_or_stiffness.torque.x, _x.action_result.result.desired.wrench_or_stiffness.torque.y, _x.action_result.result.desired.wrench_or_stiffness.torque.z, _x.action_result.result.desired.isForceX, _x.action_result.result.desired.isForceY, _x.action_result.result.desired.isForceZ, _x.action_result.result.desired.isTorqueX, _x.action_result.result.desired.isTorqueY, _x.action_result.result.desired.isTorqueZ, _x.action_result.result.desired.time_from_start.secs, _x.action_result.result.desired.time_from_start.nsecs, _x.action_result.result.actual_pose.position.x, _x.action_result.result.actual_pose.position.y, _x.action_result.result.actual_pose.position.z, _x.action_result.result.actual_pose.orientation.x, _x.action_result.result.actual_pose.orientation.y, _x.action_result.result.actual_pose.orientation.z, _x.action_result.result.actual_pose.orientation.w, _x.action_result.result.effort_sq_error, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_13d6B2i8d3I.unpack(str[start:end])
00621       self.action_result.result.desired.isForceX = bool(self.action_result.result.desired.isForceX)
00622       self.action_result.result.desired.isForceY = bool(self.action_result.result.desired.isForceY)
00623       self.action_result.result.desired.isForceZ = bool(self.action_result.result.desired.isForceZ)
00624       self.action_result.result.desired.isTorqueX = bool(self.action_result.result.desired.isTorqueX)
00625       self.action_result.result.desired.isTorqueY = bool(self.action_result.result.desired.isTorqueY)
00626       self.action_result.result.desired.isTorqueZ = bool(self.action_result.result.desired.isTorqueZ)
00627       start = end
00628       end += 4
00629       (length,) = _struct_I.unpack(str[start:end])
00630       start = end
00631       end += length
00632       if python3:
00633         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00634       else:
00635         self.action_feedback.header.frame_id = str[start:end]
00636       _x = self
00637       start = end
00638       end += 8
00639       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00640       start = end
00641       end += 4
00642       (length,) = _struct_I.unpack(str[start:end])
00643       start = end
00644       end += length
00645       if python3:
00646         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00647       else:
00648         self.action_feedback.status.goal_id.id = str[start:end]
00649       start = end
00650       end += 1
00651       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00652       start = end
00653       end += 4
00654       (length,) = _struct_I.unpack(str[start:end])
00655       start = end
00656       end += length
00657       if python3:
00658         self.action_feedback.status.text = str[start:end].decode('utf-8')
00659       else:
00660         self.action_feedback.status.text = str[start:end]
00661       _x = self
00662       start = end
00663       end += 12
00664       (_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00665       start = end
00666       end += 4
00667       (length,) = _struct_I.unpack(str[start:end])
00668       start = end
00669       end += length
00670       if python3:
00671         self.action_feedback.feedback.header.frame_id = str[start:end].decode('utf-8')
00672       else:
00673         self.action_feedback.feedback.header.frame_id = str[start:end]
00674       start = end
00675       end += 4
00676       (length,) = _struct_I.unpack(str[start:end])
00677       self.action_feedback.feedback.goal = []
00678       for i in range(0, length):
00679         val1 = ee_cart_imped_msgs.msg.StiffPoint()
00680         _v28 = val1.header
00681         start = end
00682         end += 4
00683         (_v28.seq,) = _struct_I.unpack(str[start:end])
00684         _v29 = _v28.stamp
00685         _x = _v29
00686         start = end
00687         end += 8
00688         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00689         start = end
00690         end += 4
00691         (length,) = _struct_I.unpack(str[start:end])
00692         start = end
00693         end += length
00694         if python3:
00695           _v28.frame_id = str[start:end].decode('utf-8')
00696         else:
00697           _v28.frame_id = str[start:end]
00698         _v30 = val1.pose
00699         _v31 = _v30.position
00700         _x = _v31
00701         start = end
00702         end += 24
00703         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00704         _v32 = _v30.orientation
00705         _x = _v32
00706         start = end
00707         end += 32
00708         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00709         _v33 = val1.wrench_or_stiffness
00710         _v34 = _v33.force
00711         _x = _v34
00712         start = end
00713         end += 24
00714         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00715         _v35 = _v33.torque
00716         _x = _v35
00717         start = end
00718         end += 24
00719         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00720         _x = val1
00721         start = end
00722         end += 6
00723         (_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ,) = _struct_6B.unpack(str[start:end])
00724         val1.isForceX = bool(val1.isForceX)
00725         val1.isForceY = bool(val1.isForceY)
00726         val1.isForceZ = bool(val1.isForceZ)
00727         val1.isTorqueX = bool(val1.isTorqueX)
00728         val1.isTorqueY = bool(val1.isTorqueY)
00729         val1.isTorqueZ = bool(val1.isTorqueZ)
00730         _v36 = val1.time_from_start
00731         _x = _v36
00732         start = end
00733         end += 8
00734         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00735         self.action_feedback.feedback.goal.append(val1)
00736       _x = self
00737       start = end
00738       end += 12
00739       (_x.action_feedback.feedback.initial_point.header.seq, _x.action_feedback.feedback.initial_point.header.stamp.secs, _x.action_feedback.feedback.initial_point.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00740       start = end
00741       end += 4
00742       (length,) = _struct_I.unpack(str[start:end])
00743       start = end
00744       end += length
00745       if python3:
00746         self.action_feedback.feedback.initial_point.header.frame_id = str[start:end].decode('utf-8')
00747       else:
00748         self.action_feedback.feedback.initial_point.header.frame_id = str[start:end]
00749       _x = self
00750       start = end
00751       end += 130
00752       (_x.action_feedback.feedback.initial_point.pose.position.x, _x.action_feedback.feedback.initial_point.pose.position.y, _x.action_feedback.feedback.initial_point.pose.position.z, _x.action_feedback.feedback.initial_point.pose.orientation.x, _x.action_feedback.feedback.initial_point.pose.orientation.y, _x.action_feedback.feedback.initial_point.pose.orientation.z, _x.action_feedback.feedback.initial_point.pose.orientation.w, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.x, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.y, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.z, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.initial_point.isForceX, _x.action_feedback.feedback.initial_point.isForceY, _x.action_feedback.feedback.initial_point.isForceZ, _x.action_feedback.feedback.initial_point.isTorqueX, _x.action_feedback.feedback.initial_point.isTorqueY, _x.action_feedback.feedback.initial_point.isTorqueZ, _x.action_feedback.feedback.initial_point.time_from_start.secs, _x.action_feedback.feedback.initial_point.time_from_start.nsecs, _x.action_feedback.feedback.desired.header.seq, _x.action_feedback.feedback.desired.header.stamp.secs, _x.action_feedback.feedback.desired.header.stamp.nsecs,) = _struct_13d6B2i3I.unpack(str[start:end])
00753       self.action_feedback.feedback.initial_point.isForceX = bool(self.action_feedback.feedback.initial_point.isForceX)
00754       self.action_feedback.feedback.initial_point.isForceY = bool(self.action_feedback.feedback.initial_point.isForceY)
00755       self.action_feedback.feedback.initial_point.isForceZ = bool(self.action_feedback.feedback.initial_point.isForceZ)
00756       self.action_feedback.feedback.initial_point.isTorqueX = bool(self.action_feedback.feedback.initial_point.isTorqueX)
00757       self.action_feedback.feedback.initial_point.isTorqueY = bool(self.action_feedback.feedback.initial_point.isTorqueY)
00758       self.action_feedback.feedback.initial_point.isTorqueZ = bool(self.action_feedback.feedback.initial_point.isTorqueZ)
00759       start = end
00760       end += 4
00761       (length,) = _struct_I.unpack(str[start:end])
00762       start = end
00763       end += length
00764       if python3:
00765         self.action_feedback.feedback.desired.header.frame_id = str[start:end].decode('utf-8')
00766       else:
00767         self.action_feedback.feedback.desired.header.frame_id = str[start:end]
00768       _x = self
00769       start = end
00770       end += 130
00771       (_x.action_feedback.feedback.desired.pose.position.x, _x.action_feedback.feedback.desired.pose.position.y, _x.action_feedback.feedback.desired.pose.position.z, _x.action_feedback.feedback.desired.pose.orientation.x, _x.action_feedback.feedback.desired.pose.orientation.y, _x.action_feedback.feedback.desired.pose.orientation.z, _x.action_feedback.feedback.desired.pose.orientation.w, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.x, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.y, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.z, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.desired.isForceX, _x.action_feedback.feedback.desired.isForceY, _x.action_feedback.feedback.desired.isForceZ, _x.action_feedback.feedback.desired.isTorqueX, _x.action_feedback.feedback.desired.isTorqueY, _x.action_feedback.feedback.desired.isTorqueZ, _x.action_feedback.feedback.desired.time_from_start.secs, _x.action_feedback.feedback.desired.time_from_start.nsecs, _x.action_feedback.feedback.actual_pose.header.seq, _x.action_feedback.feedback.actual_pose.header.stamp.secs, _x.action_feedback.feedback.actual_pose.header.stamp.nsecs,) = _struct_13d6B2i3I.unpack(str[start:end])
00772       self.action_feedback.feedback.desired.isForceX = bool(self.action_feedback.feedback.desired.isForceX)
00773       self.action_feedback.feedback.desired.isForceY = bool(self.action_feedback.feedback.desired.isForceY)
00774       self.action_feedback.feedback.desired.isForceZ = bool(self.action_feedback.feedback.desired.isForceZ)
00775       self.action_feedback.feedback.desired.isTorqueX = bool(self.action_feedback.feedback.desired.isTorqueX)
00776       self.action_feedback.feedback.desired.isTorqueY = bool(self.action_feedback.feedback.desired.isTorqueY)
00777       self.action_feedback.feedback.desired.isTorqueZ = bool(self.action_feedback.feedback.desired.isTorqueZ)
00778       start = end
00779       end += 4
00780       (length,) = _struct_I.unpack(str[start:end])
00781       start = end
00782       end += length
00783       if python3:
00784         self.action_feedback.feedback.actual_pose.header.frame_id = str[start:end].decode('utf-8')
00785       else:
00786         self.action_feedback.feedback.actual_pose.header.frame_id = str[start:end]
00787       _x = self
00788       start = end
00789       end += 126
00790       (_x.action_feedback.feedback.actual_pose.pose.position.x, _x.action_feedback.feedback.actual_pose.pose.position.y, _x.action_feedback.feedback.actual_pose.pose.position.z, _x.action_feedback.feedback.actual_pose.pose.orientation.x, _x.action_feedback.feedback.actual_pose.pose.orientation.y, _x.action_feedback.feedback.actual_pose.pose.orientation.z, _x.action_feedback.feedback.actual_pose.pose.orientation.w, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.x, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.y, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.z, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.actual_pose.isForceX, _x.action_feedback.feedback.actual_pose.isForceY, _x.action_feedback.feedback.actual_pose.isForceZ, _x.action_feedback.feedback.actual_pose.isTorqueX, _x.action_feedback.feedback.actual_pose.isTorqueY, _x.action_feedback.feedback.actual_pose.isTorqueZ, _x.action_feedback.feedback.actual_pose.time_from_start.secs, _x.action_feedback.feedback.actual_pose.time_from_start.nsecs, _x.action_feedback.feedback.effort_sq_error,) = _struct_13d6B2id.unpack(str[start:end])
00791       self.action_feedback.feedback.actual_pose.isForceX = bool(self.action_feedback.feedback.actual_pose.isForceX)
00792       self.action_feedback.feedback.actual_pose.isForceY = bool(self.action_feedback.feedback.actual_pose.isForceY)
00793       self.action_feedback.feedback.actual_pose.isForceZ = bool(self.action_feedback.feedback.actual_pose.isForceZ)
00794       self.action_feedback.feedback.actual_pose.isTorqueX = bool(self.action_feedback.feedback.actual_pose.isTorqueX)
00795       self.action_feedback.feedback.actual_pose.isTorqueY = bool(self.action_feedback.feedback.actual_pose.isTorqueY)
00796       self.action_feedback.feedback.actual_pose.isTorqueZ = bool(self.action_feedback.feedback.actual_pose.isTorqueZ)
00797       start = end
00798       end += 4
00799       (length,) = _struct_I.unpack(str[start:end])
00800       pattern = '<%sd'%length
00801       start = end
00802       end += struct.calcsize(pattern)
00803       self.action_feedback.feedback.requested_joint_efforts = struct.unpack(pattern, str[start:end])
00804       start = end
00805       end += 4
00806       (length,) = _struct_I.unpack(str[start:end])
00807       pattern = '<%sd'%length
00808       start = end
00809       end += struct.calcsize(pattern)
00810       self.action_feedback.feedback.actual_joint_efforts = struct.unpack(pattern, str[start:end])
00811       _x = self
00812       start = end
00813       end += 8
00814       (_x.action_feedback.feedback.running_time.secs, _x.action_feedback.feedback.running_time.nsecs,) = _struct_2i.unpack(str[start:end])
00815       return self
00816     except struct.error as e:
00817       raise genpy.DeserializationError(e) #most likely buffer underfill
00818 
00819 
00820   def serialize_numpy(self, buff, numpy):
00821     """
00822     serialize message with numpy array types into buffer
00823     :param buff: buffer, ``StringIO``
00824     :param numpy: numpy python module
00825     """
00826     try:
00827       _x = self
00828       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00829       _x = self.action_goal.header.frame_id
00830       length = len(_x)
00831       if python3 or type(_x) == unicode:
00832         _x = _x.encode('utf-8')
00833         length = len(_x)
00834       buff.write(struct.pack('<I%ss'%length, length, _x))
00835       _x = self
00836       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00837       _x = self.action_goal.goal_id.id
00838       length = len(_x)
00839       if python3 or type(_x) == unicode:
00840         _x = _x.encode('utf-8')
00841         length = len(_x)
00842       buff.write(struct.pack('<I%ss'%length, length, _x))
00843       _x = self
00844       buff.write(_struct_3I.pack(_x.action_goal.goal.header.seq, _x.action_goal.goal.header.stamp.secs, _x.action_goal.goal.header.stamp.nsecs))
00845       _x = self.action_goal.goal.header.frame_id
00846       length = len(_x)
00847       if python3 or type(_x) == unicode:
00848         _x = _x.encode('utf-8')
00849         length = len(_x)
00850       buff.write(struct.pack('<I%ss'%length, length, _x))
00851       length = len(self.action_goal.goal.trajectory)
00852       buff.write(_struct_I.pack(length))
00853       for val1 in self.action_goal.goal.trajectory:
00854         _v37 = val1.header
00855         buff.write(_struct_I.pack(_v37.seq))
00856         _v38 = _v37.stamp
00857         _x = _v38
00858         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00859         _x = _v37.frame_id
00860         length = len(_x)
00861         if python3 or type(_x) == unicode:
00862           _x = _x.encode('utf-8')
00863           length = len(_x)
00864         buff.write(struct.pack('<I%ss'%length, length, _x))
00865         _v39 = val1.pose
00866         _v40 = _v39.position
00867         _x = _v40
00868         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00869         _v41 = _v39.orientation
00870         _x = _v41
00871         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00872         _v42 = val1.wrench_or_stiffness
00873         _v43 = _v42.force
00874         _x = _v43
00875         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00876         _v44 = _v42.torque
00877         _x = _v44
00878         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00879         _x = val1
00880         buff.write(_struct_6B.pack(_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ))
00881         _v45 = val1.time_from_start
00882         _x = _v45
00883         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00884       _x = self
00885       buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00886       _x = self.action_result.header.frame_id
00887       length = len(_x)
00888       if python3 or type(_x) == unicode:
00889         _x = _x.encode('utf-8')
00890         length = len(_x)
00891       buff.write(struct.pack('<I%ss'%length, length, _x))
00892       _x = self
00893       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00894       _x = self.action_result.status.goal_id.id
00895       length = len(_x)
00896       if python3 or type(_x) == unicode:
00897         _x = _x.encode('utf-8')
00898         length = len(_x)
00899       buff.write(struct.pack('<I%ss'%length, length, _x))
00900       buff.write(_struct_B.pack(self.action_result.status.status))
00901       _x = self.action_result.status.text
00902       length = len(_x)
00903       if python3 or type(_x) == unicode:
00904         _x = _x.encode('utf-8')
00905         length = len(_x)
00906       buff.write(struct.pack('<I%ss'%length, length, _x))
00907       _x = self
00908       buff.write(_struct_3I.pack(_x.action_result.result.header.seq, _x.action_result.result.header.stamp.secs, _x.action_result.result.header.stamp.nsecs))
00909       _x = self.action_result.result.header.frame_id
00910       length = len(_x)
00911       if python3 or type(_x) == unicode:
00912         _x = _x.encode('utf-8')
00913         length = len(_x)
00914       buff.write(struct.pack('<I%ss'%length, length, _x))
00915       _x = self
00916       buff.write(_struct_B3I.pack(_x.action_result.result.success, _x.action_result.result.desired.header.seq, _x.action_result.result.desired.header.stamp.secs, _x.action_result.result.desired.header.stamp.nsecs))
00917       _x = self.action_result.result.desired.header.frame_id
00918       length = len(_x)
00919       if python3 or type(_x) == unicode:
00920         _x = _x.encode('utf-8')
00921         length = len(_x)
00922       buff.write(struct.pack('<I%ss'%length, length, _x))
00923       _x = self
00924       buff.write(_struct_13d6B2i8d3I.pack(_x.action_result.result.desired.pose.position.x, _x.action_result.result.desired.pose.position.y, _x.action_result.result.desired.pose.position.z, _x.action_result.result.desired.pose.orientation.x, _x.action_result.result.desired.pose.orientation.y, _x.action_result.result.desired.pose.orientation.z, _x.action_result.result.desired.pose.orientation.w, _x.action_result.result.desired.wrench_or_stiffness.force.x, _x.action_result.result.desired.wrench_or_stiffness.force.y, _x.action_result.result.desired.wrench_or_stiffness.force.z, _x.action_result.result.desired.wrench_or_stiffness.torque.x, _x.action_result.result.desired.wrench_or_stiffness.torque.y, _x.action_result.result.desired.wrench_or_stiffness.torque.z, _x.action_result.result.desired.isForceX, _x.action_result.result.desired.isForceY, _x.action_result.result.desired.isForceZ, _x.action_result.result.desired.isTorqueX, _x.action_result.result.desired.isTorqueY, _x.action_result.result.desired.isTorqueZ, _x.action_result.result.desired.time_from_start.secs, _x.action_result.result.desired.time_from_start.nsecs, _x.action_result.result.actual_pose.position.x, _x.action_result.result.actual_pose.position.y, _x.action_result.result.actual_pose.position.z, _x.action_result.result.actual_pose.orientation.x, _x.action_result.result.actual_pose.orientation.y, _x.action_result.result.actual_pose.orientation.z, _x.action_result.result.actual_pose.orientation.w, _x.action_result.result.effort_sq_error, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00925       _x = self.action_feedback.header.frame_id
00926       length = len(_x)
00927       if python3 or type(_x) == unicode:
00928         _x = _x.encode('utf-8')
00929         length = len(_x)
00930       buff.write(struct.pack('<I%ss'%length, length, _x))
00931       _x = self
00932       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00933       _x = self.action_feedback.status.goal_id.id
00934       length = len(_x)
00935       if python3 or type(_x) == unicode:
00936         _x = _x.encode('utf-8')
00937         length = len(_x)
00938       buff.write(struct.pack('<I%ss'%length, length, _x))
00939       buff.write(_struct_B.pack(self.action_feedback.status.status))
00940       _x = self.action_feedback.status.text
00941       length = len(_x)
00942       if python3 or type(_x) == unicode:
00943         _x = _x.encode('utf-8')
00944         length = len(_x)
00945       buff.write(struct.pack('<I%ss'%length, length, _x))
00946       _x = self
00947       buff.write(_struct_3I.pack(_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs))
00948       _x = self.action_feedback.feedback.header.frame_id
00949       length = len(_x)
00950       if python3 or type(_x) == unicode:
00951         _x = _x.encode('utf-8')
00952         length = len(_x)
00953       buff.write(struct.pack('<I%ss'%length, length, _x))
00954       length = len(self.action_feedback.feedback.goal)
00955       buff.write(_struct_I.pack(length))
00956       for val1 in self.action_feedback.feedback.goal:
00957         _v46 = val1.header
00958         buff.write(_struct_I.pack(_v46.seq))
00959         _v47 = _v46.stamp
00960         _x = _v47
00961         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00962         _x = _v46.frame_id
00963         length = len(_x)
00964         if python3 or type(_x) == unicode:
00965           _x = _x.encode('utf-8')
00966           length = len(_x)
00967         buff.write(struct.pack('<I%ss'%length, length, _x))
00968         _v48 = val1.pose
00969         _v49 = _v48.position
00970         _x = _v49
00971         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00972         _v50 = _v48.orientation
00973         _x = _v50
00974         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00975         _v51 = val1.wrench_or_stiffness
00976         _v52 = _v51.force
00977         _x = _v52
00978         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00979         _v53 = _v51.torque
00980         _x = _v53
00981         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00982         _x = val1
00983         buff.write(_struct_6B.pack(_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ))
00984         _v54 = val1.time_from_start
00985         _x = _v54
00986         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00987       _x = self
00988       buff.write(_struct_3I.pack(_x.action_feedback.feedback.initial_point.header.seq, _x.action_feedback.feedback.initial_point.header.stamp.secs, _x.action_feedback.feedback.initial_point.header.stamp.nsecs))
00989       _x = self.action_feedback.feedback.initial_point.header.frame_id
00990       length = len(_x)
00991       if python3 or type(_x) == unicode:
00992         _x = _x.encode('utf-8')
00993         length = len(_x)
00994       buff.write(struct.pack('<I%ss'%length, length, _x))
00995       _x = self
00996       buff.write(_struct_13d6B2i3I.pack(_x.action_feedback.feedback.initial_point.pose.position.x, _x.action_feedback.feedback.initial_point.pose.position.y, _x.action_feedback.feedback.initial_point.pose.position.z, _x.action_feedback.feedback.initial_point.pose.orientation.x, _x.action_feedback.feedback.initial_point.pose.orientation.y, _x.action_feedback.feedback.initial_point.pose.orientation.z, _x.action_feedback.feedback.initial_point.pose.orientation.w, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.x, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.y, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.z, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.initial_point.isForceX, _x.action_feedback.feedback.initial_point.isForceY, _x.action_feedback.feedback.initial_point.isForceZ, _x.action_feedback.feedback.initial_point.isTorqueX, _x.action_feedback.feedback.initial_point.isTorqueY, _x.action_feedback.feedback.initial_point.isTorqueZ, _x.action_feedback.feedback.initial_point.time_from_start.secs, _x.action_feedback.feedback.initial_point.time_from_start.nsecs, _x.action_feedback.feedback.desired.header.seq, _x.action_feedback.feedback.desired.header.stamp.secs, _x.action_feedback.feedback.desired.header.stamp.nsecs))
00997       _x = self.action_feedback.feedback.desired.header.frame_id
00998       length = len(_x)
00999       if python3 or type(_x) == unicode:
01000         _x = _x.encode('utf-8')
01001         length = len(_x)
01002       buff.write(struct.pack('<I%ss'%length, length, _x))
01003       _x = self
01004       buff.write(_struct_13d6B2i3I.pack(_x.action_feedback.feedback.desired.pose.position.x, _x.action_feedback.feedback.desired.pose.position.y, _x.action_feedback.feedback.desired.pose.position.z, _x.action_feedback.feedback.desired.pose.orientation.x, _x.action_feedback.feedback.desired.pose.orientation.y, _x.action_feedback.feedback.desired.pose.orientation.z, _x.action_feedback.feedback.desired.pose.orientation.w, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.x, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.y, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.z, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.desired.isForceX, _x.action_feedback.feedback.desired.isForceY, _x.action_feedback.feedback.desired.isForceZ, _x.action_feedback.feedback.desired.isTorqueX, _x.action_feedback.feedback.desired.isTorqueY, _x.action_feedback.feedback.desired.isTorqueZ, _x.action_feedback.feedback.desired.time_from_start.secs, _x.action_feedback.feedback.desired.time_from_start.nsecs, _x.action_feedback.feedback.actual_pose.header.seq, _x.action_feedback.feedback.actual_pose.header.stamp.secs, _x.action_feedback.feedback.actual_pose.header.stamp.nsecs))
01005       _x = self.action_feedback.feedback.actual_pose.header.frame_id
01006       length = len(_x)
01007       if python3 or type(_x) == unicode:
01008         _x = _x.encode('utf-8')
01009         length = len(_x)
01010       buff.write(struct.pack('<I%ss'%length, length, _x))
01011       _x = self
01012       buff.write(_struct_13d6B2id.pack(_x.action_feedback.feedback.actual_pose.pose.position.x, _x.action_feedback.feedback.actual_pose.pose.position.y, _x.action_feedback.feedback.actual_pose.pose.position.z, _x.action_feedback.feedback.actual_pose.pose.orientation.x, _x.action_feedback.feedback.actual_pose.pose.orientation.y, _x.action_feedback.feedback.actual_pose.pose.orientation.z, _x.action_feedback.feedback.actual_pose.pose.orientation.w, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.x, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.y, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.z, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.actual_pose.isForceX, _x.action_feedback.feedback.actual_pose.isForceY, _x.action_feedback.feedback.actual_pose.isForceZ, _x.action_feedback.feedback.actual_pose.isTorqueX, _x.action_feedback.feedback.actual_pose.isTorqueY, _x.action_feedback.feedback.actual_pose.isTorqueZ, _x.action_feedback.feedback.actual_pose.time_from_start.secs, _x.action_feedback.feedback.actual_pose.time_from_start.nsecs, _x.action_feedback.feedback.effort_sq_error))
01013       length = len(self.action_feedback.feedback.requested_joint_efforts)
01014       buff.write(_struct_I.pack(length))
01015       pattern = '<%sd'%length
01016       buff.write(self.action_feedback.feedback.requested_joint_efforts.tostring())
01017       length = len(self.action_feedback.feedback.actual_joint_efforts)
01018       buff.write(_struct_I.pack(length))
01019       pattern = '<%sd'%length
01020       buff.write(self.action_feedback.feedback.actual_joint_efforts.tostring())
01021       _x = self
01022       buff.write(_struct_2i.pack(_x.action_feedback.feedback.running_time.secs, _x.action_feedback.feedback.running_time.nsecs))
01023     except struct.error as se: self._check_types(se)
01024     except TypeError as te: self._check_types(te)
01025 
01026   def deserialize_numpy(self, str, numpy):
01027     """
01028     unpack serialized message in str into this message instance using numpy for array types
01029     :param str: byte array of serialized message, ``str``
01030     :param numpy: numpy python module
01031     """
01032     try:
01033       if self.action_goal is None:
01034         self.action_goal = ee_cart_imped_msgs.msg.EECartImpedActionGoal()
01035       if self.action_result is None:
01036         self.action_result = ee_cart_imped_msgs.msg.EECartImpedActionResult()
01037       if self.action_feedback is None:
01038         self.action_feedback = ee_cart_imped_msgs.msg.EECartImpedActionFeedback()
01039       end = 0
01040       _x = self
01041       start = end
01042       end += 12
01043       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01044       start = end
01045       end += 4
01046       (length,) = _struct_I.unpack(str[start:end])
01047       start = end
01048       end += length
01049       if python3:
01050         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
01051       else:
01052         self.action_goal.header.frame_id = str[start:end]
01053       _x = self
01054       start = end
01055       end += 8
01056       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01057       start = end
01058       end += 4
01059       (length,) = _struct_I.unpack(str[start:end])
01060       start = end
01061       end += length
01062       if python3:
01063         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
01064       else:
01065         self.action_goal.goal_id.id = str[start:end]
01066       _x = self
01067       start = end
01068       end += 12
01069       (_x.action_goal.goal.header.seq, _x.action_goal.goal.header.stamp.secs, _x.action_goal.goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01070       start = end
01071       end += 4
01072       (length,) = _struct_I.unpack(str[start:end])
01073       start = end
01074       end += length
01075       if python3:
01076         self.action_goal.goal.header.frame_id = str[start:end].decode('utf-8')
01077       else:
01078         self.action_goal.goal.header.frame_id = str[start:end]
01079       start = end
01080       end += 4
01081       (length,) = _struct_I.unpack(str[start:end])
01082       self.action_goal.goal.trajectory = []
01083       for i in range(0, length):
01084         val1 = ee_cart_imped_msgs.msg.StiffPoint()
01085         _v55 = val1.header
01086         start = end
01087         end += 4
01088         (_v55.seq,) = _struct_I.unpack(str[start:end])
01089         _v56 = _v55.stamp
01090         _x = _v56
01091         start = end
01092         end += 8
01093         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01094         start = end
01095         end += 4
01096         (length,) = _struct_I.unpack(str[start:end])
01097         start = end
01098         end += length
01099         if python3:
01100           _v55.frame_id = str[start:end].decode('utf-8')
01101         else:
01102           _v55.frame_id = str[start:end]
01103         _v57 = val1.pose
01104         _v58 = _v57.position
01105         _x = _v58
01106         start = end
01107         end += 24
01108         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01109         _v59 = _v57.orientation
01110         _x = _v59
01111         start = end
01112         end += 32
01113         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01114         _v60 = val1.wrench_or_stiffness
01115         _v61 = _v60.force
01116         _x = _v61
01117         start = end
01118         end += 24
01119         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01120         _v62 = _v60.torque
01121         _x = _v62
01122         start = end
01123         end += 24
01124         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01125         _x = val1
01126         start = end
01127         end += 6
01128         (_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ,) = _struct_6B.unpack(str[start:end])
01129         val1.isForceX = bool(val1.isForceX)
01130         val1.isForceY = bool(val1.isForceY)
01131         val1.isForceZ = bool(val1.isForceZ)
01132         val1.isTorqueX = bool(val1.isTorqueX)
01133         val1.isTorqueY = bool(val1.isTorqueY)
01134         val1.isTorqueZ = bool(val1.isTorqueZ)
01135         _v63 = val1.time_from_start
01136         _x = _v63
01137         start = end
01138         end += 8
01139         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
01140         self.action_goal.goal.trajectory.append(val1)
01141       _x = self
01142       start = end
01143       end += 12
01144       (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01145       start = end
01146       end += 4
01147       (length,) = _struct_I.unpack(str[start:end])
01148       start = end
01149       end += length
01150       if python3:
01151         self.action_result.header.frame_id = str[start:end].decode('utf-8')
01152       else:
01153         self.action_result.header.frame_id = str[start:end]
01154       _x = self
01155       start = end
01156       end += 8
01157       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01158       start = end
01159       end += 4
01160       (length,) = _struct_I.unpack(str[start:end])
01161       start = end
01162       end += length
01163       if python3:
01164         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
01165       else:
01166         self.action_result.status.goal_id.id = str[start:end]
01167       start = end
01168       end += 1
01169       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
01170       start = end
01171       end += 4
01172       (length,) = _struct_I.unpack(str[start:end])
01173       start = end
01174       end += length
01175       if python3:
01176         self.action_result.status.text = str[start:end].decode('utf-8')
01177       else:
01178         self.action_result.status.text = str[start:end]
01179       _x = self
01180       start = end
01181       end += 12
01182       (_x.action_result.result.header.seq, _x.action_result.result.header.stamp.secs, _x.action_result.result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01183       start = end
01184       end += 4
01185       (length,) = _struct_I.unpack(str[start:end])
01186       start = end
01187       end += length
01188       if python3:
01189         self.action_result.result.header.frame_id = str[start:end].decode('utf-8')
01190       else:
01191         self.action_result.result.header.frame_id = str[start:end]
01192       _x = self
01193       start = end
01194       end += 13
01195       (_x.action_result.result.success, _x.action_result.result.desired.header.seq, _x.action_result.result.desired.header.stamp.secs, _x.action_result.result.desired.header.stamp.nsecs,) = _struct_B3I.unpack(str[start:end])
01196       self.action_result.result.success = bool(self.action_result.result.success)
01197       start = end
01198       end += 4
01199       (length,) = _struct_I.unpack(str[start:end])
01200       start = end
01201       end += length
01202       if python3:
01203         self.action_result.result.desired.header.frame_id = str[start:end].decode('utf-8')
01204       else:
01205         self.action_result.result.desired.header.frame_id = str[start:end]
01206       _x = self
01207       start = end
01208       end += 194
01209       (_x.action_result.result.desired.pose.position.x, _x.action_result.result.desired.pose.position.y, _x.action_result.result.desired.pose.position.z, _x.action_result.result.desired.pose.orientation.x, _x.action_result.result.desired.pose.orientation.y, _x.action_result.result.desired.pose.orientation.z, _x.action_result.result.desired.pose.orientation.w, _x.action_result.result.desired.wrench_or_stiffness.force.x, _x.action_result.result.desired.wrench_or_stiffness.force.y, _x.action_result.result.desired.wrench_or_stiffness.force.z, _x.action_result.result.desired.wrench_or_stiffness.torque.x, _x.action_result.result.desired.wrench_or_stiffness.torque.y, _x.action_result.result.desired.wrench_or_stiffness.torque.z, _x.action_result.result.desired.isForceX, _x.action_result.result.desired.isForceY, _x.action_result.result.desired.isForceZ, _x.action_result.result.desired.isTorqueX, _x.action_result.result.desired.isTorqueY, _x.action_result.result.desired.isTorqueZ, _x.action_result.result.desired.time_from_start.secs, _x.action_result.result.desired.time_from_start.nsecs, _x.action_result.result.actual_pose.position.x, _x.action_result.result.actual_pose.position.y, _x.action_result.result.actual_pose.position.z, _x.action_result.result.actual_pose.orientation.x, _x.action_result.result.actual_pose.orientation.y, _x.action_result.result.actual_pose.orientation.z, _x.action_result.result.actual_pose.orientation.w, _x.action_result.result.effort_sq_error, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_13d6B2i8d3I.unpack(str[start:end])
01210       self.action_result.result.desired.isForceX = bool(self.action_result.result.desired.isForceX)
01211       self.action_result.result.desired.isForceY = bool(self.action_result.result.desired.isForceY)
01212       self.action_result.result.desired.isForceZ = bool(self.action_result.result.desired.isForceZ)
01213       self.action_result.result.desired.isTorqueX = bool(self.action_result.result.desired.isTorqueX)
01214       self.action_result.result.desired.isTorqueY = bool(self.action_result.result.desired.isTorqueY)
01215       self.action_result.result.desired.isTorqueZ = bool(self.action_result.result.desired.isTorqueZ)
01216       start = end
01217       end += 4
01218       (length,) = _struct_I.unpack(str[start:end])
01219       start = end
01220       end += length
01221       if python3:
01222         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01223       else:
01224         self.action_feedback.header.frame_id = str[start:end]
01225       _x = self
01226       start = end
01227       end += 8
01228       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01229       start = end
01230       end += 4
01231       (length,) = _struct_I.unpack(str[start:end])
01232       start = end
01233       end += length
01234       if python3:
01235         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01236       else:
01237         self.action_feedback.status.goal_id.id = str[start:end]
01238       start = end
01239       end += 1
01240       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01241       start = end
01242       end += 4
01243       (length,) = _struct_I.unpack(str[start:end])
01244       start = end
01245       end += length
01246       if python3:
01247         self.action_feedback.status.text = str[start:end].decode('utf-8')
01248       else:
01249         self.action_feedback.status.text = str[start:end]
01250       _x = self
01251       start = end
01252       end += 12
01253       (_x.action_feedback.feedback.header.seq, _x.action_feedback.feedback.header.stamp.secs, _x.action_feedback.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01254       start = end
01255       end += 4
01256       (length,) = _struct_I.unpack(str[start:end])
01257       start = end
01258       end += length
01259       if python3:
01260         self.action_feedback.feedback.header.frame_id = str[start:end].decode('utf-8')
01261       else:
01262         self.action_feedback.feedback.header.frame_id = str[start:end]
01263       start = end
01264       end += 4
01265       (length,) = _struct_I.unpack(str[start:end])
01266       self.action_feedback.feedback.goal = []
01267       for i in range(0, length):
01268         val1 = ee_cart_imped_msgs.msg.StiffPoint()
01269         _v64 = val1.header
01270         start = end
01271         end += 4
01272         (_v64.seq,) = _struct_I.unpack(str[start:end])
01273         _v65 = _v64.stamp
01274         _x = _v65
01275         start = end
01276         end += 8
01277         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01278         start = end
01279         end += 4
01280         (length,) = _struct_I.unpack(str[start:end])
01281         start = end
01282         end += length
01283         if python3:
01284           _v64.frame_id = str[start:end].decode('utf-8')
01285         else:
01286           _v64.frame_id = str[start:end]
01287         _v66 = val1.pose
01288         _v67 = _v66.position
01289         _x = _v67
01290         start = end
01291         end += 24
01292         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01293         _v68 = _v66.orientation
01294         _x = _v68
01295         start = end
01296         end += 32
01297         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01298         _v69 = val1.wrench_or_stiffness
01299         _v70 = _v69.force
01300         _x = _v70
01301         start = end
01302         end += 24
01303         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01304         _v71 = _v69.torque
01305         _x = _v71
01306         start = end
01307         end += 24
01308         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01309         _x = val1
01310         start = end
01311         end += 6
01312         (_x.isForceX, _x.isForceY, _x.isForceZ, _x.isTorqueX, _x.isTorqueY, _x.isTorqueZ,) = _struct_6B.unpack(str[start:end])
01313         val1.isForceX = bool(val1.isForceX)
01314         val1.isForceY = bool(val1.isForceY)
01315         val1.isForceZ = bool(val1.isForceZ)
01316         val1.isTorqueX = bool(val1.isTorqueX)
01317         val1.isTorqueY = bool(val1.isTorqueY)
01318         val1.isTorqueZ = bool(val1.isTorqueZ)
01319         _v72 = val1.time_from_start
01320         _x = _v72
01321         start = end
01322         end += 8
01323         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
01324         self.action_feedback.feedback.goal.append(val1)
01325       _x = self
01326       start = end
01327       end += 12
01328       (_x.action_feedback.feedback.initial_point.header.seq, _x.action_feedback.feedback.initial_point.header.stamp.secs, _x.action_feedback.feedback.initial_point.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01329       start = end
01330       end += 4
01331       (length,) = _struct_I.unpack(str[start:end])
01332       start = end
01333       end += length
01334       if python3:
01335         self.action_feedback.feedback.initial_point.header.frame_id = str[start:end].decode('utf-8')
01336       else:
01337         self.action_feedback.feedback.initial_point.header.frame_id = str[start:end]
01338       _x = self
01339       start = end
01340       end += 130
01341       (_x.action_feedback.feedback.initial_point.pose.position.x, _x.action_feedback.feedback.initial_point.pose.position.y, _x.action_feedback.feedback.initial_point.pose.position.z, _x.action_feedback.feedback.initial_point.pose.orientation.x, _x.action_feedback.feedback.initial_point.pose.orientation.y, _x.action_feedback.feedback.initial_point.pose.orientation.z, _x.action_feedback.feedback.initial_point.pose.orientation.w, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.x, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.y, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.force.z, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.initial_point.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.initial_point.isForceX, _x.action_feedback.feedback.initial_point.isForceY, _x.action_feedback.feedback.initial_point.isForceZ, _x.action_feedback.feedback.initial_point.isTorqueX, _x.action_feedback.feedback.initial_point.isTorqueY, _x.action_feedback.feedback.initial_point.isTorqueZ, _x.action_feedback.feedback.initial_point.time_from_start.secs, _x.action_feedback.feedback.initial_point.time_from_start.nsecs, _x.action_feedback.feedback.desired.header.seq, _x.action_feedback.feedback.desired.header.stamp.secs, _x.action_feedback.feedback.desired.header.stamp.nsecs,) = _struct_13d6B2i3I.unpack(str[start:end])
01342       self.action_feedback.feedback.initial_point.isForceX = bool(self.action_feedback.feedback.initial_point.isForceX)
01343       self.action_feedback.feedback.initial_point.isForceY = bool(self.action_feedback.feedback.initial_point.isForceY)
01344       self.action_feedback.feedback.initial_point.isForceZ = bool(self.action_feedback.feedback.initial_point.isForceZ)
01345       self.action_feedback.feedback.initial_point.isTorqueX = bool(self.action_feedback.feedback.initial_point.isTorqueX)
01346       self.action_feedback.feedback.initial_point.isTorqueY = bool(self.action_feedback.feedback.initial_point.isTorqueY)
01347       self.action_feedback.feedback.initial_point.isTorqueZ = bool(self.action_feedback.feedback.initial_point.isTorqueZ)
01348       start = end
01349       end += 4
01350       (length,) = _struct_I.unpack(str[start:end])
01351       start = end
01352       end += length
01353       if python3:
01354         self.action_feedback.feedback.desired.header.frame_id = str[start:end].decode('utf-8')
01355       else:
01356         self.action_feedback.feedback.desired.header.frame_id = str[start:end]
01357       _x = self
01358       start = end
01359       end += 130
01360       (_x.action_feedback.feedback.desired.pose.position.x, _x.action_feedback.feedback.desired.pose.position.y, _x.action_feedback.feedback.desired.pose.position.z, _x.action_feedback.feedback.desired.pose.orientation.x, _x.action_feedback.feedback.desired.pose.orientation.y, _x.action_feedback.feedback.desired.pose.orientation.z, _x.action_feedback.feedback.desired.pose.orientation.w, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.x, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.y, _x.action_feedback.feedback.desired.wrench_or_stiffness.force.z, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.desired.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.desired.isForceX, _x.action_feedback.feedback.desired.isForceY, _x.action_feedback.feedback.desired.isForceZ, _x.action_feedback.feedback.desired.isTorqueX, _x.action_feedback.feedback.desired.isTorqueY, _x.action_feedback.feedback.desired.isTorqueZ, _x.action_feedback.feedback.desired.time_from_start.secs, _x.action_feedback.feedback.desired.time_from_start.nsecs, _x.action_feedback.feedback.actual_pose.header.seq, _x.action_feedback.feedback.actual_pose.header.stamp.secs, _x.action_feedback.feedback.actual_pose.header.stamp.nsecs,) = _struct_13d6B2i3I.unpack(str[start:end])
01361       self.action_feedback.feedback.desired.isForceX = bool(self.action_feedback.feedback.desired.isForceX)
01362       self.action_feedback.feedback.desired.isForceY = bool(self.action_feedback.feedback.desired.isForceY)
01363       self.action_feedback.feedback.desired.isForceZ = bool(self.action_feedback.feedback.desired.isForceZ)
01364       self.action_feedback.feedback.desired.isTorqueX = bool(self.action_feedback.feedback.desired.isTorqueX)
01365       self.action_feedback.feedback.desired.isTorqueY = bool(self.action_feedback.feedback.desired.isTorqueY)
01366       self.action_feedback.feedback.desired.isTorqueZ = bool(self.action_feedback.feedback.desired.isTorqueZ)
01367       start = end
01368       end += 4
01369       (length,) = _struct_I.unpack(str[start:end])
01370       start = end
01371       end += length
01372       if python3:
01373         self.action_feedback.feedback.actual_pose.header.frame_id = str[start:end].decode('utf-8')
01374       else:
01375         self.action_feedback.feedback.actual_pose.header.frame_id = str[start:end]
01376       _x = self
01377       start = end
01378       end += 126
01379       (_x.action_feedback.feedback.actual_pose.pose.position.x, _x.action_feedback.feedback.actual_pose.pose.position.y, _x.action_feedback.feedback.actual_pose.pose.position.z, _x.action_feedback.feedback.actual_pose.pose.orientation.x, _x.action_feedback.feedback.actual_pose.pose.orientation.y, _x.action_feedback.feedback.actual_pose.pose.orientation.z, _x.action_feedback.feedback.actual_pose.pose.orientation.w, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.x, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.y, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.force.z, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.x, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.y, _x.action_feedback.feedback.actual_pose.wrench_or_stiffness.torque.z, _x.action_feedback.feedback.actual_pose.isForceX, _x.action_feedback.feedback.actual_pose.isForceY, _x.action_feedback.feedback.actual_pose.isForceZ, _x.action_feedback.feedback.actual_pose.isTorqueX, _x.action_feedback.feedback.actual_pose.isTorqueY, _x.action_feedback.feedback.actual_pose.isTorqueZ, _x.action_feedback.feedback.actual_pose.time_from_start.secs, _x.action_feedback.feedback.actual_pose.time_from_start.nsecs, _x.action_feedback.feedback.effort_sq_error,) = _struct_13d6B2id.unpack(str[start:end])
01380       self.action_feedback.feedback.actual_pose.isForceX = bool(self.action_feedback.feedback.actual_pose.isForceX)
01381       self.action_feedback.feedback.actual_pose.isForceY = bool(self.action_feedback.feedback.actual_pose.isForceY)
01382       self.action_feedback.feedback.actual_pose.isForceZ = bool(self.action_feedback.feedback.actual_pose.isForceZ)
01383       self.action_feedback.feedback.actual_pose.isTorqueX = bool(self.action_feedback.feedback.actual_pose.isTorqueX)
01384       self.action_feedback.feedback.actual_pose.isTorqueY = bool(self.action_feedback.feedback.actual_pose.isTorqueY)
01385       self.action_feedback.feedback.actual_pose.isTorqueZ = bool(self.action_feedback.feedback.actual_pose.isTorqueZ)
01386       start = end
01387       end += 4
01388       (length,) = _struct_I.unpack(str[start:end])
01389       pattern = '<%sd'%length
01390       start = end
01391       end += struct.calcsize(pattern)
01392       self.action_feedback.feedback.requested_joint_efforts = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01393       start = end
01394       end += 4
01395       (length,) = _struct_I.unpack(str[start:end])
01396       pattern = '<%sd'%length
01397       start = end
01398       end += struct.calcsize(pattern)
01399       self.action_feedback.feedback.actual_joint_efforts = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
01400       _x = self
01401       start = end
01402       end += 8
01403       (_x.action_feedback.feedback.running_time.secs, _x.action_feedback.feedback.running_time.nsecs,) = _struct_2i.unpack(str[start:end])
01404       return self
01405     except struct.error as e:
01406       raise genpy.DeserializationError(e) #most likely buffer underfill
01407 
01408 _struct_I = genpy.struct_I
01409 _struct_6B = struct.Struct("<6B")
01410 _struct_B = struct.Struct("<B")
01411 _struct_13d6B2id = struct.Struct("<13d6B2id")
01412 _struct_2i = struct.Struct("<2i")
01413 _struct_3I = struct.Struct("<3I")
01414 _struct_B3I = struct.Struct("<B3I")
01415 _struct_13d6B2i3I = struct.Struct("<13d6B2i3I")
01416 _struct_13d6B2i8d3I = struct.Struct("<13d6B2i8d3I")
01417 _struct_4d = struct.Struct("<4d")
01418 _struct_2I = struct.Struct("<2I")
01419 _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