_FindADoorAction.py
Go to the documentation of this file.
00001 """autogenerated by genpy from iri_door_detector/FindADoorAction.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 arm_navigation_msgs.msg
00008 import actionlib_msgs.msg
00009 import geometry_msgs.msg
00010 import iri_door_detector.msg
00011 import sensor_msgs.msg
00012 import genpy
00013 import std_msgs.msg
00014 
00015 class FindADoorAction(genpy.Message):
00016   _md5sum = "bd77eeeb60cdef042b1e90eaea82f1f3"
00017   _type = "iri_door_detector/FindADoorAction"
00018   _has_header = False #flag to mark the presence of a Header object
00019   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00020 
00021 FindADoorActionGoal action_goal
00022 FindADoorActionResult action_result
00023 FindADoorActionFeedback action_feedback
00024 
00025 ================================================================================
00026 MSG: iri_door_detector/FindADoorActionGoal
00027 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00028 
00029 Header header
00030 actionlib_msgs/GoalID goal_id
00031 FindADoorGoal goal
00032 
00033 ================================================================================
00034 MSG: std_msgs/Header
00035 # Standard metadata for higher-level stamped data types.
00036 # This is generally used to communicate timestamped data 
00037 # in a particular coordinate frame.
00038 # 
00039 # sequence ID: consecutively increasing ID 
00040 uint32 seq
00041 #Two-integer timestamp that is expressed as:
00042 # * stamp.secs: seconds (stamp_secs) since epoch
00043 # * stamp.nsecs: nanoseconds since stamp_secs
00044 # time-handling sugar is provided by the client library
00045 time stamp
00046 #Frame this data is associated with
00047 # 0: no frame
00048 # 1: global frame
00049 string frame_id
00050 
00051 ================================================================================
00052 MSG: actionlib_msgs/GoalID
00053 # The stamp should store the time at which this goal was requested.
00054 # It is used by an action server when it tries to preempt all
00055 # goals that were requested before a certain time
00056 time stamp
00057 
00058 # The id provides a way to associate feedback and
00059 # result message with specific goal requests. The id
00060 # specified must be unique.
00061 string id
00062 
00063 
00064 ================================================================================
00065 MSG: iri_door_detector/FindADoorGoal
00066 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00067 # Define the goal
00068 int8 start
00069 
00070 ================================================================================
00071 MSG: iri_door_detector/FindADoorActionResult
00072 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00073 
00074 Header header
00075 actionlib_msgs/GoalStatus status
00076 FindADoorResult result
00077 
00078 ================================================================================
00079 MSG: actionlib_msgs/GoalStatus
00080 GoalID goal_id
00081 uint8 status
00082 uint8 PENDING         = 0   # The goal has yet to be processed by the action server
00083 uint8 ACTIVE          = 1   # The goal is currently being processed by the action server
00084 uint8 PREEMPTED       = 2   # The goal received a cancel request after it started executing
00085                             #   and has since completed its execution (Terminal State)
00086 uint8 SUCCEEDED       = 3   # The goal was achieved successfully by the action server (Terminal State)
00087 uint8 ABORTED         = 4   # The goal was aborted during execution by the action server due
00088                             #    to some failure (Terminal State)
00089 uint8 REJECTED        = 5   # The goal was rejected by the action server without being processed,
00090                             #    because the goal was unattainable or invalid (Terminal State)
00091 uint8 PREEMPTING      = 6   # The goal received a cancel request after it started executing
00092                             #    and has not yet completed execution
00093 uint8 RECALLING       = 7   # The goal received a cancel request before it started executing,
00094                             #    but the action server has not yet confirmed that the goal is canceled
00095 uint8 RECALLED        = 8   # The goal received a cancel request before it started executing
00096                             #    and was successfully cancelled (Terminal State)
00097 uint8 LOST            = 9   # An action client can determine that a goal is LOST. This should not be
00098                             #    sent over the wire by an action server
00099 
00100 #Allow for the user to associate a string with GoalStatus for debugging
00101 string text
00102 
00103 
00104 ================================================================================
00105 MSG: iri_door_detector/FindADoorResult
00106 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00107 # Define the result
00108 geometry_msgs/PoseStamped base_poses
00109 arm_navigation_msgs/MotionPlanRequest arm_poses
00110 string planner_service_name
00111 string state
00112 
00113 ================================================================================
00114 MSG: geometry_msgs/PoseStamped
00115 # A Pose with reference coordinate frame and timestamp
00116 Header header
00117 Pose pose
00118 
00119 ================================================================================
00120 MSG: geometry_msgs/Pose
00121 # A representation of pose in free space, composed of postion and orientation. 
00122 Point position
00123 Quaternion orientation
00124 
00125 ================================================================================
00126 MSG: geometry_msgs/Point
00127 # This contains the position of a point in free space
00128 float64 x
00129 float64 y
00130 float64 z
00131 
00132 ================================================================================
00133 MSG: geometry_msgs/Quaternion
00134 # This represents an orientation in free space in quaternion form.
00135 
00136 float64 x
00137 float64 y
00138 float64 z
00139 float64 w
00140 
00141 ================================================================================
00142 MSG: arm_navigation_msgs/MotionPlanRequest
00143 # This service contains the definition for a request to the motion
00144 # planner and the output it provides
00145 
00146 # Parameters for the workspace that the planner should work inside
00147 arm_navigation_msgs/WorkspaceParameters workspace_parameters
00148 
00149 # Starting state updates. If certain joints should be considered
00150 # at positions other than the current ones, these positions should
00151 # be set here
00152 arm_navigation_msgs/RobotState start_state
00153 
00154 # The goal state for the model to plan for. The goal is achieved
00155 # if all constraints are satisfied
00156 arm_navigation_msgs/Constraints goal_constraints
00157 
00158 # No state at any point along the path in the produced motion plan will violate these constraints
00159 arm_navigation_msgs/Constraints path_constraints
00160 
00161 # The name of the motion planner to use. If no name is specified,
00162 # a default motion planner will be used
00163 string planner_id
00164 
00165 # The name of the group of joints on which this planner is operating
00166 string group_name
00167 
00168 # The number of times this plan is to be computed. Shortest solution
00169 # will be reported.
00170 int32 num_planning_attempts
00171 
00172 # The maximum amount of time the motion planner is allowed to plan for
00173 duration allowed_planning_time
00174 
00175 # An expected path duration (in seconds) along with an expected discretization of the path allows the planner to determine the discretization of the trajectory that it returns
00176 duration expected_path_duration
00177 duration expected_path_dt
00178 
00179 ================================================================================
00180 MSG: arm_navigation_msgs/WorkspaceParameters
00181 # This message contains a set of parameters useful in
00182 # setting up the workspace for planning
00183 arm_navigation_msgs/Shape  workspace_region_shape
00184 geometry_msgs/PoseStamped    workspace_region_pose
00185 
00186 
00187 ================================================================================
00188 MSG: arm_navigation_msgs/Shape
00189 byte SPHERE=0
00190 byte BOX=1
00191 byte CYLINDER=2
00192 byte MESH=3
00193 
00194 byte type
00195 
00196 
00197 #### define sphere, box, cylinder ####
00198 # the origin of each shape is considered at the shape's center
00199 
00200 # for sphere
00201 # radius := dimensions[0]
00202 
00203 # for cylinder
00204 # radius := dimensions[0]
00205 # length := dimensions[1]
00206 # the length is along the Z axis
00207 
00208 # for box
00209 # size_x := dimensions[0]
00210 # size_y := dimensions[1]
00211 # size_z := dimensions[2]
00212 float64[] dimensions
00213 
00214 
00215 #### define mesh ####
00216 
00217 # list of triangles; triangle k is defined by tre vertices located
00218 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00219 int32[] triangles
00220 geometry_msgs/Point[] vertices
00221 
00222 ================================================================================
00223 MSG: arm_navigation_msgs/RobotState
00224 # This message contains information about the robot state, i.e. the positions of its joints and links
00225 sensor_msgs/JointState joint_state
00226 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
00227 
00228 ================================================================================
00229 MSG: sensor_msgs/JointState
00230 # This is a message that holds data to describe the state of a set of torque controlled joints. 
00231 #
00232 # The state of each joint (revolute or prismatic) is defined by:
00233 #  * the position of the joint (rad or m),
00234 #  * the velocity of the joint (rad/s or m/s) and 
00235 #  * the effort that is applied in the joint (Nm or N).
00236 #
00237 # Each joint is uniquely identified by its name
00238 # The header specifies the time at which the joint states were recorded. All the joint states
00239 # in one message have to be recorded at the same time.
00240 #
00241 # This message consists of a multiple arrays, one for each part of the joint state. 
00242 # The goal is to make each of the fields optional. When e.g. your joints have no
00243 # effort associated with them, you can leave the effort array empty. 
00244 #
00245 # All arrays in this message should have the same size, or be empty.
00246 # This is the only way to uniquely associate the joint name with the correct
00247 # states.
00248 
00249 
00250 Header header
00251 
00252 string[] name
00253 float64[] position
00254 float64[] velocity
00255 float64[] effort
00256 
00257 ================================================================================
00258 MSG: arm_navigation_msgs/MultiDOFJointState
00259 #A representation of a multi-dof joint state
00260 time stamp
00261 string[] joint_names
00262 string[] frame_ids
00263 string[] child_frame_ids
00264 geometry_msgs/Pose[] poses
00265 
00266 ================================================================================
00267 MSG: arm_navigation_msgs/Constraints
00268 # This message contains a list of motion planning constraints.
00269 
00270 arm_navigation_msgs/JointConstraint[] joint_constraints
00271 arm_navigation_msgs/PositionConstraint[] position_constraints
00272 arm_navigation_msgs/OrientationConstraint[] orientation_constraints
00273 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints
00274 
00275 ================================================================================
00276 MSG: arm_navigation_msgs/JointConstraint
00277 # Constrain the position of a joint to be within a certain bound
00278 string joint_name
00279 
00280 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]
00281 float64 position
00282 float64 tolerance_above
00283 float64 tolerance_below
00284 
00285 # A weighting factor for this constraint
00286 float64 weight
00287 ================================================================================
00288 MSG: arm_navigation_msgs/PositionConstraint
00289 # This message contains the definition of a position constraint.
00290 Header header
00291 
00292 # The robot link this constraint refers to
00293 string link_name
00294 
00295 # The offset (in the link frame) for the target point on the link we are planning for
00296 geometry_msgs/Point target_point_offset
00297 
00298 # The nominal/target position for the point we are planning for
00299 geometry_msgs/Point position
00300 
00301 # The shape of the bounded region that constrains the position of the end-effector
00302 # This region is always centered at the position defined above
00303 arm_navigation_msgs/Shape constraint_region_shape
00304 
00305 # The orientation of the bounded region that constrains the position of the end-effector. 
00306 # This allows the specification of non-axis aligned constraints
00307 geometry_msgs/Quaternion constraint_region_orientation
00308 
00309 # Constraint weighting factor - a weight for this constraint
00310 float64 weight
00311 
00312 ================================================================================
00313 MSG: arm_navigation_msgs/OrientationConstraint
00314 # This message contains the definition of an orientation constraint.
00315 Header header
00316 
00317 # The robot link this constraint refers to
00318 string link_name
00319 
00320 # The type of the constraint
00321 int32 type
00322 int32 LINK_FRAME=0
00323 int32 HEADER_FRAME=1
00324 
00325 # The desired orientation of the robot link specified as a quaternion
00326 geometry_msgs/Quaternion orientation
00327 
00328 # optional RPY error tolerances specified if 
00329 float64 absolute_roll_tolerance
00330 float64 absolute_pitch_tolerance
00331 float64 absolute_yaw_tolerance
00332 
00333 # Constraint weighting factor - a weight for this constraint
00334 float64 weight
00335 
00336 ================================================================================
00337 MSG: arm_navigation_msgs/VisibilityConstraint
00338 # This message contains the definition of a visibility constraint.
00339 Header header
00340 
00341 # The point stamped target that needs to be kept within view of the sensor
00342 geometry_msgs/PointStamped target
00343 
00344 # The local pose of the frame in which visibility is to be maintained
00345 # The frame id should represent the robot link to which the sensor is attached
00346 # The visual axis of the sensor is assumed to be along the X axis of this frame
00347 geometry_msgs/PoseStamped sensor_pose
00348 
00349 # The deviation (in radians) that will be tolerated
00350 # Constraint error will be measured as the solid angle between the 
00351 # X axis of the frame defined above and the vector between the origin 
00352 # of the frame defined above and the target location
00353 float64 absolute_tolerance
00354 
00355 
00356 ================================================================================
00357 MSG: geometry_msgs/PointStamped
00358 # This represents a Point with reference coordinate frame and timestamp
00359 Header header
00360 Point point
00361 
00362 ================================================================================
00363 MSG: iri_door_detector/FindADoorActionFeedback
00364 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00365 
00366 Header header
00367 actionlib_msgs/GoalStatus status
00368 FindADoorFeedback feedback
00369 
00370 ================================================================================
00371 MSG: iri_door_detector/FindADoorFeedback
00372 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00373 # Define a feedback message
00374 int8 searching
00375 
00376 
00377 """
00378   __slots__ = ['action_goal','action_result','action_feedback']
00379   _slot_types = ['iri_door_detector/FindADoorActionGoal','iri_door_detector/FindADoorActionResult','iri_door_detector/FindADoorActionFeedback']
00380 
00381   def __init__(self, *args, **kwds):
00382     """
00383     Constructor. Any message fields that are implicitly/explicitly
00384     set to None will be assigned a default value. The recommend
00385     use is keyword arguments as this is more robust to future message
00386     changes.  You cannot mix in-order arguments and keyword arguments.
00387 
00388     The available fields are:
00389        action_goal,action_result,action_feedback
00390 
00391     :param args: complete set of field values, in .msg order
00392     :param kwds: use keyword arguments corresponding to message field names
00393     to set specific fields.
00394     """
00395     if args or kwds:
00396       super(FindADoorAction, self).__init__(*args, **kwds)
00397       #message fields cannot be None, assign default values for those that are
00398       if self.action_goal is None:
00399         self.action_goal = iri_door_detector.msg.FindADoorActionGoal()
00400       if self.action_result is None:
00401         self.action_result = iri_door_detector.msg.FindADoorActionResult()
00402       if self.action_feedback is None:
00403         self.action_feedback = iri_door_detector.msg.FindADoorActionFeedback()
00404     else:
00405       self.action_goal = iri_door_detector.msg.FindADoorActionGoal()
00406       self.action_result = iri_door_detector.msg.FindADoorActionResult()
00407       self.action_feedback = iri_door_detector.msg.FindADoorActionFeedback()
00408 
00409   def _get_types(self):
00410     """
00411     internal API method
00412     """
00413     return self._slot_types
00414 
00415   def serialize(self, buff):
00416     """
00417     serialize message into buffer
00418     :param buff: buffer, ``StringIO``
00419     """
00420     try:
00421       _x = self
00422       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00423       _x = self.action_goal.header.frame_id
00424       length = len(_x)
00425       if python3 or type(_x) == unicode:
00426         _x = _x.encode('utf-8')
00427         length = len(_x)
00428       buff.write(struct.pack('<I%ss'%length, length, _x))
00429       _x = self
00430       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00431       _x = self.action_goal.goal_id.id
00432       length = len(_x)
00433       if python3 or type(_x) == unicode:
00434         _x = _x.encode('utf-8')
00435         length = len(_x)
00436       buff.write(struct.pack('<I%ss'%length, length, _x))
00437       _x = self
00438       buff.write(_struct_b3I.pack(_x.action_goal.goal.start, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00439       _x = self.action_result.header.frame_id
00440       length = len(_x)
00441       if python3 or type(_x) == unicode:
00442         _x = _x.encode('utf-8')
00443         length = len(_x)
00444       buff.write(struct.pack('<I%ss'%length, length, _x))
00445       _x = self
00446       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00447       _x = self.action_result.status.goal_id.id
00448       length = len(_x)
00449       if python3 or type(_x) == unicode:
00450         _x = _x.encode('utf-8')
00451         length = len(_x)
00452       buff.write(struct.pack('<I%ss'%length, length, _x))
00453       buff.write(_struct_B.pack(self.action_result.status.status))
00454       _x = self.action_result.status.text
00455       length = len(_x)
00456       if python3 or type(_x) == unicode:
00457         _x = _x.encode('utf-8')
00458         length = len(_x)
00459       buff.write(struct.pack('<I%ss'%length, length, _x))
00460       _x = self
00461       buff.write(_struct_3I.pack(_x.action_result.result.base_poses.header.seq, _x.action_result.result.base_poses.header.stamp.secs, _x.action_result.result.base_poses.header.stamp.nsecs))
00462       _x = self.action_result.result.base_poses.header.frame_id
00463       length = len(_x)
00464       if python3 or type(_x) == unicode:
00465         _x = _x.encode('utf-8')
00466         length = len(_x)
00467       buff.write(struct.pack('<I%ss'%length, length, _x))
00468       _x = self
00469       buff.write(_struct_7db.pack(_x.action_result.result.base_poses.pose.position.x, _x.action_result.result.base_poses.pose.position.y, _x.action_result.result.base_poses.pose.position.z, _x.action_result.result.base_poses.pose.orientation.x, _x.action_result.result.base_poses.pose.orientation.y, _x.action_result.result.base_poses.pose.orientation.z, _x.action_result.result.base_poses.pose.orientation.w, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.type))
00470       length = len(self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.dimensions)
00471       buff.write(_struct_I.pack(length))
00472       pattern = '<%sd'%length
00473       buff.write(struct.pack(pattern, *self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.dimensions))
00474       length = len(self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.triangles)
00475       buff.write(_struct_I.pack(length))
00476       pattern = '<%si'%length
00477       buff.write(struct.pack(pattern, *self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.triangles))
00478       length = len(self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.vertices)
00479       buff.write(_struct_I.pack(length))
00480       for val1 in self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.vertices:
00481         _x = val1
00482         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00483       _x = self
00484       buff.write(_struct_3I.pack(_x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.seq, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.stamp.nsecs))
00485       _x = self.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.frame_id
00486       length = len(_x)
00487       if python3 or type(_x) == unicode:
00488         _x = _x.encode('utf-8')
00489         length = len(_x)
00490       buff.write(struct.pack('<I%ss'%length, length, _x))
00491       _x = self
00492       buff.write(_struct_7d3I.pack(_x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.x, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.y, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.z, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.action_result.result.arm_poses.start_state.joint_state.header.seq, _x.action_result.result.arm_poses.start_state.joint_state.header.stamp.secs, _x.action_result.result.arm_poses.start_state.joint_state.header.stamp.nsecs))
00493       _x = self.action_result.result.arm_poses.start_state.joint_state.header.frame_id
00494       length = len(_x)
00495       if python3 or type(_x) == unicode:
00496         _x = _x.encode('utf-8')
00497         length = len(_x)
00498       buff.write(struct.pack('<I%ss'%length, length, _x))
00499       length = len(self.action_result.result.arm_poses.start_state.joint_state.name)
00500       buff.write(_struct_I.pack(length))
00501       for val1 in self.action_result.result.arm_poses.start_state.joint_state.name:
00502         length = len(val1)
00503         if python3 or type(val1) == unicode:
00504           val1 = val1.encode('utf-8')
00505           length = len(val1)
00506         buff.write(struct.pack('<I%ss'%length, length, val1))
00507       length = len(self.action_result.result.arm_poses.start_state.joint_state.position)
00508       buff.write(_struct_I.pack(length))
00509       pattern = '<%sd'%length
00510       buff.write(struct.pack(pattern, *self.action_result.result.arm_poses.start_state.joint_state.position))
00511       length = len(self.action_result.result.arm_poses.start_state.joint_state.velocity)
00512       buff.write(_struct_I.pack(length))
00513       pattern = '<%sd'%length
00514       buff.write(struct.pack(pattern, *self.action_result.result.arm_poses.start_state.joint_state.velocity))
00515       length = len(self.action_result.result.arm_poses.start_state.joint_state.effort)
00516       buff.write(_struct_I.pack(length))
00517       pattern = '<%sd'%length
00518       buff.write(struct.pack(pattern, *self.action_result.result.arm_poses.start_state.joint_state.effort))
00519       _x = self
00520       buff.write(_struct_2I.pack(_x.action_result.result.arm_poses.start_state.multi_dof_joint_state.stamp.secs, _x.action_result.result.arm_poses.start_state.multi_dof_joint_state.stamp.nsecs))
00521       length = len(self.action_result.result.arm_poses.start_state.multi_dof_joint_state.joint_names)
00522       buff.write(_struct_I.pack(length))
00523       for val1 in self.action_result.result.arm_poses.start_state.multi_dof_joint_state.joint_names:
00524         length = len(val1)
00525         if python3 or type(val1) == unicode:
00526           val1 = val1.encode('utf-8')
00527           length = len(val1)
00528         buff.write(struct.pack('<I%ss'%length, length, val1))
00529       length = len(self.action_result.result.arm_poses.start_state.multi_dof_joint_state.frame_ids)
00530       buff.write(_struct_I.pack(length))
00531       for val1 in self.action_result.result.arm_poses.start_state.multi_dof_joint_state.frame_ids:
00532         length = len(val1)
00533         if python3 or type(val1) == unicode:
00534           val1 = val1.encode('utf-8')
00535           length = len(val1)
00536         buff.write(struct.pack('<I%ss'%length, length, val1))
00537       length = len(self.action_result.result.arm_poses.start_state.multi_dof_joint_state.child_frame_ids)
00538       buff.write(_struct_I.pack(length))
00539       for val1 in self.action_result.result.arm_poses.start_state.multi_dof_joint_state.child_frame_ids:
00540         length = len(val1)
00541         if python3 or type(val1) == unicode:
00542           val1 = val1.encode('utf-8')
00543           length = len(val1)
00544         buff.write(struct.pack('<I%ss'%length, length, val1))
00545       length = len(self.action_result.result.arm_poses.start_state.multi_dof_joint_state.poses)
00546       buff.write(_struct_I.pack(length))
00547       for val1 in self.action_result.result.arm_poses.start_state.multi_dof_joint_state.poses:
00548         _v1 = val1.position
00549         _x = _v1
00550         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00551         _v2 = val1.orientation
00552         _x = _v2
00553         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00554       length = len(self.action_result.result.arm_poses.goal_constraints.joint_constraints)
00555       buff.write(_struct_I.pack(length))
00556       for val1 in self.action_result.result.arm_poses.goal_constraints.joint_constraints:
00557         _x = val1.joint_name
00558         length = len(_x)
00559         if python3 or type(_x) == unicode:
00560           _x = _x.encode('utf-8')
00561           length = len(_x)
00562         buff.write(struct.pack('<I%ss'%length, length, _x))
00563         _x = val1
00564         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00565       length = len(self.action_result.result.arm_poses.goal_constraints.position_constraints)
00566       buff.write(_struct_I.pack(length))
00567       for val1 in self.action_result.result.arm_poses.goal_constraints.position_constraints:
00568         _v3 = val1.header
00569         buff.write(_struct_I.pack(_v3.seq))
00570         _v4 = _v3.stamp
00571         _x = _v4
00572         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00573         _x = _v3.frame_id
00574         length = len(_x)
00575         if python3 or type(_x) == unicode:
00576           _x = _x.encode('utf-8')
00577           length = len(_x)
00578         buff.write(struct.pack('<I%ss'%length, length, _x))
00579         _x = val1.link_name
00580         length = len(_x)
00581         if python3 or type(_x) == unicode:
00582           _x = _x.encode('utf-8')
00583           length = len(_x)
00584         buff.write(struct.pack('<I%ss'%length, length, _x))
00585         _v5 = val1.target_point_offset
00586         _x = _v5
00587         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00588         _v6 = val1.position
00589         _x = _v6
00590         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00591         _v7 = val1.constraint_region_shape
00592         buff.write(_struct_b.pack(_v7.type))
00593         length = len(_v7.dimensions)
00594         buff.write(_struct_I.pack(length))
00595         pattern = '<%sd'%length
00596         buff.write(struct.pack(pattern, *_v7.dimensions))
00597         length = len(_v7.triangles)
00598         buff.write(_struct_I.pack(length))
00599         pattern = '<%si'%length
00600         buff.write(struct.pack(pattern, *_v7.triangles))
00601         length = len(_v7.vertices)
00602         buff.write(_struct_I.pack(length))
00603         for val3 in _v7.vertices:
00604           _x = val3
00605           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00606         _v8 = val1.constraint_region_orientation
00607         _x = _v8
00608         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00609         buff.write(_struct_d.pack(val1.weight))
00610       length = len(self.action_result.result.arm_poses.goal_constraints.orientation_constraints)
00611       buff.write(_struct_I.pack(length))
00612       for val1 in self.action_result.result.arm_poses.goal_constraints.orientation_constraints:
00613         _v9 = val1.header
00614         buff.write(_struct_I.pack(_v9.seq))
00615         _v10 = _v9.stamp
00616         _x = _v10
00617         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00618         _x = _v9.frame_id
00619         length = len(_x)
00620         if python3 or type(_x) == unicode:
00621           _x = _x.encode('utf-8')
00622           length = len(_x)
00623         buff.write(struct.pack('<I%ss'%length, length, _x))
00624         _x = val1.link_name
00625         length = len(_x)
00626         if python3 or type(_x) == unicode:
00627           _x = _x.encode('utf-8')
00628           length = len(_x)
00629         buff.write(struct.pack('<I%ss'%length, length, _x))
00630         buff.write(_struct_i.pack(val1.type))
00631         _v11 = val1.orientation
00632         _x = _v11
00633         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00634         _x = val1
00635         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00636       length = len(self.action_result.result.arm_poses.goal_constraints.visibility_constraints)
00637       buff.write(_struct_I.pack(length))
00638       for val1 in self.action_result.result.arm_poses.goal_constraints.visibility_constraints:
00639         _v12 = val1.header
00640         buff.write(_struct_I.pack(_v12.seq))
00641         _v13 = _v12.stamp
00642         _x = _v13
00643         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00644         _x = _v12.frame_id
00645         length = len(_x)
00646         if python3 or type(_x) == unicode:
00647           _x = _x.encode('utf-8')
00648           length = len(_x)
00649         buff.write(struct.pack('<I%ss'%length, length, _x))
00650         _v14 = val1.target
00651         _v15 = _v14.header
00652         buff.write(_struct_I.pack(_v15.seq))
00653         _v16 = _v15.stamp
00654         _x = _v16
00655         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00656         _x = _v15.frame_id
00657         length = len(_x)
00658         if python3 or type(_x) == unicode:
00659           _x = _x.encode('utf-8')
00660           length = len(_x)
00661         buff.write(struct.pack('<I%ss'%length, length, _x))
00662         _v17 = _v14.point
00663         _x = _v17
00664         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00665         _v18 = val1.sensor_pose
00666         _v19 = _v18.header
00667         buff.write(_struct_I.pack(_v19.seq))
00668         _v20 = _v19.stamp
00669         _x = _v20
00670         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00671         _x = _v19.frame_id
00672         length = len(_x)
00673         if python3 or type(_x) == unicode:
00674           _x = _x.encode('utf-8')
00675           length = len(_x)
00676         buff.write(struct.pack('<I%ss'%length, length, _x))
00677         _v21 = _v18.pose
00678         _v22 = _v21.position
00679         _x = _v22
00680         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00681         _v23 = _v21.orientation
00682         _x = _v23
00683         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00684         buff.write(_struct_d.pack(val1.absolute_tolerance))
00685       length = len(self.action_result.result.arm_poses.path_constraints.joint_constraints)
00686       buff.write(_struct_I.pack(length))
00687       for val1 in self.action_result.result.arm_poses.path_constraints.joint_constraints:
00688         _x = val1.joint_name
00689         length = len(_x)
00690         if python3 or type(_x) == unicode:
00691           _x = _x.encode('utf-8')
00692           length = len(_x)
00693         buff.write(struct.pack('<I%ss'%length, length, _x))
00694         _x = val1
00695         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
00696       length = len(self.action_result.result.arm_poses.path_constraints.position_constraints)
00697       buff.write(_struct_I.pack(length))
00698       for val1 in self.action_result.result.arm_poses.path_constraints.position_constraints:
00699         _v24 = val1.header
00700         buff.write(_struct_I.pack(_v24.seq))
00701         _v25 = _v24.stamp
00702         _x = _v25
00703         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00704         _x = _v24.frame_id
00705         length = len(_x)
00706         if python3 or type(_x) == unicode:
00707           _x = _x.encode('utf-8')
00708           length = len(_x)
00709         buff.write(struct.pack('<I%ss'%length, length, _x))
00710         _x = val1.link_name
00711         length = len(_x)
00712         if python3 or type(_x) == unicode:
00713           _x = _x.encode('utf-8')
00714           length = len(_x)
00715         buff.write(struct.pack('<I%ss'%length, length, _x))
00716         _v26 = val1.target_point_offset
00717         _x = _v26
00718         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00719         _v27 = val1.position
00720         _x = _v27
00721         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00722         _v28 = val1.constraint_region_shape
00723         buff.write(_struct_b.pack(_v28.type))
00724         length = len(_v28.dimensions)
00725         buff.write(_struct_I.pack(length))
00726         pattern = '<%sd'%length
00727         buff.write(struct.pack(pattern, *_v28.dimensions))
00728         length = len(_v28.triangles)
00729         buff.write(_struct_I.pack(length))
00730         pattern = '<%si'%length
00731         buff.write(struct.pack(pattern, *_v28.triangles))
00732         length = len(_v28.vertices)
00733         buff.write(_struct_I.pack(length))
00734         for val3 in _v28.vertices:
00735           _x = val3
00736           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00737         _v29 = val1.constraint_region_orientation
00738         _x = _v29
00739         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00740         buff.write(_struct_d.pack(val1.weight))
00741       length = len(self.action_result.result.arm_poses.path_constraints.orientation_constraints)
00742       buff.write(_struct_I.pack(length))
00743       for val1 in self.action_result.result.arm_poses.path_constraints.orientation_constraints:
00744         _v30 = val1.header
00745         buff.write(_struct_I.pack(_v30.seq))
00746         _v31 = _v30.stamp
00747         _x = _v31
00748         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00749         _x = _v30.frame_id
00750         length = len(_x)
00751         if python3 or type(_x) == unicode:
00752           _x = _x.encode('utf-8')
00753           length = len(_x)
00754         buff.write(struct.pack('<I%ss'%length, length, _x))
00755         _x = val1.link_name
00756         length = len(_x)
00757         if python3 or type(_x) == unicode:
00758           _x = _x.encode('utf-8')
00759           length = len(_x)
00760         buff.write(struct.pack('<I%ss'%length, length, _x))
00761         buff.write(_struct_i.pack(val1.type))
00762         _v32 = val1.orientation
00763         _x = _v32
00764         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00765         _x = val1
00766         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00767       length = len(self.action_result.result.arm_poses.path_constraints.visibility_constraints)
00768       buff.write(_struct_I.pack(length))
00769       for val1 in self.action_result.result.arm_poses.path_constraints.visibility_constraints:
00770         _v33 = val1.header
00771         buff.write(_struct_I.pack(_v33.seq))
00772         _v34 = _v33.stamp
00773         _x = _v34
00774         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00775         _x = _v33.frame_id
00776         length = len(_x)
00777         if python3 or type(_x) == unicode:
00778           _x = _x.encode('utf-8')
00779           length = len(_x)
00780         buff.write(struct.pack('<I%ss'%length, length, _x))
00781         _v35 = val1.target
00782         _v36 = _v35.header
00783         buff.write(_struct_I.pack(_v36.seq))
00784         _v37 = _v36.stamp
00785         _x = _v37
00786         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00787         _x = _v36.frame_id
00788         length = len(_x)
00789         if python3 or type(_x) == unicode:
00790           _x = _x.encode('utf-8')
00791           length = len(_x)
00792         buff.write(struct.pack('<I%ss'%length, length, _x))
00793         _v38 = _v35.point
00794         _x = _v38
00795         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00796         _v39 = val1.sensor_pose
00797         _v40 = _v39.header
00798         buff.write(_struct_I.pack(_v40.seq))
00799         _v41 = _v40.stamp
00800         _x = _v41
00801         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00802         _x = _v40.frame_id
00803         length = len(_x)
00804         if python3 or type(_x) == unicode:
00805           _x = _x.encode('utf-8')
00806           length = len(_x)
00807         buff.write(struct.pack('<I%ss'%length, length, _x))
00808         _v42 = _v39.pose
00809         _v43 = _v42.position
00810         _x = _v43
00811         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00812         _v44 = _v42.orientation
00813         _x = _v44
00814         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00815         buff.write(_struct_d.pack(val1.absolute_tolerance))
00816       _x = self.action_result.result.arm_poses.planner_id
00817       length = len(_x)
00818       if python3 or type(_x) == unicode:
00819         _x = _x.encode('utf-8')
00820         length = len(_x)
00821       buff.write(struct.pack('<I%ss'%length, length, _x))
00822       _x = self.action_result.result.arm_poses.group_name
00823       length = len(_x)
00824       if python3 or type(_x) == unicode:
00825         _x = _x.encode('utf-8')
00826         length = len(_x)
00827       buff.write(struct.pack('<I%ss'%length, length, _x))
00828       _x = self
00829       buff.write(_struct_7i.pack(_x.action_result.result.arm_poses.num_planning_attempts, _x.action_result.result.arm_poses.allowed_planning_time.secs, _x.action_result.result.arm_poses.allowed_planning_time.nsecs, _x.action_result.result.arm_poses.expected_path_duration.secs, _x.action_result.result.arm_poses.expected_path_duration.nsecs, _x.action_result.result.arm_poses.expected_path_dt.secs, _x.action_result.result.arm_poses.expected_path_dt.nsecs))
00830       _x = self.action_result.result.planner_service_name
00831       length = len(_x)
00832       if python3 or type(_x) == unicode:
00833         _x = _x.encode('utf-8')
00834         length = len(_x)
00835       buff.write(struct.pack('<I%ss'%length, length, _x))
00836       _x = self.action_result.result.state
00837       length = len(_x)
00838       if python3 or type(_x) == unicode:
00839         _x = _x.encode('utf-8')
00840         length = len(_x)
00841       buff.write(struct.pack('<I%ss'%length, length, _x))
00842       _x = self
00843       buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00844       _x = self.action_feedback.header.frame_id
00845       length = len(_x)
00846       if python3 or type(_x) == unicode:
00847         _x = _x.encode('utf-8')
00848         length = len(_x)
00849       buff.write(struct.pack('<I%ss'%length, length, _x))
00850       _x = self
00851       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00852       _x = self.action_feedback.status.goal_id.id
00853       length = len(_x)
00854       if python3 or type(_x) == unicode:
00855         _x = _x.encode('utf-8')
00856         length = len(_x)
00857       buff.write(struct.pack('<I%ss'%length, length, _x))
00858       buff.write(_struct_B.pack(self.action_feedback.status.status))
00859       _x = self.action_feedback.status.text
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       buff.write(_struct_b.pack(self.action_feedback.feedback.searching))
00866     except struct.error as se: self._check_types(se)
00867     except TypeError as te: self._check_types(te)
00868 
00869   def deserialize(self, str):
00870     """
00871     unpack serialized message in str into this message instance
00872     :param str: byte array of serialized message, ``str``
00873     """
00874     try:
00875       if self.action_goal is None:
00876         self.action_goal = iri_door_detector.msg.FindADoorActionGoal()
00877       if self.action_result is None:
00878         self.action_result = iri_door_detector.msg.FindADoorActionResult()
00879       if self.action_feedback is None:
00880         self.action_feedback = iri_door_detector.msg.FindADoorActionFeedback()
00881       end = 0
00882       _x = self
00883       start = end
00884       end += 12
00885       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00886       start = end
00887       end += 4
00888       (length,) = _struct_I.unpack(str[start:end])
00889       start = end
00890       end += length
00891       if python3:
00892         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00893       else:
00894         self.action_goal.header.frame_id = str[start:end]
00895       _x = self
00896       start = end
00897       end += 8
00898       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
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_id.id = str[start:end].decode('utf-8')
00906       else:
00907         self.action_goal.goal_id.id = str[start:end]
00908       _x = self
00909       start = end
00910       end += 13
00911       (_x.action_goal.goal.start, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_b3I.unpack(str[start:end])
00912       start = end
00913       end += 4
00914       (length,) = _struct_I.unpack(str[start:end])
00915       start = end
00916       end += length
00917       if python3:
00918         self.action_result.header.frame_id = str[start:end].decode('utf-8')
00919       else:
00920         self.action_result.header.frame_id = str[start:end]
00921       _x = self
00922       start = end
00923       end += 8
00924       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00925       start = end
00926       end += 4
00927       (length,) = _struct_I.unpack(str[start:end])
00928       start = end
00929       end += length
00930       if python3:
00931         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00932       else:
00933         self.action_result.status.goal_id.id = str[start:end]
00934       start = end
00935       end += 1
00936       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00937       start = end
00938       end += 4
00939       (length,) = _struct_I.unpack(str[start:end])
00940       start = end
00941       end += length
00942       if python3:
00943         self.action_result.status.text = str[start:end].decode('utf-8')
00944       else:
00945         self.action_result.status.text = str[start:end]
00946       _x = self
00947       start = end
00948       end += 12
00949       (_x.action_result.result.base_poses.header.seq, _x.action_result.result.base_poses.header.stamp.secs, _x.action_result.result.base_poses.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00950       start = end
00951       end += 4
00952       (length,) = _struct_I.unpack(str[start:end])
00953       start = end
00954       end += length
00955       if python3:
00956         self.action_result.result.base_poses.header.frame_id = str[start:end].decode('utf-8')
00957       else:
00958         self.action_result.result.base_poses.header.frame_id = str[start:end]
00959       _x = self
00960       start = end
00961       end += 57
00962       (_x.action_result.result.base_poses.pose.position.x, _x.action_result.result.base_poses.pose.position.y, _x.action_result.result.base_poses.pose.position.z, _x.action_result.result.base_poses.pose.orientation.x, _x.action_result.result.base_poses.pose.orientation.y, _x.action_result.result.base_poses.pose.orientation.z, _x.action_result.result.base_poses.pose.orientation.w, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.type,) = _struct_7db.unpack(str[start:end])
00963       start = end
00964       end += 4
00965       (length,) = _struct_I.unpack(str[start:end])
00966       pattern = '<%sd'%length
00967       start = end
00968       end += struct.calcsize(pattern)
00969       self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.dimensions = struct.unpack(pattern, str[start:end])
00970       start = end
00971       end += 4
00972       (length,) = _struct_I.unpack(str[start:end])
00973       pattern = '<%si'%length
00974       start = end
00975       end += struct.calcsize(pattern)
00976       self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.triangles = struct.unpack(pattern, str[start:end])
00977       start = end
00978       end += 4
00979       (length,) = _struct_I.unpack(str[start:end])
00980       self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.vertices = []
00981       for i in range(0, length):
00982         val1 = geometry_msgs.msg.Point()
00983         _x = val1
00984         start = end
00985         end += 24
00986         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00987         self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.vertices.append(val1)
00988       _x = self
00989       start = end
00990       end += 12
00991       (_x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.seq, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00992       start = end
00993       end += 4
00994       (length,) = _struct_I.unpack(str[start:end])
00995       start = end
00996       end += length
00997       if python3:
00998         self.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end].decode('utf-8')
00999       else:
01000         self.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end]
01001       _x = self
01002       start = end
01003       end += 68
01004       (_x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.x, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.y, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.z, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.action_result.result.arm_poses.start_state.joint_state.header.seq, _x.action_result.result.arm_poses.start_state.joint_state.header.stamp.secs, _x.action_result.result.arm_poses.start_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
01005       start = end
01006       end += 4
01007       (length,) = _struct_I.unpack(str[start:end])
01008       start = end
01009       end += length
01010       if python3:
01011         self.action_result.result.arm_poses.start_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
01012       else:
01013         self.action_result.result.arm_poses.start_state.joint_state.header.frame_id = str[start:end]
01014       start = end
01015       end += 4
01016       (length,) = _struct_I.unpack(str[start:end])
01017       self.action_result.result.arm_poses.start_state.joint_state.name = []
01018       for i in range(0, length):
01019         start = end
01020         end += 4
01021         (length,) = _struct_I.unpack(str[start:end])
01022         start = end
01023         end += length
01024         if python3:
01025           val1 = str[start:end].decode('utf-8')
01026         else:
01027           val1 = str[start:end]
01028         self.action_result.result.arm_poses.start_state.joint_state.name.append(val1)
01029       start = end
01030       end += 4
01031       (length,) = _struct_I.unpack(str[start:end])
01032       pattern = '<%sd'%length
01033       start = end
01034       end += struct.calcsize(pattern)
01035       self.action_result.result.arm_poses.start_state.joint_state.position = struct.unpack(pattern, str[start:end])
01036       start = end
01037       end += 4
01038       (length,) = _struct_I.unpack(str[start:end])
01039       pattern = '<%sd'%length
01040       start = end
01041       end += struct.calcsize(pattern)
01042       self.action_result.result.arm_poses.start_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
01043       start = end
01044       end += 4
01045       (length,) = _struct_I.unpack(str[start:end])
01046       pattern = '<%sd'%length
01047       start = end
01048       end += struct.calcsize(pattern)
01049       self.action_result.result.arm_poses.start_state.joint_state.effort = struct.unpack(pattern, str[start:end])
01050       _x = self
01051       start = end
01052       end += 8
01053       (_x.action_result.result.arm_poses.start_state.multi_dof_joint_state.stamp.secs, _x.action_result.result.arm_poses.start_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01054       start = end
01055       end += 4
01056       (length,) = _struct_I.unpack(str[start:end])
01057       self.action_result.result.arm_poses.start_state.multi_dof_joint_state.joint_names = []
01058       for i in range(0, length):
01059         start = end
01060         end += 4
01061         (length,) = _struct_I.unpack(str[start:end])
01062         start = end
01063         end += length
01064         if python3:
01065           val1 = str[start:end].decode('utf-8')
01066         else:
01067           val1 = str[start:end]
01068         self.action_result.result.arm_poses.start_state.multi_dof_joint_state.joint_names.append(val1)
01069       start = end
01070       end += 4
01071       (length,) = _struct_I.unpack(str[start:end])
01072       self.action_result.result.arm_poses.start_state.multi_dof_joint_state.frame_ids = []
01073       for i in range(0, length):
01074         start = end
01075         end += 4
01076         (length,) = _struct_I.unpack(str[start:end])
01077         start = end
01078         end += length
01079         if python3:
01080           val1 = str[start:end].decode('utf-8')
01081         else:
01082           val1 = str[start:end]
01083         self.action_result.result.arm_poses.start_state.multi_dof_joint_state.frame_ids.append(val1)
01084       start = end
01085       end += 4
01086       (length,) = _struct_I.unpack(str[start:end])
01087       self.action_result.result.arm_poses.start_state.multi_dof_joint_state.child_frame_ids = []
01088       for i in range(0, length):
01089         start = end
01090         end += 4
01091         (length,) = _struct_I.unpack(str[start:end])
01092         start = end
01093         end += length
01094         if python3:
01095           val1 = str[start:end].decode('utf-8')
01096         else:
01097           val1 = str[start:end]
01098         self.action_result.result.arm_poses.start_state.multi_dof_joint_state.child_frame_ids.append(val1)
01099       start = end
01100       end += 4
01101       (length,) = _struct_I.unpack(str[start:end])
01102       self.action_result.result.arm_poses.start_state.multi_dof_joint_state.poses = []
01103       for i in range(0, length):
01104         val1 = geometry_msgs.msg.Pose()
01105         _v45 = val1.position
01106         _x = _v45
01107         start = end
01108         end += 24
01109         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01110         _v46 = val1.orientation
01111         _x = _v46
01112         start = end
01113         end += 32
01114         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01115         self.action_result.result.arm_poses.start_state.multi_dof_joint_state.poses.append(val1)
01116       start = end
01117       end += 4
01118       (length,) = _struct_I.unpack(str[start:end])
01119       self.action_result.result.arm_poses.goal_constraints.joint_constraints = []
01120       for i in range(0, length):
01121         val1 = arm_navigation_msgs.msg.JointConstraint()
01122         start = end
01123         end += 4
01124         (length,) = _struct_I.unpack(str[start:end])
01125         start = end
01126         end += length
01127         if python3:
01128           val1.joint_name = str[start:end].decode('utf-8')
01129         else:
01130           val1.joint_name = str[start:end]
01131         _x = val1
01132         start = end
01133         end += 32
01134         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01135         self.action_result.result.arm_poses.goal_constraints.joint_constraints.append(val1)
01136       start = end
01137       end += 4
01138       (length,) = _struct_I.unpack(str[start:end])
01139       self.action_result.result.arm_poses.goal_constraints.position_constraints = []
01140       for i in range(0, length):
01141         val1 = arm_navigation_msgs.msg.PositionConstraint()
01142         _v47 = val1.header
01143         start = end
01144         end += 4
01145         (_v47.seq,) = _struct_I.unpack(str[start:end])
01146         _v48 = _v47.stamp
01147         _x = _v48
01148         start = end
01149         end += 8
01150         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01151         start = end
01152         end += 4
01153         (length,) = _struct_I.unpack(str[start:end])
01154         start = end
01155         end += length
01156         if python3:
01157           _v47.frame_id = str[start:end].decode('utf-8')
01158         else:
01159           _v47.frame_id = str[start:end]
01160         start = end
01161         end += 4
01162         (length,) = _struct_I.unpack(str[start:end])
01163         start = end
01164         end += length
01165         if python3:
01166           val1.link_name = str[start:end].decode('utf-8')
01167         else:
01168           val1.link_name = str[start:end]
01169         _v49 = val1.target_point_offset
01170         _x = _v49
01171         start = end
01172         end += 24
01173         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01174         _v50 = val1.position
01175         _x = _v50
01176         start = end
01177         end += 24
01178         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01179         _v51 = val1.constraint_region_shape
01180         start = end
01181         end += 1
01182         (_v51.type,) = _struct_b.unpack(str[start:end])
01183         start = end
01184         end += 4
01185         (length,) = _struct_I.unpack(str[start:end])
01186         pattern = '<%sd'%length
01187         start = end
01188         end += struct.calcsize(pattern)
01189         _v51.dimensions = struct.unpack(pattern, str[start:end])
01190         start = end
01191         end += 4
01192         (length,) = _struct_I.unpack(str[start:end])
01193         pattern = '<%si'%length
01194         start = end
01195         end += struct.calcsize(pattern)
01196         _v51.triangles = struct.unpack(pattern, str[start:end])
01197         start = end
01198         end += 4
01199         (length,) = _struct_I.unpack(str[start:end])
01200         _v51.vertices = []
01201         for i in range(0, length):
01202           val3 = geometry_msgs.msg.Point()
01203           _x = val3
01204           start = end
01205           end += 24
01206           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01207           _v51.vertices.append(val3)
01208         _v52 = val1.constraint_region_orientation
01209         _x = _v52
01210         start = end
01211         end += 32
01212         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01213         start = end
01214         end += 8
01215         (val1.weight,) = _struct_d.unpack(str[start:end])
01216         self.action_result.result.arm_poses.goal_constraints.position_constraints.append(val1)
01217       start = end
01218       end += 4
01219       (length,) = _struct_I.unpack(str[start:end])
01220       self.action_result.result.arm_poses.goal_constraints.orientation_constraints = []
01221       for i in range(0, length):
01222         val1 = arm_navigation_msgs.msg.OrientationConstraint()
01223         _v53 = val1.header
01224         start = end
01225         end += 4
01226         (_v53.seq,) = _struct_I.unpack(str[start:end])
01227         _v54 = _v53.stamp
01228         _x = _v54
01229         start = end
01230         end += 8
01231         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01232         start = end
01233         end += 4
01234         (length,) = _struct_I.unpack(str[start:end])
01235         start = end
01236         end += length
01237         if python3:
01238           _v53.frame_id = str[start:end].decode('utf-8')
01239         else:
01240           _v53.frame_id = 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           val1.link_name = str[start:end].decode('utf-8')
01248         else:
01249           val1.link_name = str[start:end]
01250         start = end
01251         end += 4
01252         (val1.type,) = _struct_i.unpack(str[start:end])
01253         _v55 = val1.orientation
01254         _x = _v55
01255         start = end
01256         end += 32
01257         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01258         _x = val1
01259         start = end
01260         end += 32
01261         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01262         self.action_result.result.arm_poses.goal_constraints.orientation_constraints.append(val1)
01263       start = end
01264       end += 4
01265       (length,) = _struct_I.unpack(str[start:end])
01266       self.action_result.result.arm_poses.goal_constraints.visibility_constraints = []
01267       for i in range(0, length):
01268         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
01269         _v56 = val1.header
01270         start = end
01271         end += 4
01272         (_v56.seq,) = _struct_I.unpack(str[start:end])
01273         _v57 = _v56.stamp
01274         _x = _v57
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           _v56.frame_id = str[start:end].decode('utf-8')
01285         else:
01286           _v56.frame_id = str[start:end]
01287         _v58 = val1.target
01288         _v59 = _v58.header
01289         start = end
01290         end += 4
01291         (_v59.seq,) = _struct_I.unpack(str[start:end])
01292         _v60 = _v59.stamp
01293         _x = _v60
01294         start = end
01295         end += 8
01296         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01297         start = end
01298         end += 4
01299         (length,) = _struct_I.unpack(str[start:end])
01300         start = end
01301         end += length
01302         if python3:
01303           _v59.frame_id = str[start:end].decode('utf-8')
01304         else:
01305           _v59.frame_id = str[start:end]
01306         _v61 = _v58.point
01307         _x = _v61
01308         start = end
01309         end += 24
01310         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01311         _v62 = val1.sensor_pose
01312         _v63 = _v62.header
01313         start = end
01314         end += 4
01315         (_v63.seq,) = _struct_I.unpack(str[start:end])
01316         _v64 = _v63.stamp
01317         _x = _v64
01318         start = end
01319         end += 8
01320         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01321         start = end
01322         end += 4
01323         (length,) = _struct_I.unpack(str[start:end])
01324         start = end
01325         end += length
01326         if python3:
01327           _v63.frame_id = str[start:end].decode('utf-8')
01328         else:
01329           _v63.frame_id = str[start:end]
01330         _v65 = _v62.pose
01331         _v66 = _v65.position
01332         _x = _v66
01333         start = end
01334         end += 24
01335         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01336         _v67 = _v65.orientation
01337         _x = _v67
01338         start = end
01339         end += 32
01340         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01341         start = end
01342         end += 8
01343         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01344         self.action_result.result.arm_poses.goal_constraints.visibility_constraints.append(val1)
01345       start = end
01346       end += 4
01347       (length,) = _struct_I.unpack(str[start:end])
01348       self.action_result.result.arm_poses.path_constraints.joint_constraints = []
01349       for i in range(0, length):
01350         val1 = arm_navigation_msgs.msg.JointConstraint()
01351         start = end
01352         end += 4
01353         (length,) = _struct_I.unpack(str[start:end])
01354         start = end
01355         end += length
01356         if python3:
01357           val1.joint_name = str[start:end].decode('utf-8')
01358         else:
01359           val1.joint_name = str[start:end]
01360         _x = val1
01361         start = end
01362         end += 32
01363         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
01364         self.action_result.result.arm_poses.path_constraints.joint_constraints.append(val1)
01365       start = end
01366       end += 4
01367       (length,) = _struct_I.unpack(str[start:end])
01368       self.action_result.result.arm_poses.path_constraints.position_constraints = []
01369       for i in range(0, length):
01370         val1 = arm_navigation_msgs.msg.PositionConstraint()
01371         _v68 = val1.header
01372         start = end
01373         end += 4
01374         (_v68.seq,) = _struct_I.unpack(str[start:end])
01375         _v69 = _v68.stamp
01376         _x = _v69
01377         start = end
01378         end += 8
01379         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01380         start = end
01381         end += 4
01382         (length,) = _struct_I.unpack(str[start:end])
01383         start = end
01384         end += length
01385         if python3:
01386           _v68.frame_id = str[start:end].decode('utf-8')
01387         else:
01388           _v68.frame_id = str[start:end]
01389         start = end
01390         end += 4
01391         (length,) = _struct_I.unpack(str[start:end])
01392         start = end
01393         end += length
01394         if python3:
01395           val1.link_name = str[start:end].decode('utf-8')
01396         else:
01397           val1.link_name = str[start:end]
01398         _v70 = val1.target_point_offset
01399         _x = _v70
01400         start = end
01401         end += 24
01402         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01403         _v71 = val1.position
01404         _x = _v71
01405         start = end
01406         end += 24
01407         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01408         _v72 = val1.constraint_region_shape
01409         start = end
01410         end += 1
01411         (_v72.type,) = _struct_b.unpack(str[start:end])
01412         start = end
01413         end += 4
01414         (length,) = _struct_I.unpack(str[start:end])
01415         pattern = '<%sd'%length
01416         start = end
01417         end += struct.calcsize(pattern)
01418         _v72.dimensions = struct.unpack(pattern, str[start:end])
01419         start = end
01420         end += 4
01421         (length,) = _struct_I.unpack(str[start:end])
01422         pattern = '<%si'%length
01423         start = end
01424         end += struct.calcsize(pattern)
01425         _v72.triangles = struct.unpack(pattern, str[start:end])
01426         start = end
01427         end += 4
01428         (length,) = _struct_I.unpack(str[start:end])
01429         _v72.vertices = []
01430         for i in range(0, length):
01431           val3 = geometry_msgs.msg.Point()
01432           _x = val3
01433           start = end
01434           end += 24
01435           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01436           _v72.vertices.append(val3)
01437         _v73 = val1.constraint_region_orientation
01438         _x = _v73
01439         start = end
01440         end += 32
01441         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01442         start = end
01443         end += 8
01444         (val1.weight,) = _struct_d.unpack(str[start:end])
01445         self.action_result.result.arm_poses.path_constraints.position_constraints.append(val1)
01446       start = end
01447       end += 4
01448       (length,) = _struct_I.unpack(str[start:end])
01449       self.action_result.result.arm_poses.path_constraints.orientation_constraints = []
01450       for i in range(0, length):
01451         val1 = arm_navigation_msgs.msg.OrientationConstraint()
01452         _v74 = val1.header
01453         start = end
01454         end += 4
01455         (_v74.seq,) = _struct_I.unpack(str[start:end])
01456         _v75 = _v74.stamp
01457         _x = _v75
01458         start = end
01459         end += 8
01460         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01461         start = end
01462         end += 4
01463         (length,) = _struct_I.unpack(str[start:end])
01464         start = end
01465         end += length
01466         if python3:
01467           _v74.frame_id = str[start:end].decode('utf-8')
01468         else:
01469           _v74.frame_id = str[start:end]
01470         start = end
01471         end += 4
01472         (length,) = _struct_I.unpack(str[start:end])
01473         start = end
01474         end += length
01475         if python3:
01476           val1.link_name = str[start:end].decode('utf-8')
01477         else:
01478           val1.link_name = str[start:end]
01479         start = end
01480         end += 4
01481         (val1.type,) = _struct_i.unpack(str[start:end])
01482         _v76 = val1.orientation
01483         _x = _v76
01484         start = end
01485         end += 32
01486         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01487         _x = val1
01488         start = end
01489         end += 32
01490         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
01491         self.action_result.result.arm_poses.path_constraints.orientation_constraints.append(val1)
01492       start = end
01493       end += 4
01494       (length,) = _struct_I.unpack(str[start:end])
01495       self.action_result.result.arm_poses.path_constraints.visibility_constraints = []
01496       for i in range(0, length):
01497         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
01498         _v77 = val1.header
01499         start = end
01500         end += 4
01501         (_v77.seq,) = _struct_I.unpack(str[start:end])
01502         _v78 = _v77.stamp
01503         _x = _v78
01504         start = end
01505         end += 8
01506         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01507         start = end
01508         end += 4
01509         (length,) = _struct_I.unpack(str[start:end])
01510         start = end
01511         end += length
01512         if python3:
01513           _v77.frame_id = str[start:end].decode('utf-8')
01514         else:
01515           _v77.frame_id = str[start:end]
01516         _v79 = val1.target
01517         _v80 = _v79.header
01518         start = end
01519         end += 4
01520         (_v80.seq,) = _struct_I.unpack(str[start:end])
01521         _v81 = _v80.stamp
01522         _x = _v81
01523         start = end
01524         end += 8
01525         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01526         start = end
01527         end += 4
01528         (length,) = _struct_I.unpack(str[start:end])
01529         start = end
01530         end += length
01531         if python3:
01532           _v80.frame_id = str[start:end].decode('utf-8')
01533         else:
01534           _v80.frame_id = str[start:end]
01535         _v82 = _v79.point
01536         _x = _v82
01537         start = end
01538         end += 24
01539         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01540         _v83 = val1.sensor_pose
01541         _v84 = _v83.header
01542         start = end
01543         end += 4
01544         (_v84.seq,) = _struct_I.unpack(str[start:end])
01545         _v85 = _v84.stamp
01546         _x = _v85
01547         start = end
01548         end += 8
01549         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01550         start = end
01551         end += 4
01552         (length,) = _struct_I.unpack(str[start:end])
01553         start = end
01554         end += length
01555         if python3:
01556           _v84.frame_id = str[start:end].decode('utf-8')
01557         else:
01558           _v84.frame_id = str[start:end]
01559         _v86 = _v83.pose
01560         _v87 = _v86.position
01561         _x = _v87
01562         start = end
01563         end += 24
01564         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01565         _v88 = _v86.orientation
01566         _x = _v88
01567         start = end
01568         end += 32
01569         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01570         start = end
01571         end += 8
01572         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
01573         self.action_result.result.arm_poses.path_constraints.visibility_constraints.append(val1)
01574       start = end
01575       end += 4
01576       (length,) = _struct_I.unpack(str[start:end])
01577       start = end
01578       end += length
01579       if python3:
01580         self.action_result.result.arm_poses.planner_id = str[start:end].decode('utf-8')
01581       else:
01582         self.action_result.result.arm_poses.planner_id = str[start:end]
01583       start = end
01584       end += 4
01585       (length,) = _struct_I.unpack(str[start:end])
01586       start = end
01587       end += length
01588       if python3:
01589         self.action_result.result.arm_poses.group_name = str[start:end].decode('utf-8')
01590       else:
01591         self.action_result.result.arm_poses.group_name = str[start:end]
01592       _x = self
01593       start = end
01594       end += 28
01595       (_x.action_result.result.arm_poses.num_planning_attempts, _x.action_result.result.arm_poses.allowed_planning_time.secs, _x.action_result.result.arm_poses.allowed_planning_time.nsecs, _x.action_result.result.arm_poses.expected_path_duration.secs, _x.action_result.result.arm_poses.expected_path_duration.nsecs, _x.action_result.result.arm_poses.expected_path_dt.secs, _x.action_result.result.arm_poses.expected_path_dt.nsecs,) = _struct_7i.unpack(str[start:end])
01596       start = end
01597       end += 4
01598       (length,) = _struct_I.unpack(str[start:end])
01599       start = end
01600       end += length
01601       if python3:
01602         self.action_result.result.planner_service_name = str[start:end].decode('utf-8')
01603       else:
01604         self.action_result.result.planner_service_name = str[start:end]
01605       start = end
01606       end += 4
01607       (length,) = _struct_I.unpack(str[start:end])
01608       start = end
01609       end += length
01610       if python3:
01611         self.action_result.result.state = str[start:end].decode('utf-8')
01612       else:
01613         self.action_result.result.state = str[start:end]
01614       _x = self
01615       start = end
01616       end += 12
01617       (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01618       start = end
01619       end += 4
01620       (length,) = _struct_I.unpack(str[start:end])
01621       start = end
01622       end += length
01623       if python3:
01624         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
01625       else:
01626         self.action_feedback.header.frame_id = str[start:end]
01627       _x = self
01628       start = end
01629       end += 8
01630       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
01631       start = end
01632       end += 4
01633       (length,) = _struct_I.unpack(str[start:end])
01634       start = end
01635       end += length
01636       if python3:
01637         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
01638       else:
01639         self.action_feedback.status.goal_id.id = str[start:end]
01640       start = end
01641       end += 1
01642       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
01643       start = end
01644       end += 4
01645       (length,) = _struct_I.unpack(str[start:end])
01646       start = end
01647       end += length
01648       if python3:
01649         self.action_feedback.status.text = str[start:end].decode('utf-8')
01650       else:
01651         self.action_feedback.status.text = str[start:end]
01652       start = end
01653       end += 1
01654       (self.action_feedback.feedback.searching,) = _struct_b.unpack(str[start:end])
01655       return self
01656     except struct.error as e:
01657       raise genpy.DeserializationError(e) #most likely buffer underfill
01658 
01659 
01660   def serialize_numpy(self, buff, numpy):
01661     """
01662     serialize message with numpy array types into buffer
01663     :param buff: buffer, ``StringIO``
01664     :param numpy: numpy python module
01665     """
01666     try:
01667       _x = self
01668       buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
01669       _x = self.action_goal.header.frame_id
01670       length = len(_x)
01671       if python3 or type(_x) == unicode:
01672         _x = _x.encode('utf-8')
01673         length = len(_x)
01674       buff.write(struct.pack('<I%ss'%length, length, _x))
01675       _x = self
01676       buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
01677       _x = self.action_goal.goal_id.id
01678       length = len(_x)
01679       if python3 or type(_x) == unicode:
01680         _x = _x.encode('utf-8')
01681         length = len(_x)
01682       buff.write(struct.pack('<I%ss'%length, length, _x))
01683       _x = self
01684       buff.write(_struct_b3I.pack(_x.action_goal.goal.start, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
01685       _x = self.action_result.header.frame_id
01686       length = len(_x)
01687       if python3 or type(_x) == unicode:
01688         _x = _x.encode('utf-8')
01689         length = len(_x)
01690       buff.write(struct.pack('<I%ss'%length, length, _x))
01691       _x = self
01692       buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
01693       _x = self.action_result.status.goal_id.id
01694       length = len(_x)
01695       if python3 or type(_x) == unicode:
01696         _x = _x.encode('utf-8')
01697         length = len(_x)
01698       buff.write(struct.pack('<I%ss'%length, length, _x))
01699       buff.write(_struct_B.pack(self.action_result.status.status))
01700       _x = self.action_result.status.text
01701       length = len(_x)
01702       if python3 or type(_x) == unicode:
01703         _x = _x.encode('utf-8')
01704         length = len(_x)
01705       buff.write(struct.pack('<I%ss'%length, length, _x))
01706       _x = self
01707       buff.write(_struct_3I.pack(_x.action_result.result.base_poses.header.seq, _x.action_result.result.base_poses.header.stamp.secs, _x.action_result.result.base_poses.header.stamp.nsecs))
01708       _x = self.action_result.result.base_poses.header.frame_id
01709       length = len(_x)
01710       if python3 or type(_x) == unicode:
01711         _x = _x.encode('utf-8')
01712         length = len(_x)
01713       buff.write(struct.pack('<I%ss'%length, length, _x))
01714       _x = self
01715       buff.write(_struct_7db.pack(_x.action_result.result.base_poses.pose.position.x, _x.action_result.result.base_poses.pose.position.y, _x.action_result.result.base_poses.pose.position.z, _x.action_result.result.base_poses.pose.orientation.x, _x.action_result.result.base_poses.pose.orientation.y, _x.action_result.result.base_poses.pose.orientation.z, _x.action_result.result.base_poses.pose.orientation.w, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.type))
01716       length = len(self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.dimensions)
01717       buff.write(_struct_I.pack(length))
01718       pattern = '<%sd'%length
01719       buff.write(self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.dimensions.tostring())
01720       length = len(self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.triangles)
01721       buff.write(_struct_I.pack(length))
01722       pattern = '<%si'%length
01723       buff.write(self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.triangles.tostring())
01724       length = len(self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.vertices)
01725       buff.write(_struct_I.pack(length))
01726       for val1 in self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.vertices:
01727         _x = val1
01728         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01729       _x = self
01730       buff.write(_struct_3I.pack(_x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.seq, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.stamp.nsecs))
01731       _x = self.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.frame_id
01732       length = len(_x)
01733       if python3 or type(_x) == unicode:
01734         _x = _x.encode('utf-8')
01735         length = len(_x)
01736       buff.write(struct.pack('<I%ss'%length, length, _x))
01737       _x = self
01738       buff.write(_struct_7d3I.pack(_x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.x, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.y, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.z, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.action_result.result.arm_poses.start_state.joint_state.header.seq, _x.action_result.result.arm_poses.start_state.joint_state.header.stamp.secs, _x.action_result.result.arm_poses.start_state.joint_state.header.stamp.nsecs))
01739       _x = self.action_result.result.arm_poses.start_state.joint_state.header.frame_id
01740       length = len(_x)
01741       if python3 or type(_x) == unicode:
01742         _x = _x.encode('utf-8')
01743         length = len(_x)
01744       buff.write(struct.pack('<I%ss'%length, length, _x))
01745       length = len(self.action_result.result.arm_poses.start_state.joint_state.name)
01746       buff.write(_struct_I.pack(length))
01747       for val1 in self.action_result.result.arm_poses.start_state.joint_state.name:
01748         length = len(val1)
01749         if python3 or type(val1) == unicode:
01750           val1 = val1.encode('utf-8')
01751           length = len(val1)
01752         buff.write(struct.pack('<I%ss'%length, length, val1))
01753       length = len(self.action_result.result.arm_poses.start_state.joint_state.position)
01754       buff.write(_struct_I.pack(length))
01755       pattern = '<%sd'%length
01756       buff.write(self.action_result.result.arm_poses.start_state.joint_state.position.tostring())
01757       length = len(self.action_result.result.arm_poses.start_state.joint_state.velocity)
01758       buff.write(_struct_I.pack(length))
01759       pattern = '<%sd'%length
01760       buff.write(self.action_result.result.arm_poses.start_state.joint_state.velocity.tostring())
01761       length = len(self.action_result.result.arm_poses.start_state.joint_state.effort)
01762       buff.write(_struct_I.pack(length))
01763       pattern = '<%sd'%length
01764       buff.write(self.action_result.result.arm_poses.start_state.joint_state.effort.tostring())
01765       _x = self
01766       buff.write(_struct_2I.pack(_x.action_result.result.arm_poses.start_state.multi_dof_joint_state.stamp.secs, _x.action_result.result.arm_poses.start_state.multi_dof_joint_state.stamp.nsecs))
01767       length = len(self.action_result.result.arm_poses.start_state.multi_dof_joint_state.joint_names)
01768       buff.write(_struct_I.pack(length))
01769       for val1 in self.action_result.result.arm_poses.start_state.multi_dof_joint_state.joint_names:
01770         length = len(val1)
01771         if python3 or type(val1) == unicode:
01772           val1 = val1.encode('utf-8')
01773           length = len(val1)
01774         buff.write(struct.pack('<I%ss'%length, length, val1))
01775       length = len(self.action_result.result.arm_poses.start_state.multi_dof_joint_state.frame_ids)
01776       buff.write(_struct_I.pack(length))
01777       for val1 in self.action_result.result.arm_poses.start_state.multi_dof_joint_state.frame_ids:
01778         length = len(val1)
01779         if python3 or type(val1) == unicode:
01780           val1 = val1.encode('utf-8')
01781           length = len(val1)
01782         buff.write(struct.pack('<I%ss'%length, length, val1))
01783       length = len(self.action_result.result.arm_poses.start_state.multi_dof_joint_state.child_frame_ids)
01784       buff.write(_struct_I.pack(length))
01785       for val1 in self.action_result.result.arm_poses.start_state.multi_dof_joint_state.child_frame_ids:
01786         length = len(val1)
01787         if python3 or type(val1) == unicode:
01788           val1 = val1.encode('utf-8')
01789           length = len(val1)
01790         buff.write(struct.pack('<I%ss'%length, length, val1))
01791       length = len(self.action_result.result.arm_poses.start_state.multi_dof_joint_state.poses)
01792       buff.write(_struct_I.pack(length))
01793       for val1 in self.action_result.result.arm_poses.start_state.multi_dof_joint_state.poses:
01794         _v89 = val1.position
01795         _x = _v89
01796         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01797         _v90 = val1.orientation
01798         _x = _v90
01799         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01800       length = len(self.action_result.result.arm_poses.goal_constraints.joint_constraints)
01801       buff.write(_struct_I.pack(length))
01802       for val1 in self.action_result.result.arm_poses.goal_constraints.joint_constraints:
01803         _x = val1.joint_name
01804         length = len(_x)
01805         if python3 or type(_x) == unicode:
01806           _x = _x.encode('utf-8')
01807           length = len(_x)
01808         buff.write(struct.pack('<I%ss'%length, length, _x))
01809         _x = val1
01810         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01811       length = len(self.action_result.result.arm_poses.goal_constraints.position_constraints)
01812       buff.write(_struct_I.pack(length))
01813       for val1 in self.action_result.result.arm_poses.goal_constraints.position_constraints:
01814         _v91 = val1.header
01815         buff.write(_struct_I.pack(_v91.seq))
01816         _v92 = _v91.stamp
01817         _x = _v92
01818         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01819         _x = _v91.frame_id
01820         length = len(_x)
01821         if python3 or type(_x) == unicode:
01822           _x = _x.encode('utf-8')
01823           length = len(_x)
01824         buff.write(struct.pack('<I%ss'%length, length, _x))
01825         _x = val1.link_name
01826         length = len(_x)
01827         if python3 or type(_x) == unicode:
01828           _x = _x.encode('utf-8')
01829           length = len(_x)
01830         buff.write(struct.pack('<I%ss'%length, length, _x))
01831         _v93 = val1.target_point_offset
01832         _x = _v93
01833         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01834         _v94 = val1.position
01835         _x = _v94
01836         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01837         _v95 = val1.constraint_region_shape
01838         buff.write(_struct_b.pack(_v95.type))
01839         length = len(_v95.dimensions)
01840         buff.write(_struct_I.pack(length))
01841         pattern = '<%sd'%length
01842         buff.write(_v95.dimensions.tostring())
01843         length = len(_v95.triangles)
01844         buff.write(_struct_I.pack(length))
01845         pattern = '<%si'%length
01846         buff.write(_v95.triangles.tostring())
01847         length = len(_v95.vertices)
01848         buff.write(_struct_I.pack(length))
01849         for val3 in _v95.vertices:
01850           _x = val3
01851           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01852         _v96 = val1.constraint_region_orientation
01853         _x = _v96
01854         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01855         buff.write(_struct_d.pack(val1.weight))
01856       length = len(self.action_result.result.arm_poses.goal_constraints.orientation_constraints)
01857       buff.write(_struct_I.pack(length))
01858       for val1 in self.action_result.result.arm_poses.goal_constraints.orientation_constraints:
01859         _v97 = val1.header
01860         buff.write(_struct_I.pack(_v97.seq))
01861         _v98 = _v97.stamp
01862         _x = _v98
01863         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01864         _x = _v97.frame_id
01865         length = len(_x)
01866         if python3 or type(_x) == unicode:
01867           _x = _x.encode('utf-8')
01868           length = len(_x)
01869         buff.write(struct.pack('<I%ss'%length, length, _x))
01870         _x = val1.link_name
01871         length = len(_x)
01872         if python3 or type(_x) == unicode:
01873           _x = _x.encode('utf-8')
01874           length = len(_x)
01875         buff.write(struct.pack('<I%ss'%length, length, _x))
01876         buff.write(_struct_i.pack(val1.type))
01877         _v99 = val1.orientation
01878         _x = _v99
01879         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01880         _x = val1
01881         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
01882       length = len(self.action_result.result.arm_poses.goal_constraints.visibility_constraints)
01883       buff.write(_struct_I.pack(length))
01884       for val1 in self.action_result.result.arm_poses.goal_constraints.visibility_constraints:
01885         _v100 = val1.header
01886         buff.write(_struct_I.pack(_v100.seq))
01887         _v101 = _v100.stamp
01888         _x = _v101
01889         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01890         _x = _v100.frame_id
01891         length = len(_x)
01892         if python3 or type(_x) == unicode:
01893           _x = _x.encode('utf-8')
01894           length = len(_x)
01895         buff.write(struct.pack('<I%ss'%length, length, _x))
01896         _v102 = val1.target
01897         _v103 = _v102.header
01898         buff.write(_struct_I.pack(_v103.seq))
01899         _v104 = _v103.stamp
01900         _x = _v104
01901         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01902         _x = _v103.frame_id
01903         length = len(_x)
01904         if python3 or type(_x) == unicode:
01905           _x = _x.encode('utf-8')
01906           length = len(_x)
01907         buff.write(struct.pack('<I%ss'%length, length, _x))
01908         _v105 = _v102.point
01909         _x = _v105
01910         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01911         _v106 = val1.sensor_pose
01912         _v107 = _v106.header
01913         buff.write(_struct_I.pack(_v107.seq))
01914         _v108 = _v107.stamp
01915         _x = _v108
01916         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01917         _x = _v107.frame_id
01918         length = len(_x)
01919         if python3 or type(_x) == unicode:
01920           _x = _x.encode('utf-8')
01921           length = len(_x)
01922         buff.write(struct.pack('<I%ss'%length, length, _x))
01923         _v109 = _v106.pose
01924         _v110 = _v109.position
01925         _x = _v110
01926         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01927         _v111 = _v109.orientation
01928         _x = _v111
01929         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01930         buff.write(_struct_d.pack(val1.absolute_tolerance))
01931       length = len(self.action_result.result.arm_poses.path_constraints.joint_constraints)
01932       buff.write(_struct_I.pack(length))
01933       for val1 in self.action_result.result.arm_poses.path_constraints.joint_constraints:
01934         _x = val1.joint_name
01935         length = len(_x)
01936         if python3 or type(_x) == unicode:
01937           _x = _x.encode('utf-8')
01938           length = len(_x)
01939         buff.write(struct.pack('<I%ss'%length, length, _x))
01940         _x = val1
01941         buff.write(_struct_4d.pack(_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight))
01942       length = len(self.action_result.result.arm_poses.path_constraints.position_constraints)
01943       buff.write(_struct_I.pack(length))
01944       for val1 in self.action_result.result.arm_poses.path_constraints.position_constraints:
01945         _v112 = val1.header
01946         buff.write(_struct_I.pack(_v112.seq))
01947         _v113 = _v112.stamp
01948         _x = _v113
01949         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01950         _x = _v112.frame_id
01951         length = len(_x)
01952         if python3 or type(_x) == unicode:
01953           _x = _x.encode('utf-8')
01954           length = len(_x)
01955         buff.write(struct.pack('<I%ss'%length, length, _x))
01956         _x = val1.link_name
01957         length = len(_x)
01958         if python3 or type(_x) == unicode:
01959           _x = _x.encode('utf-8')
01960           length = len(_x)
01961         buff.write(struct.pack('<I%ss'%length, length, _x))
01962         _v114 = val1.target_point_offset
01963         _x = _v114
01964         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01965         _v115 = val1.position
01966         _x = _v115
01967         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01968         _v116 = val1.constraint_region_shape
01969         buff.write(_struct_b.pack(_v116.type))
01970         length = len(_v116.dimensions)
01971         buff.write(_struct_I.pack(length))
01972         pattern = '<%sd'%length
01973         buff.write(_v116.dimensions.tostring())
01974         length = len(_v116.triangles)
01975         buff.write(_struct_I.pack(length))
01976         pattern = '<%si'%length
01977         buff.write(_v116.triangles.tostring())
01978         length = len(_v116.vertices)
01979         buff.write(_struct_I.pack(length))
01980         for val3 in _v116.vertices:
01981           _x = val3
01982           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01983         _v117 = val1.constraint_region_orientation
01984         _x = _v117
01985         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01986         buff.write(_struct_d.pack(val1.weight))
01987       length = len(self.action_result.result.arm_poses.path_constraints.orientation_constraints)
01988       buff.write(_struct_I.pack(length))
01989       for val1 in self.action_result.result.arm_poses.path_constraints.orientation_constraints:
01990         _v118 = val1.header
01991         buff.write(_struct_I.pack(_v118.seq))
01992         _v119 = _v118.stamp
01993         _x = _v119
01994         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01995         _x = _v118.frame_id
01996         length = len(_x)
01997         if python3 or type(_x) == unicode:
01998           _x = _x.encode('utf-8')
01999           length = len(_x)
02000         buff.write(struct.pack('<I%ss'%length, length, _x))
02001         _x = val1.link_name
02002         length = len(_x)
02003         if python3 or type(_x) == unicode:
02004           _x = _x.encode('utf-8')
02005           length = len(_x)
02006         buff.write(struct.pack('<I%ss'%length, length, _x))
02007         buff.write(_struct_i.pack(val1.type))
02008         _v120 = val1.orientation
02009         _x = _v120
02010         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02011         _x = val1
02012         buff.write(_struct_4d.pack(_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
02013       length = len(self.action_result.result.arm_poses.path_constraints.visibility_constraints)
02014       buff.write(_struct_I.pack(length))
02015       for val1 in self.action_result.result.arm_poses.path_constraints.visibility_constraints:
02016         _v121 = val1.header
02017         buff.write(_struct_I.pack(_v121.seq))
02018         _v122 = _v121.stamp
02019         _x = _v122
02020         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02021         _x = _v121.frame_id
02022         length = len(_x)
02023         if python3 or type(_x) == unicode:
02024           _x = _x.encode('utf-8')
02025           length = len(_x)
02026         buff.write(struct.pack('<I%ss'%length, length, _x))
02027         _v123 = val1.target
02028         _v124 = _v123.header
02029         buff.write(_struct_I.pack(_v124.seq))
02030         _v125 = _v124.stamp
02031         _x = _v125
02032         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02033         _x = _v124.frame_id
02034         length = len(_x)
02035         if python3 or type(_x) == unicode:
02036           _x = _x.encode('utf-8')
02037           length = len(_x)
02038         buff.write(struct.pack('<I%ss'%length, length, _x))
02039         _v126 = _v123.point
02040         _x = _v126
02041         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02042         _v127 = val1.sensor_pose
02043         _v128 = _v127.header
02044         buff.write(_struct_I.pack(_v128.seq))
02045         _v129 = _v128.stamp
02046         _x = _v129
02047         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02048         _x = _v128.frame_id
02049         length = len(_x)
02050         if python3 or type(_x) == unicode:
02051           _x = _x.encode('utf-8')
02052           length = len(_x)
02053         buff.write(struct.pack('<I%ss'%length, length, _x))
02054         _v130 = _v127.pose
02055         _v131 = _v130.position
02056         _x = _v131
02057         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02058         _v132 = _v130.orientation
02059         _x = _v132
02060         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02061         buff.write(_struct_d.pack(val1.absolute_tolerance))
02062       _x = self.action_result.result.arm_poses.planner_id
02063       length = len(_x)
02064       if python3 or type(_x) == unicode:
02065         _x = _x.encode('utf-8')
02066         length = len(_x)
02067       buff.write(struct.pack('<I%ss'%length, length, _x))
02068       _x = self.action_result.result.arm_poses.group_name
02069       length = len(_x)
02070       if python3 or type(_x) == unicode:
02071         _x = _x.encode('utf-8')
02072         length = len(_x)
02073       buff.write(struct.pack('<I%ss'%length, length, _x))
02074       _x = self
02075       buff.write(_struct_7i.pack(_x.action_result.result.arm_poses.num_planning_attempts, _x.action_result.result.arm_poses.allowed_planning_time.secs, _x.action_result.result.arm_poses.allowed_planning_time.nsecs, _x.action_result.result.arm_poses.expected_path_duration.secs, _x.action_result.result.arm_poses.expected_path_duration.nsecs, _x.action_result.result.arm_poses.expected_path_dt.secs, _x.action_result.result.arm_poses.expected_path_dt.nsecs))
02076       _x = self.action_result.result.planner_service_name
02077       length = len(_x)
02078       if python3 or type(_x) == unicode:
02079         _x = _x.encode('utf-8')
02080         length = len(_x)
02081       buff.write(struct.pack('<I%ss'%length, length, _x))
02082       _x = self.action_result.result.state
02083       length = len(_x)
02084       if python3 or type(_x) == unicode:
02085         _x = _x.encode('utf-8')
02086         length = len(_x)
02087       buff.write(struct.pack('<I%ss'%length, length, _x))
02088       _x = self
02089       buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
02090       _x = self.action_feedback.header.frame_id
02091       length = len(_x)
02092       if python3 or type(_x) == unicode:
02093         _x = _x.encode('utf-8')
02094         length = len(_x)
02095       buff.write(struct.pack('<I%ss'%length, length, _x))
02096       _x = self
02097       buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
02098       _x = self.action_feedback.status.goal_id.id
02099       length = len(_x)
02100       if python3 or type(_x) == unicode:
02101         _x = _x.encode('utf-8')
02102         length = len(_x)
02103       buff.write(struct.pack('<I%ss'%length, length, _x))
02104       buff.write(_struct_B.pack(self.action_feedback.status.status))
02105       _x = self.action_feedback.status.text
02106       length = len(_x)
02107       if python3 or type(_x) == unicode:
02108         _x = _x.encode('utf-8')
02109         length = len(_x)
02110       buff.write(struct.pack('<I%ss'%length, length, _x))
02111       buff.write(_struct_b.pack(self.action_feedback.feedback.searching))
02112     except struct.error as se: self._check_types(se)
02113     except TypeError as te: self._check_types(te)
02114 
02115   def deserialize_numpy(self, str, numpy):
02116     """
02117     unpack serialized message in str into this message instance using numpy for array types
02118     :param str: byte array of serialized message, ``str``
02119     :param numpy: numpy python module
02120     """
02121     try:
02122       if self.action_goal is None:
02123         self.action_goal = iri_door_detector.msg.FindADoorActionGoal()
02124       if self.action_result is None:
02125         self.action_result = iri_door_detector.msg.FindADoorActionResult()
02126       if self.action_feedback is None:
02127         self.action_feedback = iri_door_detector.msg.FindADoorActionFeedback()
02128       end = 0
02129       _x = self
02130       start = end
02131       end += 12
02132       (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02133       start = end
02134       end += 4
02135       (length,) = _struct_I.unpack(str[start:end])
02136       start = end
02137       end += length
02138       if python3:
02139         self.action_goal.header.frame_id = str[start:end].decode('utf-8')
02140       else:
02141         self.action_goal.header.frame_id = str[start:end]
02142       _x = self
02143       start = end
02144       end += 8
02145       (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02146       start = end
02147       end += 4
02148       (length,) = _struct_I.unpack(str[start:end])
02149       start = end
02150       end += length
02151       if python3:
02152         self.action_goal.goal_id.id = str[start:end].decode('utf-8')
02153       else:
02154         self.action_goal.goal_id.id = str[start:end]
02155       _x = self
02156       start = end
02157       end += 13
02158       (_x.action_goal.goal.start, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_b3I.unpack(str[start:end])
02159       start = end
02160       end += 4
02161       (length,) = _struct_I.unpack(str[start:end])
02162       start = end
02163       end += length
02164       if python3:
02165         self.action_result.header.frame_id = str[start:end].decode('utf-8')
02166       else:
02167         self.action_result.header.frame_id = str[start:end]
02168       _x = self
02169       start = end
02170       end += 8
02171       (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02172       start = end
02173       end += 4
02174       (length,) = _struct_I.unpack(str[start:end])
02175       start = end
02176       end += length
02177       if python3:
02178         self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
02179       else:
02180         self.action_result.status.goal_id.id = str[start:end]
02181       start = end
02182       end += 1
02183       (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
02184       start = end
02185       end += 4
02186       (length,) = _struct_I.unpack(str[start:end])
02187       start = end
02188       end += length
02189       if python3:
02190         self.action_result.status.text = str[start:end].decode('utf-8')
02191       else:
02192         self.action_result.status.text = str[start:end]
02193       _x = self
02194       start = end
02195       end += 12
02196       (_x.action_result.result.base_poses.header.seq, _x.action_result.result.base_poses.header.stamp.secs, _x.action_result.result.base_poses.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02197       start = end
02198       end += 4
02199       (length,) = _struct_I.unpack(str[start:end])
02200       start = end
02201       end += length
02202       if python3:
02203         self.action_result.result.base_poses.header.frame_id = str[start:end].decode('utf-8')
02204       else:
02205         self.action_result.result.base_poses.header.frame_id = str[start:end]
02206       _x = self
02207       start = end
02208       end += 57
02209       (_x.action_result.result.base_poses.pose.position.x, _x.action_result.result.base_poses.pose.position.y, _x.action_result.result.base_poses.pose.position.z, _x.action_result.result.base_poses.pose.orientation.x, _x.action_result.result.base_poses.pose.orientation.y, _x.action_result.result.base_poses.pose.orientation.z, _x.action_result.result.base_poses.pose.orientation.w, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.type,) = _struct_7db.unpack(str[start:end])
02210       start = end
02211       end += 4
02212       (length,) = _struct_I.unpack(str[start:end])
02213       pattern = '<%sd'%length
02214       start = end
02215       end += struct.calcsize(pattern)
02216       self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02217       start = end
02218       end += 4
02219       (length,) = _struct_I.unpack(str[start:end])
02220       pattern = '<%si'%length
02221       start = end
02222       end += struct.calcsize(pattern)
02223       self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02224       start = end
02225       end += 4
02226       (length,) = _struct_I.unpack(str[start:end])
02227       self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.vertices = []
02228       for i in range(0, length):
02229         val1 = geometry_msgs.msg.Point()
02230         _x = val1
02231         start = end
02232         end += 24
02233         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02234         self.action_result.result.arm_poses.workspace_parameters.workspace_region_shape.vertices.append(val1)
02235       _x = self
02236       start = end
02237       end += 12
02238       (_x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.seq, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.stamp.secs, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02239       start = end
02240       end += 4
02241       (length,) = _struct_I.unpack(str[start:end])
02242       start = end
02243       end += length
02244       if python3:
02245         self.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end].decode('utf-8')
02246       else:
02247         self.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.header.frame_id = str[start:end]
02248       _x = self
02249       start = end
02250       end += 68
02251       (_x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.x, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.y, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.position.z, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.x, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.y, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.z, _x.action_result.result.arm_poses.workspace_parameters.workspace_region_pose.pose.orientation.w, _x.action_result.result.arm_poses.start_state.joint_state.header.seq, _x.action_result.result.arm_poses.start_state.joint_state.header.stamp.secs, _x.action_result.result.arm_poses.start_state.joint_state.header.stamp.nsecs,) = _struct_7d3I.unpack(str[start:end])
02252       start = end
02253       end += 4
02254       (length,) = _struct_I.unpack(str[start:end])
02255       start = end
02256       end += length
02257       if python3:
02258         self.action_result.result.arm_poses.start_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
02259       else:
02260         self.action_result.result.arm_poses.start_state.joint_state.header.frame_id = str[start:end]
02261       start = end
02262       end += 4
02263       (length,) = _struct_I.unpack(str[start:end])
02264       self.action_result.result.arm_poses.start_state.joint_state.name = []
02265       for i in range(0, length):
02266         start = end
02267         end += 4
02268         (length,) = _struct_I.unpack(str[start:end])
02269         start = end
02270         end += length
02271         if python3:
02272           val1 = str[start:end].decode('utf-8')
02273         else:
02274           val1 = str[start:end]
02275         self.action_result.result.arm_poses.start_state.joint_state.name.append(val1)
02276       start = end
02277       end += 4
02278       (length,) = _struct_I.unpack(str[start:end])
02279       pattern = '<%sd'%length
02280       start = end
02281       end += struct.calcsize(pattern)
02282       self.action_result.result.arm_poses.start_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02283       start = end
02284       end += 4
02285       (length,) = _struct_I.unpack(str[start:end])
02286       pattern = '<%sd'%length
02287       start = end
02288       end += struct.calcsize(pattern)
02289       self.action_result.result.arm_poses.start_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02290       start = end
02291       end += 4
02292       (length,) = _struct_I.unpack(str[start:end])
02293       pattern = '<%sd'%length
02294       start = end
02295       end += struct.calcsize(pattern)
02296       self.action_result.result.arm_poses.start_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02297       _x = self
02298       start = end
02299       end += 8
02300       (_x.action_result.result.arm_poses.start_state.multi_dof_joint_state.stamp.secs, _x.action_result.result.arm_poses.start_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02301       start = end
02302       end += 4
02303       (length,) = _struct_I.unpack(str[start:end])
02304       self.action_result.result.arm_poses.start_state.multi_dof_joint_state.joint_names = []
02305       for i in range(0, length):
02306         start = end
02307         end += 4
02308         (length,) = _struct_I.unpack(str[start:end])
02309         start = end
02310         end += length
02311         if python3:
02312           val1 = str[start:end].decode('utf-8')
02313         else:
02314           val1 = str[start:end]
02315         self.action_result.result.arm_poses.start_state.multi_dof_joint_state.joint_names.append(val1)
02316       start = end
02317       end += 4
02318       (length,) = _struct_I.unpack(str[start:end])
02319       self.action_result.result.arm_poses.start_state.multi_dof_joint_state.frame_ids = []
02320       for i in range(0, length):
02321         start = end
02322         end += 4
02323         (length,) = _struct_I.unpack(str[start:end])
02324         start = end
02325         end += length
02326         if python3:
02327           val1 = str[start:end].decode('utf-8')
02328         else:
02329           val1 = str[start:end]
02330         self.action_result.result.arm_poses.start_state.multi_dof_joint_state.frame_ids.append(val1)
02331       start = end
02332       end += 4
02333       (length,) = _struct_I.unpack(str[start:end])
02334       self.action_result.result.arm_poses.start_state.multi_dof_joint_state.child_frame_ids = []
02335       for i in range(0, length):
02336         start = end
02337         end += 4
02338         (length,) = _struct_I.unpack(str[start:end])
02339         start = end
02340         end += length
02341         if python3:
02342           val1 = str[start:end].decode('utf-8')
02343         else:
02344           val1 = str[start:end]
02345         self.action_result.result.arm_poses.start_state.multi_dof_joint_state.child_frame_ids.append(val1)
02346       start = end
02347       end += 4
02348       (length,) = _struct_I.unpack(str[start:end])
02349       self.action_result.result.arm_poses.start_state.multi_dof_joint_state.poses = []
02350       for i in range(0, length):
02351         val1 = geometry_msgs.msg.Pose()
02352         _v133 = val1.position
02353         _x = _v133
02354         start = end
02355         end += 24
02356         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02357         _v134 = val1.orientation
02358         _x = _v134
02359         start = end
02360         end += 32
02361         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02362         self.action_result.result.arm_poses.start_state.multi_dof_joint_state.poses.append(val1)
02363       start = end
02364       end += 4
02365       (length,) = _struct_I.unpack(str[start:end])
02366       self.action_result.result.arm_poses.goal_constraints.joint_constraints = []
02367       for i in range(0, length):
02368         val1 = arm_navigation_msgs.msg.JointConstraint()
02369         start = end
02370         end += 4
02371         (length,) = _struct_I.unpack(str[start:end])
02372         start = end
02373         end += length
02374         if python3:
02375           val1.joint_name = str[start:end].decode('utf-8')
02376         else:
02377           val1.joint_name = str[start:end]
02378         _x = val1
02379         start = end
02380         end += 32
02381         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
02382         self.action_result.result.arm_poses.goal_constraints.joint_constraints.append(val1)
02383       start = end
02384       end += 4
02385       (length,) = _struct_I.unpack(str[start:end])
02386       self.action_result.result.arm_poses.goal_constraints.position_constraints = []
02387       for i in range(0, length):
02388         val1 = arm_navigation_msgs.msg.PositionConstraint()
02389         _v135 = val1.header
02390         start = end
02391         end += 4
02392         (_v135.seq,) = _struct_I.unpack(str[start:end])
02393         _v136 = _v135.stamp
02394         _x = _v136
02395         start = end
02396         end += 8
02397         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02398         start = end
02399         end += 4
02400         (length,) = _struct_I.unpack(str[start:end])
02401         start = end
02402         end += length
02403         if python3:
02404           _v135.frame_id = str[start:end].decode('utf-8')
02405         else:
02406           _v135.frame_id = str[start:end]
02407         start = end
02408         end += 4
02409         (length,) = _struct_I.unpack(str[start:end])
02410         start = end
02411         end += length
02412         if python3:
02413           val1.link_name = str[start:end].decode('utf-8')
02414         else:
02415           val1.link_name = str[start:end]
02416         _v137 = val1.target_point_offset
02417         _x = _v137
02418         start = end
02419         end += 24
02420         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02421         _v138 = val1.position
02422         _x = _v138
02423         start = end
02424         end += 24
02425         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02426         _v139 = val1.constraint_region_shape
02427         start = end
02428         end += 1
02429         (_v139.type,) = _struct_b.unpack(str[start:end])
02430         start = end
02431         end += 4
02432         (length,) = _struct_I.unpack(str[start:end])
02433         pattern = '<%sd'%length
02434         start = end
02435         end += struct.calcsize(pattern)
02436         _v139.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02437         start = end
02438         end += 4
02439         (length,) = _struct_I.unpack(str[start:end])
02440         pattern = '<%si'%length
02441         start = end
02442         end += struct.calcsize(pattern)
02443         _v139.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02444         start = end
02445         end += 4
02446         (length,) = _struct_I.unpack(str[start:end])
02447         _v139.vertices = []
02448         for i in range(0, length):
02449           val3 = geometry_msgs.msg.Point()
02450           _x = val3
02451           start = end
02452           end += 24
02453           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02454           _v139.vertices.append(val3)
02455         _v140 = val1.constraint_region_orientation
02456         _x = _v140
02457         start = end
02458         end += 32
02459         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02460         start = end
02461         end += 8
02462         (val1.weight,) = _struct_d.unpack(str[start:end])
02463         self.action_result.result.arm_poses.goal_constraints.position_constraints.append(val1)
02464       start = end
02465       end += 4
02466       (length,) = _struct_I.unpack(str[start:end])
02467       self.action_result.result.arm_poses.goal_constraints.orientation_constraints = []
02468       for i in range(0, length):
02469         val1 = arm_navigation_msgs.msg.OrientationConstraint()
02470         _v141 = val1.header
02471         start = end
02472         end += 4
02473         (_v141.seq,) = _struct_I.unpack(str[start:end])
02474         _v142 = _v141.stamp
02475         _x = _v142
02476         start = end
02477         end += 8
02478         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02479         start = end
02480         end += 4
02481         (length,) = _struct_I.unpack(str[start:end])
02482         start = end
02483         end += length
02484         if python3:
02485           _v141.frame_id = str[start:end].decode('utf-8')
02486         else:
02487           _v141.frame_id = str[start:end]
02488         start = end
02489         end += 4
02490         (length,) = _struct_I.unpack(str[start:end])
02491         start = end
02492         end += length
02493         if python3:
02494           val1.link_name = str[start:end].decode('utf-8')
02495         else:
02496           val1.link_name = str[start:end]
02497         start = end
02498         end += 4
02499         (val1.type,) = _struct_i.unpack(str[start:end])
02500         _v143 = val1.orientation
02501         _x = _v143
02502         start = end
02503         end += 32
02504         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02505         _x = val1
02506         start = end
02507         end += 32
02508         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02509         self.action_result.result.arm_poses.goal_constraints.orientation_constraints.append(val1)
02510       start = end
02511       end += 4
02512       (length,) = _struct_I.unpack(str[start:end])
02513       self.action_result.result.arm_poses.goal_constraints.visibility_constraints = []
02514       for i in range(0, length):
02515         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02516         _v144 = val1.header
02517         start = end
02518         end += 4
02519         (_v144.seq,) = _struct_I.unpack(str[start:end])
02520         _v145 = _v144.stamp
02521         _x = _v145
02522         start = end
02523         end += 8
02524         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02525         start = end
02526         end += 4
02527         (length,) = _struct_I.unpack(str[start:end])
02528         start = end
02529         end += length
02530         if python3:
02531           _v144.frame_id = str[start:end].decode('utf-8')
02532         else:
02533           _v144.frame_id = str[start:end]
02534         _v146 = val1.target
02535         _v147 = _v146.header
02536         start = end
02537         end += 4
02538         (_v147.seq,) = _struct_I.unpack(str[start:end])
02539         _v148 = _v147.stamp
02540         _x = _v148
02541         start = end
02542         end += 8
02543         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02544         start = end
02545         end += 4
02546         (length,) = _struct_I.unpack(str[start:end])
02547         start = end
02548         end += length
02549         if python3:
02550           _v147.frame_id = str[start:end].decode('utf-8')
02551         else:
02552           _v147.frame_id = str[start:end]
02553         _v149 = _v146.point
02554         _x = _v149
02555         start = end
02556         end += 24
02557         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02558         _v150 = val1.sensor_pose
02559         _v151 = _v150.header
02560         start = end
02561         end += 4
02562         (_v151.seq,) = _struct_I.unpack(str[start:end])
02563         _v152 = _v151.stamp
02564         _x = _v152
02565         start = end
02566         end += 8
02567         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02568         start = end
02569         end += 4
02570         (length,) = _struct_I.unpack(str[start:end])
02571         start = end
02572         end += length
02573         if python3:
02574           _v151.frame_id = str[start:end].decode('utf-8')
02575         else:
02576           _v151.frame_id = str[start:end]
02577         _v153 = _v150.pose
02578         _v154 = _v153.position
02579         _x = _v154
02580         start = end
02581         end += 24
02582         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02583         _v155 = _v153.orientation
02584         _x = _v155
02585         start = end
02586         end += 32
02587         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02588         start = end
02589         end += 8
02590         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02591         self.action_result.result.arm_poses.goal_constraints.visibility_constraints.append(val1)
02592       start = end
02593       end += 4
02594       (length,) = _struct_I.unpack(str[start:end])
02595       self.action_result.result.arm_poses.path_constraints.joint_constraints = []
02596       for i in range(0, length):
02597         val1 = arm_navigation_msgs.msg.JointConstraint()
02598         start = end
02599         end += 4
02600         (length,) = _struct_I.unpack(str[start:end])
02601         start = end
02602         end += length
02603         if python3:
02604           val1.joint_name = str[start:end].decode('utf-8')
02605         else:
02606           val1.joint_name = str[start:end]
02607         _x = val1
02608         start = end
02609         end += 32
02610         (_x.position, _x.tolerance_above, _x.tolerance_below, _x.weight,) = _struct_4d.unpack(str[start:end])
02611         self.action_result.result.arm_poses.path_constraints.joint_constraints.append(val1)
02612       start = end
02613       end += 4
02614       (length,) = _struct_I.unpack(str[start:end])
02615       self.action_result.result.arm_poses.path_constraints.position_constraints = []
02616       for i in range(0, length):
02617         val1 = arm_navigation_msgs.msg.PositionConstraint()
02618         _v156 = val1.header
02619         start = end
02620         end += 4
02621         (_v156.seq,) = _struct_I.unpack(str[start:end])
02622         _v157 = _v156.stamp
02623         _x = _v157
02624         start = end
02625         end += 8
02626         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02627         start = end
02628         end += 4
02629         (length,) = _struct_I.unpack(str[start:end])
02630         start = end
02631         end += length
02632         if python3:
02633           _v156.frame_id = str[start:end].decode('utf-8')
02634         else:
02635           _v156.frame_id = str[start:end]
02636         start = end
02637         end += 4
02638         (length,) = _struct_I.unpack(str[start:end])
02639         start = end
02640         end += length
02641         if python3:
02642           val1.link_name = str[start:end].decode('utf-8')
02643         else:
02644           val1.link_name = str[start:end]
02645         _v158 = val1.target_point_offset
02646         _x = _v158
02647         start = end
02648         end += 24
02649         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02650         _v159 = val1.position
02651         _x = _v159
02652         start = end
02653         end += 24
02654         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02655         _v160 = val1.constraint_region_shape
02656         start = end
02657         end += 1
02658         (_v160.type,) = _struct_b.unpack(str[start:end])
02659         start = end
02660         end += 4
02661         (length,) = _struct_I.unpack(str[start:end])
02662         pattern = '<%sd'%length
02663         start = end
02664         end += struct.calcsize(pattern)
02665         _v160.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
02666         start = end
02667         end += 4
02668         (length,) = _struct_I.unpack(str[start:end])
02669         pattern = '<%si'%length
02670         start = end
02671         end += struct.calcsize(pattern)
02672         _v160.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
02673         start = end
02674         end += 4
02675         (length,) = _struct_I.unpack(str[start:end])
02676         _v160.vertices = []
02677         for i in range(0, length):
02678           val3 = geometry_msgs.msg.Point()
02679           _x = val3
02680           start = end
02681           end += 24
02682           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02683           _v160.vertices.append(val3)
02684         _v161 = val1.constraint_region_orientation
02685         _x = _v161
02686         start = end
02687         end += 32
02688         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02689         start = end
02690         end += 8
02691         (val1.weight,) = _struct_d.unpack(str[start:end])
02692         self.action_result.result.arm_poses.path_constraints.position_constraints.append(val1)
02693       start = end
02694       end += 4
02695       (length,) = _struct_I.unpack(str[start:end])
02696       self.action_result.result.arm_poses.path_constraints.orientation_constraints = []
02697       for i in range(0, length):
02698         val1 = arm_navigation_msgs.msg.OrientationConstraint()
02699         _v162 = val1.header
02700         start = end
02701         end += 4
02702         (_v162.seq,) = _struct_I.unpack(str[start:end])
02703         _v163 = _v162.stamp
02704         _x = _v163
02705         start = end
02706         end += 8
02707         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02708         start = end
02709         end += 4
02710         (length,) = _struct_I.unpack(str[start:end])
02711         start = end
02712         end += length
02713         if python3:
02714           _v162.frame_id = str[start:end].decode('utf-8')
02715         else:
02716           _v162.frame_id = str[start:end]
02717         start = end
02718         end += 4
02719         (length,) = _struct_I.unpack(str[start:end])
02720         start = end
02721         end += length
02722         if python3:
02723           val1.link_name = str[start:end].decode('utf-8')
02724         else:
02725           val1.link_name = str[start:end]
02726         start = end
02727         end += 4
02728         (val1.type,) = _struct_i.unpack(str[start:end])
02729         _v164 = val1.orientation
02730         _x = _v164
02731         start = end
02732         end += 32
02733         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02734         _x = val1
02735         start = end
02736         end += 32
02737         (_x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_4d.unpack(str[start:end])
02738         self.action_result.result.arm_poses.path_constraints.orientation_constraints.append(val1)
02739       start = end
02740       end += 4
02741       (length,) = _struct_I.unpack(str[start:end])
02742       self.action_result.result.arm_poses.path_constraints.visibility_constraints = []
02743       for i in range(0, length):
02744         val1 = arm_navigation_msgs.msg.VisibilityConstraint()
02745         _v165 = val1.header
02746         start = end
02747         end += 4
02748         (_v165.seq,) = _struct_I.unpack(str[start:end])
02749         _v166 = _v165.stamp
02750         _x = _v166
02751         start = end
02752         end += 8
02753         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02754         start = end
02755         end += 4
02756         (length,) = _struct_I.unpack(str[start:end])
02757         start = end
02758         end += length
02759         if python3:
02760           _v165.frame_id = str[start:end].decode('utf-8')
02761         else:
02762           _v165.frame_id = str[start:end]
02763         _v167 = val1.target
02764         _v168 = _v167.header
02765         start = end
02766         end += 4
02767         (_v168.seq,) = _struct_I.unpack(str[start:end])
02768         _v169 = _v168.stamp
02769         _x = _v169
02770         start = end
02771         end += 8
02772         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02773         start = end
02774         end += 4
02775         (length,) = _struct_I.unpack(str[start:end])
02776         start = end
02777         end += length
02778         if python3:
02779           _v168.frame_id = str[start:end].decode('utf-8')
02780         else:
02781           _v168.frame_id = str[start:end]
02782         _v170 = _v167.point
02783         _x = _v170
02784         start = end
02785         end += 24
02786         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02787         _v171 = val1.sensor_pose
02788         _v172 = _v171.header
02789         start = end
02790         end += 4
02791         (_v172.seq,) = _struct_I.unpack(str[start:end])
02792         _v173 = _v172.stamp
02793         _x = _v173
02794         start = end
02795         end += 8
02796         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02797         start = end
02798         end += 4
02799         (length,) = _struct_I.unpack(str[start:end])
02800         start = end
02801         end += length
02802         if python3:
02803           _v172.frame_id = str[start:end].decode('utf-8')
02804         else:
02805           _v172.frame_id = str[start:end]
02806         _v174 = _v171.pose
02807         _v175 = _v174.position
02808         _x = _v175
02809         start = end
02810         end += 24
02811         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02812         _v176 = _v174.orientation
02813         _x = _v176
02814         start = end
02815         end += 32
02816         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02817         start = end
02818         end += 8
02819         (val1.absolute_tolerance,) = _struct_d.unpack(str[start:end])
02820         self.action_result.result.arm_poses.path_constraints.visibility_constraints.append(val1)
02821       start = end
02822       end += 4
02823       (length,) = _struct_I.unpack(str[start:end])
02824       start = end
02825       end += length
02826       if python3:
02827         self.action_result.result.arm_poses.planner_id = str[start:end].decode('utf-8')
02828       else:
02829         self.action_result.result.arm_poses.planner_id = str[start:end]
02830       start = end
02831       end += 4
02832       (length,) = _struct_I.unpack(str[start:end])
02833       start = end
02834       end += length
02835       if python3:
02836         self.action_result.result.arm_poses.group_name = str[start:end].decode('utf-8')
02837       else:
02838         self.action_result.result.arm_poses.group_name = str[start:end]
02839       _x = self
02840       start = end
02841       end += 28
02842       (_x.action_result.result.arm_poses.num_planning_attempts, _x.action_result.result.arm_poses.allowed_planning_time.secs, _x.action_result.result.arm_poses.allowed_planning_time.nsecs, _x.action_result.result.arm_poses.expected_path_duration.secs, _x.action_result.result.arm_poses.expected_path_duration.nsecs, _x.action_result.result.arm_poses.expected_path_dt.secs, _x.action_result.result.arm_poses.expected_path_dt.nsecs,) = _struct_7i.unpack(str[start:end])
02843       start = end
02844       end += 4
02845       (length,) = _struct_I.unpack(str[start:end])
02846       start = end
02847       end += length
02848       if python3:
02849         self.action_result.result.planner_service_name = str[start:end].decode('utf-8')
02850       else:
02851         self.action_result.result.planner_service_name = str[start:end]
02852       start = end
02853       end += 4
02854       (length,) = _struct_I.unpack(str[start:end])
02855       start = end
02856       end += length
02857       if python3:
02858         self.action_result.result.state = str[start:end].decode('utf-8')
02859       else:
02860         self.action_result.result.state = str[start:end]
02861       _x = self
02862       start = end
02863       end += 12
02864       (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02865       start = end
02866       end += 4
02867       (length,) = _struct_I.unpack(str[start:end])
02868       start = end
02869       end += length
02870       if python3:
02871         self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
02872       else:
02873         self.action_feedback.header.frame_id = str[start:end]
02874       _x = self
02875       start = end
02876       end += 8
02877       (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
02878       start = end
02879       end += 4
02880       (length,) = _struct_I.unpack(str[start:end])
02881       start = end
02882       end += length
02883       if python3:
02884         self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
02885       else:
02886         self.action_feedback.status.goal_id.id = str[start:end]
02887       start = end
02888       end += 1
02889       (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
02890       start = end
02891       end += 4
02892       (length,) = _struct_I.unpack(str[start:end])
02893       start = end
02894       end += length
02895       if python3:
02896         self.action_feedback.status.text = str[start:end].decode('utf-8')
02897       else:
02898         self.action_feedback.status.text = str[start:end]
02899       start = end
02900       end += 1
02901       (self.action_feedback.feedback.searching,) = _struct_b.unpack(str[start:end])
02902       return self
02903     except struct.error as e:
02904       raise genpy.DeserializationError(e) #most likely buffer underfill
02905 
02906 _struct_I = genpy.struct_I
02907 _struct_7db = struct.Struct("<7db")
02908 _struct_B = struct.Struct("<B")
02909 _struct_d = struct.Struct("<d")
02910 _struct_7i = struct.Struct("<7i")
02911 _struct_7d3I = struct.Struct("<7d3I")
02912 _struct_i = struct.Struct("<i")
02913 _struct_3I = struct.Struct("<3I")
02914 _struct_b = struct.Struct("<b")
02915 _struct_b3I = struct.Struct("<b3I")
02916 _struct_4d = struct.Struct("<4d")
02917 _struct_2I = struct.Struct("<2I")
02918 _struct_3d = struct.Struct("<3d")


iri_door_detector
Author(s): Jose Rodriguez
autogenerated on Fri Dec 6 2013 23:57:15