_ReactivePlaceAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from object_manipulation_msgs/ReactivePlaceAction.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 trajectory_msgs.msg
00008 import object_manipulation_msgs.msg
00009 import actionlib_msgs.msg
00010 import geometry_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013 
00014 class ReactivePlaceAction(genpy.Message):
00015   _md5sum = "ae0ee2c7f49f2e6b00a5b3a1cc9bde61"
00016   _type = "object_manipulation_msgs/ReactivePlaceAction"
00017   _has_header = False #flag to mark the presence of a Header object
00018   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019 
00020 ReactivePlaceActionGoal action_goal
00021 ReactivePlaceActionResult action_result
00022 ReactivePlaceActionFeedback action_feedback
00023 
00024 ================================================================================
00025 MSG: object_manipulation_msgs/ReactivePlaceActionGoal
00026 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00027 
00028 Header header
00029 actionlib_msgs/GoalID goal_id
00030 ReactivePlaceGoal goal
00031 
00032 ================================================================================
00033 MSG: std_msgs/Header
00034 # Standard metadata for higher-level stamped data types.
00035 # This is generally used to communicate timestamped data 
00036 # in a particular coordinate frame.
00037 # 
00038 # sequence ID: consecutively increasing ID 
00039 uint32 seq
00040 #Two-integer timestamp that is expressed as:
00041 # * stamp.secs: seconds (stamp_secs) since epoch
00042 # * stamp.nsecs: nanoseconds since stamp_secs
00043 # time-handling sugar is provided by the client library
00044 time stamp
00045 #Frame this data is associated with
00046 # 0: no frame
00047 # 1: global frame
00048 string frame_id
00049 
00050 ================================================================================
00051 MSG: actionlib_msgs/GoalID
00052 # The stamp should store the time at which this goal was requested.
00053 # It is used by an action server when it tries to preempt all
00054 # goals that were requested before a certain time
00055 time stamp
00056 
00057 # The id provides a way to associate feedback and
00058 # result message with specific goal requests. The id
00059 # specified must be unique.
00060 string id
00061 
00062 
00063 ================================================================================
00064 MSG: object_manipulation_msgs/ReactivePlaceGoal
00065 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00066 # an action for placing the object using tactile sensor feedback.
00067 # a reactive place starts from the current pose of the gripper and ends
00068 # at a desired place pose, presumably using the touch sensors along the way
00069 
00070 # the name of the arm being used
00071 string arm_name
00072 
00073 # the desired final place pose for the hand
00074 geometry_msgs/PoseStamped final_place_pose
00075 
00076 # the joint trajectory to use for the place (if available)
00077 # this trajectory is expected to start at the current pose of the gripper
00078 # and end at the desired place pose
00079 trajectory_msgs/JointTrajectory trajectory
00080 
00081 # the name of the support surface in the collision environment, if any
00082 string collision_support_surface_name
00083 
00084 # the name in the collision environment of the object being placed, if any
00085 string collision_object_name
00086 
00087 ================================================================================
00088 MSG: geometry_msgs/PoseStamped
00089 # A Pose with reference coordinate frame and timestamp
00090 Header header
00091 Pose pose
00092 
00093 ================================================================================
00094 MSG: geometry_msgs/Pose
00095 # A representation of pose in free space, composed of postion and orientation. 
00096 Point position
00097 Quaternion orientation
00098 
00099 ================================================================================
00100 MSG: geometry_msgs/Point
00101 # This contains the position of a point in free space
00102 float64 x
00103 float64 y
00104 float64 z
00105 
00106 ================================================================================
00107 MSG: geometry_msgs/Quaternion
00108 # This represents an orientation in free space in quaternion form.
00109 
00110 float64 x
00111 float64 y
00112 float64 z
00113 float64 w
00114 
00115 ================================================================================
00116 MSG: trajectory_msgs/JointTrajectory
00117 Header header
00118 string[] joint_names
00119 JointTrajectoryPoint[] points
00120 ================================================================================
00121 MSG: trajectory_msgs/JointTrajectoryPoint
00122 float64[] positions
00123 float64[] velocities
00124 float64[] accelerations
00125 duration time_from_start
00126 ================================================================================
00127 MSG: object_manipulation_msgs/ReactivePlaceActionResult
00128 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00129 
00130 Header header
00131 actionlib_msgs/GoalStatus status
00132 ReactivePlaceResult result
00133 
00134 ================================================================================
00135 MSG: actionlib_msgs/GoalStatus
00136 GoalID goal_id
00137 uint8 status
00138 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00139 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00140 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00141                             #   and has since completed its execution (Terminal State)
00142 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00143 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00144                             #    to some failure (Terminal State)
00145 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00146                             #    because the goal was unattainable or invalid (Terminal State)
00147 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00148                             #    and has not yet completed execution
00149 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00150                             #    but the action server has not yet confirmed that the goal is canceled
00151 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00152                             #    and was successfully cancelled (Terminal State)
00153 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00154                             #    sent over the wire by an action server
00155 
00156 #Allow for the user to associate a string with GoalStatus for debugging
00157 string text
00158 
00159 
00160 ================================================================================
00161 MSG: object_manipulation_msgs/ReactivePlaceResult
00162 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00163 
00164 # the result of the reactive place attempt
00165 
00166 ManipulationResult manipulation_result
00167 
00168 
00169 ================================================================================
00170 MSG: object_manipulation_msgs/ManipulationResult
00171 # Result codes for manipulation tasks
00172 
00173 # task completed as expected
00174 # generally means you can proceed as planned
00175 int32 SUCCESS = 1
00176 
00177 # task not possible (e.g. out of reach or obstacles in the way)
00178 # generally means that the world was not disturbed, so you can try another task
00179 int32 UNFEASIBLE = -1
00180 
00181 # task was thought possible, but failed due to unexpected events during execution
00182 # it is likely that the world was disturbed, so you are encouraged to refresh
00183 # your sensed world model before proceeding to another task
00184 int32 FAILED = -2
00185 
00186 # a lower level error prevented task completion (e.g. joint controller not responding)
00187 # generally requires human attention
00188 int32 ERROR = -3
00189 
00190 # means that at some point during execution we ended up in a state that the collision-aware
00191 # arm navigation module will not move out of. The world was likely not disturbed, but you 
00192 # probably need a new collision map to move the arm out of the stuck position
00193 int32 ARM_MOVEMENT_PREVENTED = -4
00194 
00195 # specific to grasp actions
00196 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested
00197 # it is likely that the collision environment will see collisions between the hand/object and the support surface
00198 int32 LIFT_FAILED = -5
00199 
00200 # specific to place actions
00201 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested
00202 # it is likely that the collision environment will see collisions between the hand and the object
00203 int32 RETREAT_FAILED = -6
00204 
00205 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else"
00206 int32 CANCELLED = -7
00207 
00208 # the actual value of this error code
00209 int32 value
00210 
00211 ================================================================================
00212 MSG: object_manipulation_msgs/ReactivePlaceActionFeedback
00213 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00214 
00215 Header header
00216 actionlib_msgs/GoalStatus status
00217 ReactivePlaceFeedback feedback
00218 
00219 ================================================================================
00220 MSG: object_manipulation_msgs/ReactivePlaceFeedback
00221 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00222 
00223 # which phase the place is in
00224 
00225 ManipulationPhase manipulation_phase
00226 
00227 
00228 ================================================================================
00229 MSG: object_manipulation_msgs/ManipulationPhase
00230 int32 CHECKING_FEASIBILITY = 0
00231 int32 MOVING_TO_PREGRASP = 1
00232 int32 MOVING_TO_GRASP = 2
00233 int32 CLOSING = 3 
00234 int32 ADJUSTING_GRASP = 4
00235 int32 LIFTING = 5
00236 int32 MOVING_WITH_OBJECT = 6
00237 int32 MOVING_TO_PLACE = 7
00238 int32 PLACING = 8
00239 int32 OPENING = 9
00240 int32 RETREATING = 10
00241 int32 MOVING_WITHOUT_OBJECT = 11
00242 int32 SHAKING = 12
00243 int32 SUCCEEDED = 13
00244 int32 FAILED = 14
00245 int32 ABORTED = 15
00246 int32 HOLDING_OBJECT = 16
00247 
00248 int32 phase
00249 """
00250   __slots__ = ['action_goal','action_result','action_feedback']
00251   _slot_types = ['object_manipulation_msgs/ReactivePlaceActionGoal','object_manipulation_msgs/ReactivePlaceActionResult','object_manipulation_msgs/ReactivePlaceActionFeedback']
00252 
00253   def __init__(self, *args, **kwds):
00254     """
00255     Constructor. Any message fields that are implicitly/explicitly
00256     set to None will be assigned a default value. The recommend
00257     use is keyword arguments as this is more robust to future message
00258     changes.  You cannot mix in-order arguments and keyword arguments.
00259 
00260     The available fields are:
00261        action_goal,action_result,action_feedback
00262 
00263     :param args: complete set of field values, in .msg order
00264     :param kwds: use keyword arguments corresponding to message field names
00265     to set specific fields.
00266     """
00267     if args or kwds:
00268       super(ReactivePlaceAction, self).__init__(*args, **kwds)
00269       #message fields cannot be None, assign default values for those that are
00270       if self.action_goal is None:
00271         self.action_goal = object_manipulation_msgs.msg.ReactivePlaceActionGoal()
00272       if self.action_result is None:
00273         self.action_result = object_manipulation_msgs.msg.ReactivePlaceActionResult()
00274       if self.action_feedback is None:
00275         self.action_feedback = object_manipulation_msgs.msg.ReactivePlaceActionFeedback()
00276     else:
00277       self.action_goal = object_manipulation_msgs.msg.ReactivePlaceActionGoal()
00278       self.action_result = object_manipulation_msgs.msg.ReactivePlaceActionResult()
00279       self.action_feedback = object_manipulation_msgs.msg.ReactivePlaceActionFeedback()
00280 
00281   def _get_types(self):
00282     """
00283     internal API method
00284     """
00285     return self._slot_types
00286 
00287   def serialize(self, buff):
00288     """
00289     serialize message into buffer
00290     :param buff: buffer, ``StringIO``
00291     """
00292     try:
00293       _x = self
00294       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00295       _x = self.action_goal.header.frame_id
00296       length = len(_x)
00297       if python3 or type(_x) == unicode:
00298         _x = _x.encode('utf-8')
00299         length = len(_x)
00300       buff.write(struct.pack('<I%ss'%length, length, _x))
00301       _x = self
00302       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00303       _x = self.action_goal.goal_id.id
00304       length = len(_x)
00305       if python3 or type(_x) == unicode:
00306         _x = _x.encode('utf-8')
00307         length = len(_x)
00308       buff.write(struct.pack('<I%ss'%length, length, _x))
00309       _x = self.action_goal.goal.arm_name
00310       length = len(_x)
00311       if python3 or type(_x) == unicode:
00312         _x = _x.encode('utf-8')
00313         length = len(_x)
00314       buff.write(struct.pack('<I%ss'%length, length, _x))
00315       _x = self
00316       buff.write(_struct_3I.pack(_x.action_goal.goal.final_place_pose.header.seq, _x.action_goal.goal.final_place_pose.header.stamp.secs, _x.action_goal.goal.final_place_pose.header.stamp.nsecs))
00317       _x = self.action_goal.goal.final_place_pose.header.frame_id
00318       length = len(_x)
00319       if python3 or type(_x) == unicode:
00320         _x = _x.encode('utf-8')
00321         length = len(_x)
00322       buff.write(struct.pack('<I%ss'%length, length, _x))
00323       _x = self
00324       buff.write(_struct_7d3I.pack(_x.action_goal.goal.final_place_pose.pose.position.x, _x.action_goal.goal.final_place_pose.pose.position.y, _x.action_goal.goal.final_place_pose.pose.position.z, _x.action_goal.goal.final_place_pose.pose.orientation.x, _x.action_goal.goal.final_place_pose.pose.orientation.y, _x.action_goal.goal.final_place_pose.pose.orientation.z, _x.action_goal.goal.final_place_pose.pose.orientation.w, _x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs))
00325       _x = self.action_goal.goal.trajectory.header.frame_id
00326       length = len(_x)
00327       if python3 or type(_x) == unicode:
00328         _x = _x.encode('utf-8')
00329         length = len(_x)
00330       buff.write(struct.pack('<I%ss'%length, length, _x))
00331       length = len(self.action_goal.goal.trajectory.joint_names)
00332       buff.write(_struct_I.pack(length))
00333       for val1 in self.action_goal.goal.trajectory.joint_names:
00334         length = len(val1)
00335         if python3 or type(val1) == unicode:
00336           val1 = val1.encode('utf-8')
00337           length = len(val1)
00338         buff.write(struct.pack('<I%ss'%length, length, val1))
00339       length = len(self.action_goal.goal.trajectory.points)
00340       buff.write(_struct_I.pack(length))
00341       for val1 in self.action_goal.goal.trajectory.points:
00342         length = len(val1.positions)
00343         buff.write(_struct_I.pack(length))
00344         pattern = '<%sd'%length
00345         buff.write(struct.pack(pattern, *val1.positions))
00346         length = len(val1.velocities)
00347         buff.write(_struct_I.pack(length))
00348         pattern = '<%sd'%length
00349         buff.write(struct.pack(pattern, *val1.velocities))
00350         length = len(val1.accelerations)
00351         buff.write(_struct_I.pack(length))
00352         pattern = '<%sd'%length
00353         buff.write(struct.pack(pattern, *val1.accelerations))
00354         _v1 = val1.time_from_start
00355         _x = _v1
00356         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00357       _x = self.action_goal.goal.collision_support_surface_name
00358       length = len(_x)
00359       if python3 or type(_x) == unicode:
00360         _x = _x.encode('utf-8')
00361         length = len(_x)
00362       buff.write(struct.pack('<I%ss'%length, length, _x))
00363       _x = self.action_goal.goal.collision_object_name
00364       length = len(_x)
00365       if python3 or type(_x) == unicode:
00366         _x = _x.encode('utf-8')
00367         length = len(_x)
00368       buff.write(struct.pack('<I%ss'%length, length, _x))
00369       _x = self
00370       buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00371       _x = self.action_result.header.frame_id
00372       length = len(_x)
00373       if python3 or type(_x) == unicode:
00374         _x = _x.encode('utf-8')
00375         length = len(_x)
00376       buff.write(struct.pack('<I%ss'%length, length, _x))
00377       _x = self
00378       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00379       _x = self.action_result.status.goal_id.id
00380       length = len(_x)
00381       if python3 or type(_x) == unicode:
00382         _x = _x.encode('utf-8')
00383         length = len(_x)
00384       buff.write(struct.pack('<I%ss'%length, length, _x))
00385       buff.write(_struct_B.pack(self.action_result.status.status))
00386       _x = self.action_result.status.text
00387       length = len(_x)
00388       if python3 or type(_x) == unicode:
00389         _x = _x.encode('utf-8')
00390         length = len(_x)
00391       buff.write(struct.pack('<I%ss'%length, length, _x))
00392       _x = self
00393       buff.write(_struct_i3I.pack(_x.action_result.result.manipulation_result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00394       _x = self.action_feedback.header.frame_id
00395       length = len(_x)
00396       if python3 or type(_x) == unicode:
00397         _x = _x.encode('utf-8')
00398         length = len(_x)
00399       buff.write(struct.pack('<I%ss'%length, length, _x))
00400       _x = self
00401       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00402       _x = self.action_feedback.status.goal_id.id
00403       length = len(_x)
00404       if python3 or type(_x) == unicode:
00405         _x = _x.encode('utf-8')
00406         length = len(_x)
00407       buff.write(struct.pack('<I%ss'%length, length, _x))
00408       buff.write(_struct_B.pack(self.action_feedback.status.status))
00409       _x = self.action_feedback.status.text
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       buff.write(_struct_i.pack(self.action_feedback.feedback.manipulation_phase.phase))
00416     except struct.error as se: self._check_types(se)
00417     except TypeError as te: self._check_types(te)
00418 
00419   def deserialize(self, str):
00420     """
00421     unpack serialized message in str into this message instance
00422     :param str: byte array of serialized message, ``str``
00423     """
00424     try:
00425       if self.action_goal is None:
00426         self.action_goal = object_manipulation_msgs.msg.ReactivePlaceActionGoal()
00427       if self.action_result is None:
00428         self.action_result = object_manipulation_msgs.msg.ReactivePlaceActionResult()
00429       if self.action_feedback is None:
00430         self.action_feedback = object_manipulation_msgs.msg.ReactivePlaceActionFeedback()
00431       end = 0
00432       _x = self
00433       start = end
00434       end += 12
00435       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00436       start = end
00437       end += 4
00438       (length,) = _struct_I.unpack(str[start:end])
00439       start = end
00440       end += length
00441       if python3:
00442         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00443       else:
00444         self.action_goal.header.frame_id = str[start:end]
00445       _x = self
00446       start = end
00447       end += 8
00448       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00449       start = end
00450       end += 4
00451       (length,) = _struct_I.unpack(str[start:end])
00452       start = end
00453       end += length
00454       if python3:
00455         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00456       else:
00457         self.action_goal.goal_id.id = str[start:end]
00458       start = end
00459       end += 4
00460       (length,) = _struct_I.unpack(str[start:end])
00461       start = end
00462       end += length
00463       if python3:
00464         self.action_goal.goal.arm_name = str[start:end].decode('utf-8')
00465       else:
00466         self.action_goal.goal.arm_name = str[start:end]
00467       _x = self
00468       start = end
00469       end += 12
00470       (_x.action_goal.goal.final_place_pose.header.seq, _x.action_goal.goal.final_place_pose.header.stamp.secs, _x.action_goal.goal.final_place_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00471       start = end
00472       end += 4
00473       (length,) = _struct_I.unpack(str[start:end])
00474       start = end
00475       end += length
00476       if python3:
00477         self.action_goal.goal.final_place_pose.header.frame_id = str[start:end].decode('utf-8')
00478       else:
00479         self.action_goal.goal.final_place_pose.header.frame_id = str[start:end]
00480       _x = self
00481       start = end
00482       end += 68
00483       (_x.action_goal.goal.final_place_pose.pose.position.x, _x.action_goal.goal.final_place_pose.pose.position.y, _x.action_goal.goal.final_place_pose.pose.position.z, _x.action_goal.goal.final_place_pose.pose.orientation.x, _x.action_goal.goal.final_place_pose.pose.orientation.y, _x.action_goal.goal.final_place_pose.pose.orientation.z, _x.action_goal.goal.final_place_pose.pose.orientation.w, _x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00484       start = end
00485       end += 4
00486       (length,) = _struct_I.unpack(str[start:end])
00487       start = end
00488       end += length
00489       if python3:
00490         self.action_goal.goal.trajectory.header.frame_id = str[start:end].decode('utf-8')
00491       else:
00492         self.action_goal.goal.trajectory.header.frame_id = str[start:end]
00493       start = end
00494       end += 4
00495       (length,) = _struct_I.unpack(str[start:end])
00496       self.action_goal.goal.trajectory.joint_names = []
00497       for i in range(0, length):
00498         start = end
00499         end += 4
00500         (length,) = _struct_I.unpack(str[start:end])
00501         start = end
00502         end += length
00503         if python3:
00504           val1 = str[start:end].decode('utf-8')
00505         else:
00506           val1 = str[start:end]
00507         self.action_goal.goal.trajectory.joint_names.append(val1)
00508       start = end
00509       end += 4
00510       (length,) = _struct_I.unpack(str[start:end])
00511       self.action_goal.goal.trajectory.points = []
00512       for i in range(0, length):
00513         val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00514         start = end
00515         end += 4
00516         (length,) = _struct_I.unpack(str[start:end])
00517         pattern = '<%sd'%length
00518         start = end
00519         end += struct.calcsize(pattern)
00520         val1.positions = struct.unpack(pattern, str[start:end])
00521         start = end
00522         end += 4
00523         (length,) = _struct_I.unpack(str[start:end])
00524         pattern = '<%sd'%length
00525         start = end
00526         end += struct.calcsize(pattern)
00527         val1.velocities = struct.unpack(pattern, str[start:end])
00528         start = end
00529         end += 4
00530         (length,) = _struct_I.unpack(str[start:end])
00531         pattern = '<%sd'%length
00532         start = end
00533         end += struct.calcsize(pattern)
00534         val1.accelerations = struct.unpack(pattern, str[start:end])
00535         _v2 = val1.time_from_start
00536         _x = _v2
00537         start = end
00538         end += 8
00539         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00540         self.action_goal.goal.trajectory.points.append(val1)
00541       start = end
00542       end += 4
00543       (length,) = _struct_I.unpack(str[start:end])
00544       start = end
00545       end += length
00546       if python3:
00547         self.action_goal.goal.collision_support_surface_name = str[start:end].decode('utf-8')
00548       else:
00549         self.action_goal.goal.collision_support_surface_name = str[start:end]
00550       start = end
00551       end += 4
00552       (length,) = _struct_I.unpack(str[start:end])
00553       start = end
00554       end += length
00555       if python3:
00556         self.action_goal.goal.collision_object_name = str[start:end].decode('utf-8')
00557       else:
00558         self.action_goal.goal.collision_object_name = str[start:end]
00559       _x = self
00560       start = end
00561       end += 12
00562       (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00563       start = end
00564       end += 4
00565       (length,) = _struct_I.unpack(str[start:end])
00566       start = end
00567       end += length
00568       if python3:
00569         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00570       else:
00571         self.action_result.header.frame_id = str[start:end]
00572       _x = self
00573       start = end
00574       end += 8
00575       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00576       start = end
00577       end += 4
00578       (length,) = _struct_I.unpack(str[start:end])
00579       start = end
00580       end += length
00581       if python3:
00582         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00583       else:
00584         self.action_result.status.goal_id.id = str[start:end]
00585       start = end
00586       end += 1
00587       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00588       start = end
00589       end += 4
00590       (length,) = _struct_I.unpack(str[start:end])
00591       start = end
00592       end += length
00593       if python3:
00594         self.action_result.status.text = str[start:end].decode('utf-8')
00595       else:
00596         self.action_result.status.text = str[start:end]
00597       _x = self
00598       start = end
00599       end += 16
00600       (_x.action_result.result.manipulation_result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00601       start = end
00602       end += 4
00603       (length,) = _struct_I.unpack(str[start:end])
00604       start = end
00605       end += length
00606       if python3:
00607         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00608       else:
00609         self.action_feedback.header.frame_id = str[start:end]
00610       _x = self
00611       start = end
00612       end += 8
00613       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00614       start = end
00615       end += 4
00616       (length,) = _struct_I.unpack(str[start:end])
00617       start = end
00618       end += length
00619       if python3:
00620         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00621       else:
00622         self.action_feedback.status.goal_id.id = str[start:end]
00623       start = end
00624       end += 1
00625       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00626       start = end
00627       end += 4
00628       (length,) = _struct_I.unpack(str[start:end])
00629       start = end
00630       end += length
00631       if python3:
00632         self.action_feedback.status.text = str[start:end].decode('utf-8')
00633       else:
00634         self.action_feedback.status.text = str[start:end]
00635       start = end
00636       end += 4
00637       (self.action_feedback.feedback.manipulation_phase.phase,) = _struct_i.unpack(str[start:end])
00638       return self
00639     except struct.error as e:
00640       raise genpy.DeserializationError(e) #most likely buffer underfill
00641 
00642 
00643   def serialize_numpy(self, buff, numpy):
00644     """
00645     serialize message with numpy array types into buffer
00646     :param buff: buffer, ``StringIO``
00647     :param numpy: numpy python module
00648     """
00649     try:
00650       _x = self
00651       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00652       _x = self.action_goal.header.frame_id
00653       length = len(_x)
00654       if python3 or type(_x) == unicode:
00655         _x = _x.encode('utf-8')
00656         length = len(_x)
00657       buff.write(struct.pack('<I%ss'%length, length, _x))
00658       _x = self
00659       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00660       _x = self.action_goal.goal_id.id
00661       length = len(_x)
00662       if python3 or type(_x) == unicode:
00663         _x = _x.encode('utf-8')
00664         length = len(_x)
00665       buff.write(struct.pack('<I%ss'%length, length, _x))
00666       _x = self.action_goal.goal.arm_name
00667       length = len(_x)
00668       if python3 or type(_x) == unicode:
00669         _x = _x.encode('utf-8')
00670         length = len(_x)
00671       buff.write(struct.pack('<I%ss'%length, length, _x))
00672       _x = self
00673       buff.write(_struct_3I.pack(_x.action_goal.goal.final_place_pose.header.seq, _x.action_goal.goal.final_place_pose.header.stamp.secs, _x.action_goal.goal.final_place_pose.header.stamp.nsecs))
00674       _x = self.action_goal.goal.final_place_pose.header.frame_id
00675       length = len(_x)
00676       if python3 or type(_x) == unicode:
00677         _x = _x.encode('utf-8')
00678         length = len(_x)
00679       buff.write(struct.pack('<I%ss'%length, length, _x))
00680       _x = self
00681       buff.write(_struct_7d3I.pack(_x.action_goal.goal.final_place_pose.pose.position.x, _x.action_goal.goal.final_place_pose.pose.position.y, _x.action_goal.goal.final_place_pose.pose.position.z, _x.action_goal.goal.final_place_pose.pose.orientation.x, _x.action_goal.goal.final_place_pose.pose.orientation.y, _x.action_goal.goal.final_place_pose.pose.orientation.z, _x.action_goal.goal.final_place_pose.pose.orientation.w, _x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs))
00682       _x = self.action_goal.goal.trajectory.header.frame_id
00683       length = len(_x)
00684       if python3 or type(_x) == unicode:
00685         _x = _x.encode('utf-8')
00686         length = len(_x)
00687       buff.write(struct.pack('<I%ss'%length, length, _x))
00688       length = len(self.action_goal.goal.trajectory.joint_names)
00689       buff.write(_struct_I.pack(length))
00690       for val1 in self.action_goal.goal.trajectory.joint_names:
00691         length = len(val1)
00692         if python3 or type(val1) == unicode:
00693           val1 = val1.encode('utf-8')
00694           length = len(val1)
00695         buff.write(struct.pack('<I%ss'%length, length, val1))
00696       length = len(self.action_goal.goal.trajectory.points)
00697       buff.write(_struct_I.pack(length))
00698       for val1 in self.action_goal.goal.trajectory.points:
00699         length = len(val1.positions)
00700         buff.write(_struct_I.pack(length))
00701         pattern = '<%sd'%length
00702         buff.write(val1.positions.tostring())
00703         length = len(val1.velocities)
00704         buff.write(_struct_I.pack(length))
00705         pattern = '<%sd'%length
00706         buff.write(val1.velocities.tostring())
00707         length = len(val1.accelerations)
00708         buff.write(_struct_I.pack(length))
00709         pattern = '<%sd'%length
00710         buff.write(val1.accelerations.tostring())
00711         _v3 = val1.time_from_start
00712         _x = _v3
00713         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00714       _x = self.action_goal.goal.collision_support_surface_name
00715       length = len(_x)
00716       if python3 or type(_x) == unicode:
00717         _x = _x.encode('utf-8')
00718         length = len(_x)
00719       buff.write(struct.pack('<I%ss'%length, length, _x))
00720       _x = self.action_goal.goal.collision_object_name
00721       length = len(_x)
00722       if python3 or type(_x) == unicode:
00723         _x = _x.encode('utf-8')
00724         length = len(_x)
00725       buff.write(struct.pack('<I%ss'%length, length, _x))
00726       _x = self
00727       buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00728       _x = self.action_result.header.frame_id
00729       length = len(_x)
00730       if python3 or type(_x) == unicode:
00731         _x = _x.encode('utf-8')
00732         length = len(_x)
00733       buff.write(struct.pack('<I%ss'%length, length, _x))
00734       _x = self
00735       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00736       _x = self.action_result.status.goal_id.id
00737       length = len(_x)
00738       if python3 or type(_x) == unicode:
00739         _x = _x.encode('utf-8')
00740         length = len(_x)
00741       buff.write(struct.pack('<I%ss'%length, length, _x))
00742       buff.write(_struct_B.pack(self.action_result.status.status))
00743       _x = self.action_result.status.text
00744       length = len(_x)
00745       if python3 or type(_x) == unicode:
00746         _x = _x.encode('utf-8')
00747         length = len(_x)
00748       buff.write(struct.pack('<I%ss'%length, length, _x))
00749       _x = self
00750       buff.write(_struct_i3I.pack(_x.action_result.result.manipulation_result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00751       _x = self.action_feedback.header.frame_id
00752       length = len(_x)
00753       if python3 or type(_x) == unicode:
00754         _x = _x.encode('utf-8')
00755         length = len(_x)
00756       buff.write(struct.pack('<I%ss'%length, length, _x))
00757       _x = self
00758       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00759       _x = self.action_feedback.status.goal_id.id
00760       length = len(_x)
00761       if python3 or type(_x) == unicode:
00762         _x = _x.encode('utf-8')
00763         length = len(_x)
00764       buff.write(struct.pack('<I%ss'%length, length, _x))
00765       buff.write(_struct_B.pack(self.action_feedback.status.status))
00766       _x = self.action_feedback.status.text
00767       length = len(_x)
00768       if python3 or type(_x) == unicode:
00769         _x = _x.encode('utf-8')
00770         length = len(_x)
00771       buff.write(struct.pack('<I%ss'%length, length, _x))
00772       buff.write(_struct_i.pack(self.action_feedback.feedback.manipulation_phase.phase))
00773     except struct.error as se: self._check_types(se)
00774     except TypeError as te: self._check_types(te)
00775 
00776   def deserialize_numpy(self, str, numpy):
00777     """
00778     unpack serialized message in str into this message instance using numpy for array types
00779     :param str: byte array of serialized message, ``str``
00780     :param numpy: numpy python module
00781     """
00782     try:
00783       if self.action_goal is None:
00784         self.action_goal = object_manipulation_msgs.msg.ReactivePlaceActionGoal()
00785       if self.action_result is None:
00786         self.action_result = object_manipulation_msgs.msg.ReactivePlaceActionResult()
00787       if self.action_feedback is None:
00788         self.action_feedback = object_manipulation_msgs.msg.ReactivePlaceActionFeedback()
00789       end = 0
00790       _x = self
00791       start = end
00792       end += 12
00793       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00794       start = end
00795       end += 4
00796       (length,) = _struct_I.unpack(str[start:end])
00797       start = end
00798       end += length
00799       if python3:
00800         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00801       else:
00802         self.action_goal.header.frame_id = str[start:end]
00803       _x = self
00804       start = end
00805       end += 8
00806       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00807       start = end
00808       end += 4
00809       (length,) = _struct_I.unpack(str[start:end])
00810       start = end
00811       end += length
00812       if python3:
00813         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00814       else:
00815         self.action_goal.goal_id.id = str[start:end]
00816       start = end
00817       end += 4
00818       (length,) = _struct_I.unpack(str[start:end])
00819       start = end
00820       end += length
00821       if python3:
00822         self.action_goal.goal.arm_name = str[start:end].decode('utf-8')
00823       else:
00824         self.action_goal.goal.arm_name = str[start:end]
00825       _x = self
00826       start = end
00827       end += 12
00828       (_x.action_goal.goal.final_place_pose.header.seq, _x.action_goal.goal.final_place_pose.header.stamp.secs, _x.action_goal.goal.final_place_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00829       start = end
00830       end += 4
00831       (length,) = _struct_I.unpack(str[start:end])
00832       start = end
00833       end += length
00834       if python3:
00835         self.action_goal.goal.final_place_pose.header.frame_id = str[start:end].decode('utf-8')
00836       else:
00837         self.action_goal.goal.final_place_pose.header.frame_id = str[start:end]
00838       _x = self
00839       start = end
00840       end += 68
00841       (_x.action_goal.goal.final_place_pose.pose.position.x, _x.action_goal.goal.final_place_pose.pose.position.y, _x.action_goal.goal.final_place_pose.pose.position.z, _x.action_goal.goal.final_place_pose.pose.orientation.x, _x.action_goal.goal.final_place_pose.pose.orientation.y, _x.action_goal.goal.final_place_pose.pose.orientation.z, _x.action_goal.goal.final_place_pose.pose.orientation.w, _x.action_goal.goal.trajectory.header.seq, _x.action_goal.goal.trajectory.header.stamp.secs, _x.action_goal.goal.trajectory.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
00842       start = end
00843       end += 4
00844       (length,) = _struct_I.unpack(str[start:end])
00845       start = end
00846       end += length
00847       if python3:
00848         self.action_goal.goal.trajectory.header.frame_id = str[start:end].decode('utf-8')
00849       else:
00850         self.action_goal.goal.trajectory.header.frame_id = str[start:end]
00851       start = end
00852       end += 4
00853       (length,) = _struct_I.unpack(str[start:end])
00854       self.action_goal.goal.trajectory.joint_names = []
00855       for i in range(0, length):
00856         start = end
00857         end += 4
00858         (length,) = _struct_I.unpack(str[start:end])
00859         start = end
00860         end += length
00861         if python3:
00862           val1 = str[start:end].decode('utf-8')
00863         else:
00864           val1 = str[start:end]
00865         self.action_goal.goal.trajectory.joint_names.append(val1)
00866       start = end
00867       end += 4
00868       (length,) = _struct_I.unpack(str[start:end])
00869       self.action_goal.goal.trajectory.points = []
00870       for i in range(0, length):
00871         val1 = trajectory_msgs.msg.JointTrajectoryPoint()
00872         start = end
00873         end += 4
00874         (length,) = _struct_I.unpack(str[start:end])
00875         pattern = '<%sd'%length
00876         start = end
00877         end += struct.calcsize(pattern)
00878         val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00879         start = end
00880         end += 4
00881         (length,) = _struct_I.unpack(str[start:end])
00882         pattern = '<%sd'%length
00883         start = end
00884         end += struct.calcsize(pattern)
00885         val1.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00886         start = end
00887         end += 4
00888         (length,) = _struct_I.unpack(str[start:end])
00889         pattern = '<%sd'%length
00890         start = end
00891         end += struct.calcsize(pattern)
00892         val1.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00893         _v4 = val1.time_from_start
00894         _x = _v4
00895         start = end
00896         end += 8
00897         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00898         self.action_goal.goal.trajectory.points.append(val1)
00899       start = end
00900       end += 4
00901       (length,) = _struct_I.unpack(str[start:end])
00902       start = end
00903       end += length
00904       if python3:
00905         self.action_goal.goal.collision_support_surface_name = str[start:end].decode('utf-8')
00906       else:
00907         self.action_goal.goal.collision_support_surface_name = str[start:end]
00908       start = end
00909       end += 4
00910       (length,) = _struct_I.unpack(str[start:end])
00911       start = end
00912       end += length
00913       if python3:
00914         self.action_goal.goal.collision_object_name = str[start:end].decode('utf-8')
00915       else:
00916         self.action_goal.goal.collision_object_name = str[start:end]
00917       _x = self
00918       start = end
00919       end += 12
00920       (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00921       start = end
00922       end += 4
00923       (length,) = _struct_I.unpack(str[start:end])
00924       start = end
00925       end += length
00926       if python3:
00927         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00928       else:
00929         self.action_result.header.frame_id = str[start:end]
00930       _x = self
00931       start = end
00932       end += 8
00933       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00934       start = end
00935       end += 4
00936       (length,) = _struct_I.unpack(str[start:end])
00937       start = end
00938       end += length
00939       if python3:
00940         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00941       else:
00942         self.action_result.status.goal_id.id = str[start:end]
00943       start = end
00944       end += 1
00945       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00946       start = end
00947       end += 4
00948       (length,) = _struct_I.unpack(str[start:end])
00949       start = end
00950       end += length
00951       if python3:
00952         self.action_result.status.text = str[start:end].decode('utf-8')
00953       else:
00954         self.action_result.status.text = str[start:end]
00955       _x = self
00956       start = end
00957       end += 16
00958       (_x.action_result.result.manipulation_result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00959       start = end
00960       end += 4
00961       (length,) = _struct_I.unpack(str[start:end])
00962       start = end
00963       end += length
00964       if python3:
00965         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00966       else:
00967         self.action_feedback.header.frame_id = str[start:end]
00968       _x = self
00969       start = end
00970       end += 8
00971       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00972       start = end
00973       end += 4
00974       (length,) = _struct_I.unpack(str[start:end])
00975       start = end
00976       end += length
00977       if python3:
00978         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00979       else:
00980         self.action_feedback.status.goal_id.id = str[start:end]
00981       start = end
00982       end += 1
00983       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00984       start = end
00985       end += 4
00986       (length,) = _struct_I.unpack(str[start:end])
00987       start = end
00988       end += length
00989       if python3:
00990         self.action_feedback.status.text = str[start:end].decode('utf-8')
00991       else:
00992         self.action_feedback.status.text = str[start:end]
00993       start = end
00994       end += 4
00995       (self.action_feedback.feedback.manipulation_phase.phase,) = _struct_i.unpack(str[start:end])
00996       return self
00997     except struct.error as e:
00998       raise genpy.DeserializationError(e) #most likely buffer underfill
00999 
01000 _struct_I = genpy.struct_I
01001 _struct_7d3I = struct.Struct("<7d3I")
01002 _struct_B = struct.Struct("<B")
01003 _struct_i = struct.Struct("<i")
01004 _struct_i3I = struct.Struct("<i3I")
01005 _struct_2I = struct.Struct("<2I")
01006 _struct_3I = struct.Struct("<3I")
01007 _struct_2i = struct.Struct("<2i")


object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Thu Jan 2 2014 11:38:12