00001 """autogenerated by genmsg_py from GraspHandPostureExecutionAction.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import object_manipulation_msgs.msg
00006 import roslib.rostime
00007 import actionlib_msgs.msg
00008 import geometry_msgs.msg
00009 import sensor_msgs.msg
00010 import std_msgs.msg
00011
00012 class GraspHandPostureExecutionAction(roslib.message.Message):
00013 _md5sum = "434b6850ea8ab0f7659ef128d319c1fe"
00014 _type = "object_manipulation_msgs/GraspHandPostureExecutionAction"
00015 _has_header = False
00016 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00017
00018 GraspHandPostureExecutionActionGoal action_goal
00019 GraspHandPostureExecutionActionResult action_result
00020 GraspHandPostureExecutionActionFeedback action_feedback
00021
00022 ================================================================================
00023 MSG: object_manipulation_msgs/GraspHandPostureExecutionActionGoal
00024 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00025
00026 Header header
00027 actionlib_msgs/GoalID goal_id
00028 GraspHandPostureExecutionGoal goal
00029
00030 ================================================================================
00031 MSG: std_msgs/Header
00032 # Standard metadata for higher-level stamped data types.
00033 # This is generally used to communicate timestamped data
00034 # in a particular coordinate frame.
00035 #
00036 # sequence ID: consecutively increasing ID
00037 uint32 seq
00038 #Two-integer timestamp that is expressed as:
00039 # * stamp.secs: seconds (stamp_secs) since epoch
00040 # * stamp.nsecs: nanoseconds since stamp_secs
00041 # time-handling sugar is provided by the client library
00042 time stamp
00043 #Frame this data is associated with
00044 # 0: no frame
00045 # 1: global frame
00046 string frame_id
00047
00048 ================================================================================
00049 MSG: actionlib_msgs/GoalID
00050 # The stamp should store the time at which this goal was requested.
00051 # It is used by an action server when it tries to preempt all
00052 # goals that were requested before a certain time
00053 time stamp
00054
00055 # The id provides a way to associate feedback and
00056 # result message with specific goal requests. The id
00057 # specified must be unique.
00058 string id
00059
00060
00061 ================================================================================
00062 MSG: object_manipulation_msgs/GraspHandPostureExecutionGoal
00063 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00064 # an action for requesting the finger posture part of grasp be physically carried out by a hand
00065 # the name of the arm being used is not in here, as this will be sent to a specific action server
00066 # for each arm
00067
00068 # the grasp to be executed
00069 Grasp grasp
00070
00071 # the goal of this action
00072 # requests that the hand be set in the pre-grasp posture
00073 int32 PRE_GRASP=1
00074 # requests that the hand execute the actual grasp
00075 int32 GRASP=2
00076 # requests that the hand open to release the object
00077 int32 RELEASE=3
00078 int32 goal
00079
00080
00081 ================================================================================
00082 MSG: object_manipulation_msgs/Grasp
00083
00084 # The internal posture of the hand for the pre-grasp
00085 # only positions are used
00086 sensor_msgs/JointState pre_grasp_posture
00087
00088 # The internal posture of the hand for the grasp
00089 # positions and efforts are used
00090 sensor_msgs/JointState grasp_posture
00091
00092 # The position of the end-effector for the grasp relative to the object
00093 geometry_msgs/Pose grasp_pose
00094
00095 # The estimated probability of success for this grasp
00096 float64 success_probability
00097
00098 # Debug flag to indicate that this grasp would be the best in its cluster
00099 bool cluster_rep
00100 ================================================================================
00101 MSG: sensor_msgs/JointState
00102 # This is a message that holds data to describe the state of a set of torque controlled joints.
00103 #
00104 # The state of each joint (revolute or prismatic) is defined by:
00105 # * the position of the joint (rad or m),
00106 # * the velocity of the joint (rad/s or m/s) and
00107 # * the effort that is applied in the joint (Nm or N).
00108 #
00109 # Each joint is uniquely identified by its name
00110 # The header specifies the time at which the joint states were recorded. All the joint states
00111 # in one message have to be recorded at the same time.
00112 #
00113 # This message consists of a multiple arrays, one for each part of the joint state.
00114 # The goal is to make each of the fields optional. When e.g. your joints have no
00115 # effort associated with them, you can leave the effort array empty.
00116 #
00117 # All arrays in this message should have the same size, or be empty.
00118 # This is the only way to uniquely associate the joint name with the correct
00119 # states.
00120
00121
00122 Header header
00123
00124 string[] name
00125 float64[] position
00126 float64[] velocity
00127 float64[] effort
00128
00129 ================================================================================
00130 MSG: geometry_msgs/Pose
00131 # A representation of pose in free space, composed of postion and orientation.
00132 Point position
00133 Quaternion orientation
00134
00135 ================================================================================
00136 MSG: geometry_msgs/Point
00137 # This contains the position of a point in free space
00138 float64 x
00139 float64 y
00140 float64 z
00141
00142 ================================================================================
00143 MSG: geometry_msgs/Quaternion
00144 # This represents an orientation in free space in quaternion form.
00145
00146 float64 x
00147 float64 y
00148 float64 z
00149 float64 w
00150
00151 ================================================================================
00152 MSG: object_manipulation_msgs/GraspHandPostureExecutionActionResult
00153 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00154
00155 Header header
00156 actionlib_msgs/GoalStatus status
00157 GraspHandPostureExecutionResult result
00158
00159 ================================================================================
00160 MSG: actionlib_msgs/GoalStatus
00161 GoalID goal_id
00162 uint8 status
00163 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00164 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00165 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00166 # and has since completed its execution (Terminal State)
00167 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00168 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00169 # to some failure (Terminal State)
00170 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00171 # because the goal was unattainable or invalid (Terminal State)
00172 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00173 # and has not yet completed execution
00174 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00175 # but the action server has not yet confirmed that the goal is canceled
00176 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00177 # and was successfully cancelled (Terminal State)
00178 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00179 # sent over the wire by an action server
00180
00181 #Allow for the user to associate a string with GoalStatus for debugging
00182 string text
00183
00184
00185 ================================================================================
00186 MSG: object_manipulation_msgs/GraspHandPostureExecutionResult
00187 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00188 # the result of the action
00189 ManipulationResult result
00190
00191
00192 ================================================================================
00193 MSG: object_manipulation_msgs/ManipulationResult
00194 # Result codes for manipulation tasks
00195
00196 # task completed as expected
00197 # generally means you can proceed as planned
00198 int32 SUCCESS = 1
00199
00200 # task not possible (e.g. out of reach or obstacles in the way)
00201 # generally means that the world was not disturbed, so you can try another task
00202 int32 UNFEASIBLE = -1
00203
00204 # task was thought possible, but failed due to unexpected events during execution
00205 # it is likely that the world was disturbed, so you are encouraged to refresh
00206 # your sensed world model before proceeding to another task
00207 int32 FAILED = -2
00208
00209 # a lower level error prevented task completion (e.g. joint controller not responding)
00210 # generally requires human attention
00211 int32 ERROR = -3
00212
00213 # means that at some point during execution we ended up in a state that the collision-aware
00214 # arm navigation module will not move out of. The world was likely not disturbed, but you
00215 # probably need a new collision map to move the arm out of the stuck position
00216 int32 ARM_MOVEMENT_PREVENTED = -4
00217
00218 # specific to grasp actions
00219 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested
00220 # it is likely that the collision environment will see collisions between the hand/object and the support surface
00221 int32 LIFT_FAILED = -5
00222
00223 # specific to place actions
00224 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested
00225 # it is likely that the collision environment will see collisions between the hand and the object
00226 int32 RETREAT_FAILED = -6
00227
00228 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else"
00229 int32 CANCELLED = -7
00230
00231 # the actual value of this error code
00232 int32 value
00233
00234 ================================================================================
00235 MSG: object_manipulation_msgs/GraspHandPostureExecutionActionFeedback
00236 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00237
00238 Header header
00239 actionlib_msgs/GoalStatus status
00240 GraspHandPostureExecutionFeedback feedback
00241
00242 ================================================================================
00243 MSG: object_manipulation_msgs/GraspHandPostureExecutionFeedback
00244 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00245 # empty for now
00246
00247
00248
00249 """
00250 __slots__ = ['action_goal','action_result','action_feedback']
00251 _slot_types = ['object_manipulation_msgs/GraspHandPostureExecutionActionGoal','object_manipulation_msgs/GraspHandPostureExecutionActionResult','object_manipulation_msgs/GraspHandPostureExecutionActionFeedback']
00252
00253 def __init__(self, *args, **kwds):
00254 """
00255 Constructor. Any message fields that are implicitly/explicitly
00256 set to None will be assigned a default value. The recommend
00257 use is keyword arguments as this is more robust to future message
00258 changes. You cannot mix in-order arguments and keyword arguments.
00259
00260 The available fields are:
00261 action_goal,action_result,action_feedback
00262
00263 @param args: complete set of field values, in .msg order
00264 @param kwds: use keyword arguments corresponding to message field names
00265 to set specific fields.
00266 """
00267 if args or kwds:
00268 super(GraspHandPostureExecutionAction, self).__init__(*args, **kwds)
00269
00270 if self.action_goal is None:
00271 self.action_goal = object_manipulation_msgs.msg.GraspHandPostureExecutionActionGoal()
00272 if self.action_result is None:
00273 self.action_result = object_manipulation_msgs.msg.GraspHandPostureExecutionActionResult()
00274 if self.action_feedback is None:
00275 self.action_feedback = object_manipulation_msgs.msg.GraspHandPostureExecutionActionFeedback()
00276 else:
00277 self.action_goal = object_manipulation_msgs.msg.GraspHandPostureExecutionActionGoal()
00278 self.action_result = object_manipulation_msgs.msg.GraspHandPostureExecutionActionResult()
00279 self.action_feedback = object_manipulation_msgs.msg.GraspHandPostureExecutionActionFeedback()
00280
00281 def _get_types(self):
00282 """
00283 internal API method
00284 """
00285 return self._slot_types
00286
00287 def serialize(self, buff):
00288 """
00289 serialize message into buffer
00290 @param buff: buffer
00291 @type buff: StringIO
00292 """
00293 try:
00294 _x = self
00295 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00296 _x = self.action_goal.header.frame_id
00297 length = len(_x)
00298 buff.write(struct.pack('<I%ss'%length, length, _x))
00299 _x = self
00300 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00301 _x = self.action_goal.goal_id.id
00302 length = len(_x)
00303 buff.write(struct.pack('<I%ss'%length, length, _x))
00304 _x = self
00305 buff.write(_struct_3I.pack(_x.action_goal.goal.grasp.pre_grasp_posture.header.seq, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.nsecs))
00306 _x = self.action_goal.goal.grasp.pre_grasp_posture.header.frame_id
00307 length = len(_x)
00308 buff.write(struct.pack('<I%ss'%length, length, _x))
00309 length = len(self.action_goal.goal.grasp.pre_grasp_posture.name)
00310 buff.write(_struct_I.pack(length))
00311 for val1 in self.action_goal.goal.grasp.pre_grasp_posture.name:
00312 length = len(val1)
00313 buff.write(struct.pack('<I%ss'%length, length, val1))
00314 length = len(self.action_goal.goal.grasp.pre_grasp_posture.position)
00315 buff.write(_struct_I.pack(length))
00316 pattern = '<%sd'%length
00317 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.pre_grasp_posture.position))
00318 length = len(self.action_goal.goal.grasp.pre_grasp_posture.velocity)
00319 buff.write(_struct_I.pack(length))
00320 pattern = '<%sd'%length
00321 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.pre_grasp_posture.velocity))
00322 length = len(self.action_goal.goal.grasp.pre_grasp_posture.effort)
00323 buff.write(_struct_I.pack(length))
00324 pattern = '<%sd'%length
00325 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.pre_grasp_posture.effort))
00326 _x = self
00327 buff.write(_struct_3I.pack(_x.action_goal.goal.grasp.grasp_posture.header.seq, _x.action_goal.goal.grasp.grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.grasp_posture.header.stamp.nsecs))
00328 _x = self.action_goal.goal.grasp.grasp_posture.header.frame_id
00329 length = len(_x)
00330 buff.write(struct.pack('<I%ss'%length, length, _x))
00331 length = len(self.action_goal.goal.grasp.grasp_posture.name)
00332 buff.write(_struct_I.pack(length))
00333 for val1 in self.action_goal.goal.grasp.grasp_posture.name:
00334 length = len(val1)
00335 buff.write(struct.pack('<I%ss'%length, length, val1))
00336 length = len(self.action_goal.goal.grasp.grasp_posture.position)
00337 buff.write(_struct_I.pack(length))
00338 pattern = '<%sd'%length
00339 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.grasp_posture.position))
00340 length = len(self.action_goal.goal.grasp.grasp_posture.velocity)
00341 buff.write(_struct_I.pack(length))
00342 pattern = '<%sd'%length
00343 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.grasp_posture.velocity))
00344 length = len(self.action_goal.goal.grasp.grasp_posture.effort)
00345 buff.write(_struct_I.pack(length))
00346 pattern = '<%sd'%length
00347 buff.write(struct.pack(pattern, *self.action_goal.goal.grasp.grasp_posture.effort))
00348 _x = self
00349 buff.write(_struct_8dBi3I.pack(_x.action_goal.goal.grasp.grasp_pose.position.x, _x.action_goal.goal.grasp.grasp_pose.position.y, _x.action_goal.goal.grasp.grasp_pose.position.z, _x.action_goal.goal.grasp.grasp_pose.orientation.x, _x.action_goal.goal.grasp.grasp_pose.orientation.y, _x.action_goal.goal.grasp.grasp_pose.orientation.z, _x.action_goal.goal.grasp.grasp_pose.orientation.w, _x.action_goal.goal.grasp.success_probability, _x.action_goal.goal.grasp.cluster_rep, _x.action_goal.goal.goal, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00350 _x = self.action_result.header.frame_id
00351 length = len(_x)
00352 buff.write(struct.pack('<I%ss'%length, length, _x))
00353 _x = self
00354 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00355 _x = self.action_result.status.goal_id.id
00356 length = len(_x)
00357 buff.write(struct.pack('<I%ss'%length, length, _x))
00358 buff.write(_struct_B.pack(self.action_result.status.status))
00359 _x = self.action_result.status.text
00360 length = len(_x)
00361 buff.write(struct.pack('<I%ss'%length, length, _x))
00362 _x = self
00363 buff.write(_struct_i3I.pack(_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00364 _x = self.action_feedback.header.frame_id
00365 length = len(_x)
00366 buff.write(struct.pack('<I%ss'%length, length, _x))
00367 _x = self
00368 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00369 _x = self.action_feedback.status.goal_id.id
00370 length = len(_x)
00371 buff.write(struct.pack('<I%ss'%length, length, _x))
00372 buff.write(_struct_B.pack(self.action_feedback.status.status))
00373 _x = self.action_feedback.status.text
00374 length = len(_x)
00375 buff.write(struct.pack('<I%ss'%length, length, _x))
00376 except struct.error, se: self._check_types(se)
00377 except TypeError, te: self._check_types(te)
00378
00379 def deserialize(self, str):
00380 """
00381 unpack serialized message in str into this message instance
00382 @param str: byte array of serialized message
00383 @type str: str
00384 """
00385 try:
00386 if self.action_goal is None:
00387 self.action_goal = object_manipulation_msgs.msg.GraspHandPostureExecutionActionGoal()
00388 if self.action_result is None:
00389 self.action_result = object_manipulation_msgs.msg.GraspHandPostureExecutionActionResult()
00390 if self.action_feedback is None:
00391 self.action_feedback = object_manipulation_msgs.msg.GraspHandPostureExecutionActionFeedback()
00392 end = 0
00393 _x = self
00394 start = end
00395 end += 12
00396 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00397 start = end
00398 end += 4
00399 (length,) = _struct_I.unpack(str[start:end])
00400 start = end
00401 end += length
00402 self.action_goal.header.frame_id = str[start:end]
00403 _x = self
00404 start = end
00405 end += 8
00406 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00407 start = end
00408 end += 4
00409 (length,) = _struct_I.unpack(str[start:end])
00410 start = end
00411 end += length
00412 self.action_goal.goal_id.id = str[start:end]
00413 _x = self
00414 start = end
00415 end += 12
00416 (_x.action_goal.goal.grasp.pre_grasp_posture.header.seq, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00417 start = end
00418 end += 4
00419 (length,) = _struct_I.unpack(str[start:end])
00420 start = end
00421 end += length
00422 self.action_goal.goal.grasp.pre_grasp_posture.header.frame_id = str[start:end]
00423 start = end
00424 end += 4
00425 (length,) = _struct_I.unpack(str[start:end])
00426 self.action_goal.goal.grasp.pre_grasp_posture.name = []
00427 for i in xrange(0, length):
00428 start = end
00429 end += 4
00430 (length,) = _struct_I.unpack(str[start:end])
00431 start = end
00432 end += length
00433 val1 = str[start:end]
00434 self.action_goal.goal.grasp.pre_grasp_posture.name.append(val1)
00435 start = end
00436 end += 4
00437 (length,) = _struct_I.unpack(str[start:end])
00438 pattern = '<%sd'%length
00439 start = end
00440 end += struct.calcsize(pattern)
00441 self.action_goal.goal.grasp.pre_grasp_posture.position = struct.unpack(pattern, str[start:end])
00442 start = end
00443 end += 4
00444 (length,) = _struct_I.unpack(str[start:end])
00445 pattern = '<%sd'%length
00446 start = end
00447 end += struct.calcsize(pattern)
00448 self.action_goal.goal.grasp.pre_grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00449 start = end
00450 end += 4
00451 (length,) = _struct_I.unpack(str[start:end])
00452 pattern = '<%sd'%length
00453 start = end
00454 end += struct.calcsize(pattern)
00455 self.action_goal.goal.grasp.pre_grasp_posture.effort = struct.unpack(pattern, str[start:end])
00456 _x = self
00457 start = end
00458 end += 12
00459 (_x.action_goal.goal.grasp.grasp_posture.header.seq, _x.action_goal.goal.grasp.grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00460 start = end
00461 end += 4
00462 (length,) = _struct_I.unpack(str[start:end])
00463 start = end
00464 end += length
00465 self.action_goal.goal.grasp.grasp_posture.header.frame_id = str[start:end]
00466 start = end
00467 end += 4
00468 (length,) = _struct_I.unpack(str[start:end])
00469 self.action_goal.goal.grasp.grasp_posture.name = []
00470 for i in xrange(0, length):
00471 start = end
00472 end += 4
00473 (length,) = _struct_I.unpack(str[start:end])
00474 start = end
00475 end += length
00476 val1 = str[start:end]
00477 self.action_goal.goal.grasp.grasp_posture.name.append(val1)
00478 start = end
00479 end += 4
00480 (length,) = _struct_I.unpack(str[start:end])
00481 pattern = '<%sd'%length
00482 start = end
00483 end += struct.calcsize(pattern)
00484 self.action_goal.goal.grasp.grasp_posture.position = struct.unpack(pattern, str[start:end])
00485 start = end
00486 end += 4
00487 (length,) = _struct_I.unpack(str[start:end])
00488 pattern = '<%sd'%length
00489 start = end
00490 end += struct.calcsize(pattern)
00491 self.action_goal.goal.grasp.grasp_posture.velocity = struct.unpack(pattern, str[start:end])
00492 start = end
00493 end += 4
00494 (length,) = _struct_I.unpack(str[start:end])
00495 pattern = '<%sd'%length
00496 start = end
00497 end += struct.calcsize(pattern)
00498 self.action_goal.goal.grasp.grasp_posture.effort = struct.unpack(pattern, str[start:end])
00499 _x = self
00500 start = end
00501 end += 81
00502 (_x.action_goal.goal.grasp.grasp_pose.position.x, _x.action_goal.goal.grasp.grasp_pose.position.y, _x.action_goal.goal.grasp.grasp_pose.position.z, _x.action_goal.goal.grasp.grasp_pose.orientation.x, _x.action_goal.goal.grasp.grasp_pose.orientation.y, _x.action_goal.goal.grasp.grasp_pose.orientation.z, _x.action_goal.goal.grasp.grasp_pose.orientation.w, _x.action_goal.goal.grasp.success_probability, _x.action_goal.goal.grasp.cluster_rep, _x.action_goal.goal.goal, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_8dBi3I.unpack(str[start:end])
00503 self.action_goal.goal.grasp.cluster_rep = bool(self.action_goal.goal.grasp.cluster_rep)
00504 start = end
00505 end += 4
00506 (length,) = _struct_I.unpack(str[start:end])
00507 start = end
00508 end += length
00509 self.action_result.header.frame_id = str[start:end]
00510 _x = self
00511 start = end
00512 end += 8
00513 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00514 start = end
00515 end += 4
00516 (length,) = _struct_I.unpack(str[start:end])
00517 start = end
00518 end += length
00519 self.action_result.status.goal_id.id = str[start:end]
00520 start = end
00521 end += 1
00522 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00523 start = end
00524 end += 4
00525 (length,) = _struct_I.unpack(str[start:end])
00526 start = end
00527 end += length
00528 self.action_result.status.text = str[start:end]
00529 _x = self
00530 start = end
00531 end += 16
00532 (_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00533 start = end
00534 end += 4
00535 (length,) = _struct_I.unpack(str[start:end])
00536 start = end
00537 end += length
00538 self.action_feedback.header.frame_id = str[start:end]
00539 _x = self
00540 start = end
00541 end += 8
00542 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00543 start = end
00544 end += 4
00545 (length,) = _struct_I.unpack(str[start:end])
00546 start = end
00547 end += length
00548 self.action_feedback.status.goal_id.id = str[start:end]
00549 start = end
00550 end += 1
00551 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00552 start = end
00553 end += 4
00554 (length,) = _struct_I.unpack(str[start:end])
00555 start = end
00556 end += length
00557 self.action_feedback.status.text = str[start:end]
00558 return self
00559 except struct.error, e:
00560 raise roslib.message.DeserializationError(e)
00561
00562
00563 def serialize_numpy(self, buff, numpy):
00564 """
00565 serialize message with numpy array types into buffer
00566 @param buff: buffer
00567 @type buff: StringIO
00568 @param numpy: numpy python module
00569 @type numpy module
00570 """
00571 try:
00572 _x = self
00573 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00574 _x = self.action_goal.header.frame_id
00575 length = len(_x)
00576 buff.write(struct.pack('<I%ss'%length, length, _x))
00577 _x = self
00578 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00579 _x = self.action_goal.goal_id.id
00580 length = len(_x)
00581 buff.write(struct.pack('<I%ss'%length, length, _x))
00582 _x = self
00583 buff.write(_struct_3I.pack(_x.action_goal.goal.grasp.pre_grasp_posture.header.seq, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.nsecs))
00584 _x = self.action_goal.goal.grasp.pre_grasp_posture.header.frame_id
00585 length = len(_x)
00586 buff.write(struct.pack('<I%ss'%length, length, _x))
00587 length = len(self.action_goal.goal.grasp.pre_grasp_posture.name)
00588 buff.write(_struct_I.pack(length))
00589 for val1 in self.action_goal.goal.grasp.pre_grasp_posture.name:
00590 length = len(val1)
00591 buff.write(struct.pack('<I%ss'%length, length, val1))
00592 length = len(self.action_goal.goal.grasp.pre_grasp_posture.position)
00593 buff.write(_struct_I.pack(length))
00594 pattern = '<%sd'%length
00595 buff.write(self.action_goal.goal.grasp.pre_grasp_posture.position.tostring())
00596 length = len(self.action_goal.goal.grasp.pre_grasp_posture.velocity)
00597 buff.write(_struct_I.pack(length))
00598 pattern = '<%sd'%length
00599 buff.write(self.action_goal.goal.grasp.pre_grasp_posture.velocity.tostring())
00600 length = len(self.action_goal.goal.grasp.pre_grasp_posture.effort)
00601 buff.write(_struct_I.pack(length))
00602 pattern = '<%sd'%length
00603 buff.write(self.action_goal.goal.grasp.pre_grasp_posture.effort.tostring())
00604 _x = self
00605 buff.write(_struct_3I.pack(_x.action_goal.goal.grasp.grasp_posture.header.seq, _x.action_goal.goal.grasp.grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.grasp_posture.header.stamp.nsecs))
00606 _x = self.action_goal.goal.grasp.grasp_posture.header.frame_id
00607 length = len(_x)
00608 buff.write(struct.pack('<I%ss'%length, length, _x))
00609 length = len(self.action_goal.goal.grasp.grasp_posture.name)
00610 buff.write(_struct_I.pack(length))
00611 for val1 in self.action_goal.goal.grasp.grasp_posture.name:
00612 length = len(val1)
00613 buff.write(struct.pack('<I%ss'%length, length, val1))
00614 length = len(self.action_goal.goal.grasp.grasp_posture.position)
00615 buff.write(_struct_I.pack(length))
00616 pattern = '<%sd'%length
00617 buff.write(self.action_goal.goal.grasp.grasp_posture.position.tostring())
00618 length = len(self.action_goal.goal.grasp.grasp_posture.velocity)
00619 buff.write(_struct_I.pack(length))
00620 pattern = '<%sd'%length
00621 buff.write(self.action_goal.goal.grasp.grasp_posture.velocity.tostring())
00622 length = len(self.action_goal.goal.grasp.grasp_posture.effort)
00623 buff.write(_struct_I.pack(length))
00624 pattern = '<%sd'%length
00625 buff.write(self.action_goal.goal.grasp.grasp_posture.effort.tostring())
00626 _x = self
00627 buff.write(_struct_8dBi3I.pack(_x.action_goal.goal.grasp.grasp_pose.position.x, _x.action_goal.goal.grasp.grasp_pose.position.y, _x.action_goal.goal.grasp.grasp_pose.position.z, _x.action_goal.goal.grasp.grasp_pose.orientation.x, _x.action_goal.goal.grasp.grasp_pose.orientation.y, _x.action_goal.goal.grasp.grasp_pose.orientation.z, _x.action_goal.goal.grasp.grasp_pose.orientation.w, _x.action_goal.goal.grasp.success_probability, _x.action_goal.goal.grasp.cluster_rep, _x.action_goal.goal.goal, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00628 _x = self.action_result.header.frame_id
00629 length = len(_x)
00630 buff.write(struct.pack('<I%ss'%length, length, _x))
00631 _x = self
00632 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00633 _x = self.action_result.status.goal_id.id
00634 length = len(_x)
00635 buff.write(struct.pack('<I%ss'%length, length, _x))
00636 buff.write(_struct_B.pack(self.action_result.status.status))
00637 _x = self.action_result.status.text
00638 length = len(_x)
00639 buff.write(struct.pack('<I%ss'%length, length, _x))
00640 _x = self
00641 buff.write(_struct_i3I.pack(_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00642 _x = self.action_feedback.header.frame_id
00643 length = len(_x)
00644 buff.write(struct.pack('<I%ss'%length, length, _x))
00645 _x = self
00646 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00647 _x = self.action_feedback.status.goal_id.id
00648 length = len(_x)
00649 buff.write(struct.pack('<I%ss'%length, length, _x))
00650 buff.write(_struct_B.pack(self.action_feedback.status.status))
00651 _x = self.action_feedback.status.text
00652 length = len(_x)
00653 buff.write(struct.pack('<I%ss'%length, length, _x))
00654 except struct.error, se: self._check_types(se)
00655 except TypeError, te: self._check_types(te)
00656
00657 def deserialize_numpy(self, str, numpy):
00658 """
00659 unpack serialized message in str into this message instance using numpy for array types
00660 @param str: byte array of serialized message
00661 @type str: str
00662 @param numpy: numpy python module
00663 @type numpy: module
00664 """
00665 try:
00666 if self.action_goal is None:
00667 self.action_goal = object_manipulation_msgs.msg.GraspHandPostureExecutionActionGoal()
00668 if self.action_result is None:
00669 self.action_result = object_manipulation_msgs.msg.GraspHandPostureExecutionActionResult()
00670 if self.action_feedback is None:
00671 self.action_feedback = object_manipulation_msgs.msg.GraspHandPostureExecutionActionFeedback()
00672 end = 0
00673 _x = self
00674 start = end
00675 end += 12
00676 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00677 start = end
00678 end += 4
00679 (length,) = _struct_I.unpack(str[start:end])
00680 start = end
00681 end += length
00682 self.action_goal.header.frame_id = str[start:end]
00683 _x = self
00684 start = end
00685 end += 8
00686 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00687 start = end
00688 end += 4
00689 (length,) = _struct_I.unpack(str[start:end])
00690 start = end
00691 end += length
00692 self.action_goal.goal_id.id = str[start:end]
00693 _x = self
00694 start = end
00695 end += 12
00696 (_x.action_goal.goal.grasp.pre_grasp_posture.header.seq, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.pre_grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00697 start = end
00698 end += 4
00699 (length,) = _struct_I.unpack(str[start:end])
00700 start = end
00701 end += length
00702 self.action_goal.goal.grasp.pre_grasp_posture.header.frame_id = str[start:end]
00703 start = end
00704 end += 4
00705 (length,) = _struct_I.unpack(str[start:end])
00706 self.action_goal.goal.grasp.pre_grasp_posture.name = []
00707 for i in xrange(0, length):
00708 start = end
00709 end += 4
00710 (length,) = _struct_I.unpack(str[start:end])
00711 start = end
00712 end += length
00713 val1 = str[start:end]
00714 self.action_goal.goal.grasp.pre_grasp_posture.name.append(val1)
00715 start = end
00716 end += 4
00717 (length,) = _struct_I.unpack(str[start:end])
00718 pattern = '<%sd'%length
00719 start = end
00720 end += struct.calcsize(pattern)
00721 self.action_goal.goal.grasp.pre_grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00722 start = end
00723 end += 4
00724 (length,) = _struct_I.unpack(str[start:end])
00725 pattern = '<%sd'%length
00726 start = end
00727 end += struct.calcsize(pattern)
00728 self.action_goal.goal.grasp.pre_grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00729 start = end
00730 end += 4
00731 (length,) = _struct_I.unpack(str[start:end])
00732 pattern = '<%sd'%length
00733 start = end
00734 end += struct.calcsize(pattern)
00735 self.action_goal.goal.grasp.pre_grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00736 _x = self
00737 start = end
00738 end += 12
00739 (_x.action_goal.goal.grasp.grasp_posture.header.seq, _x.action_goal.goal.grasp.grasp_posture.header.stamp.secs, _x.action_goal.goal.grasp.grasp_posture.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00740 start = end
00741 end += 4
00742 (length,) = _struct_I.unpack(str[start:end])
00743 start = end
00744 end += length
00745 self.action_goal.goal.grasp.grasp_posture.header.frame_id = str[start:end]
00746 start = end
00747 end += 4
00748 (length,) = _struct_I.unpack(str[start:end])
00749 self.action_goal.goal.grasp.grasp_posture.name = []
00750 for i in xrange(0, length):
00751 start = end
00752 end += 4
00753 (length,) = _struct_I.unpack(str[start:end])
00754 start = end
00755 end += length
00756 val1 = str[start:end]
00757 self.action_goal.goal.grasp.grasp_posture.name.append(val1)
00758 start = end
00759 end += 4
00760 (length,) = _struct_I.unpack(str[start:end])
00761 pattern = '<%sd'%length
00762 start = end
00763 end += struct.calcsize(pattern)
00764 self.action_goal.goal.grasp.grasp_posture.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00765 start = end
00766 end += 4
00767 (length,) = _struct_I.unpack(str[start:end])
00768 pattern = '<%sd'%length
00769 start = end
00770 end += struct.calcsize(pattern)
00771 self.action_goal.goal.grasp.grasp_posture.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00772 start = end
00773 end += 4
00774 (length,) = _struct_I.unpack(str[start:end])
00775 pattern = '<%sd'%length
00776 start = end
00777 end += struct.calcsize(pattern)
00778 self.action_goal.goal.grasp.grasp_posture.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00779 _x = self
00780 start = end
00781 end += 81
00782 (_x.action_goal.goal.grasp.grasp_pose.position.x, _x.action_goal.goal.grasp.grasp_pose.position.y, _x.action_goal.goal.grasp.grasp_pose.position.z, _x.action_goal.goal.grasp.grasp_pose.orientation.x, _x.action_goal.goal.grasp.grasp_pose.orientation.y, _x.action_goal.goal.grasp.grasp_pose.orientation.z, _x.action_goal.goal.grasp.grasp_pose.orientation.w, _x.action_goal.goal.grasp.success_probability, _x.action_goal.goal.grasp.cluster_rep, _x.action_goal.goal.goal, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_8dBi3I.unpack(str[start:end])
00783 self.action_goal.goal.grasp.cluster_rep = bool(self.action_goal.goal.grasp.cluster_rep)
00784 start = end
00785 end += 4
00786 (length,) = _struct_I.unpack(str[start:end])
00787 start = end
00788 end += length
00789 self.action_result.header.frame_id = str[start:end]
00790 _x = self
00791 start = end
00792 end += 8
00793 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00794 start = end
00795 end += 4
00796 (length,) = _struct_I.unpack(str[start:end])
00797 start = end
00798 end += length
00799 self.action_result.status.goal_id.id = str[start:end]
00800 start = end
00801 end += 1
00802 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00803 start = end
00804 end += 4
00805 (length,) = _struct_I.unpack(str[start:end])
00806 start = end
00807 end += length
00808 self.action_result.status.text = str[start:end]
00809 _x = self
00810 start = end
00811 end += 16
00812 (_x.action_result.result.result.value, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00813 start = end
00814 end += 4
00815 (length,) = _struct_I.unpack(str[start:end])
00816 start = end
00817 end += length
00818 self.action_feedback.header.frame_id = str[start:end]
00819 _x = self
00820 start = end
00821 end += 8
00822 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00823 start = end
00824 end += 4
00825 (length,) = _struct_I.unpack(str[start:end])
00826 start = end
00827 end += length
00828 self.action_feedback.status.goal_id.id = str[start:end]
00829 start = end
00830 end += 1
00831 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00832 start = end
00833 end += 4
00834 (length,) = _struct_I.unpack(str[start:end])
00835 start = end
00836 end += length
00837 self.action_feedback.status.text = str[start:end]
00838 return self
00839 except struct.error, e:
00840 raise roslib.message.DeserializationError(e)
00841
00842 _struct_I = roslib.message.struct_I
00843 _struct_8dBi3I = struct.Struct("<8dBi3I")
00844 _struct_3I = struct.Struct("<3I")
00845 _struct_B = struct.Struct("<B")
00846 _struct_2I = struct.Struct("<2I")
00847 _struct_i3I = struct.Struct("<i3I")