00001 """autogenerated by genmsg_py from ArmHandAction.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import roslib.rostime
00006 import actionlib_msgs.msg
00007 import geometry_msgs.msg
00008 import vision_msgs.msg
00009 import cogman_msgs.msg
00010 import std_msgs.msg
00011
00012 class ArmHandAction(roslib.message.Message):
00013 _md5sum = "47caad1eeab6545c2c3e92dff9f336b8"
00014 _type = "cogman_msgs/ArmHandAction"
00015 _has_header = False
00016 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00017
00018 ArmHandActionGoal action_goal
00019 ArmHandActionResult action_result
00020 ArmHandActionFeedback action_feedback
00021
00022 ================================================================================
00023 MSG: cogman_msgs/ArmHandActionGoal
00024 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00025
00026 Header header
00027 actionlib_msgs/GoalID goal_id
00028 ArmHandGoal 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: cogman_msgs/ArmHandGoal
00063 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00064 string command # 'arm_cart_loid', 'arm_cart_pose', 'arm_cart_name', 'arm_joints', 'arm_joint_name', 'reach_primitive', 'hand_primitive', 'lift', 'put_down'
00065 string pose_name # When moving to pre-defined poses, cointains the name
00066 float32[] joint_angles # If command is 'arm_joints', the joint angles
00067 geometry_msgs/Pose end_effector_pose # command=arm_cart_pose: where the arm should go
00068 uint64 end_effector_loid # one lo_id where the arm should go
00069 string hand_primitive # Allowed strings: open open_thumb90 3pinch 2pinch cup_top peace handshake noop. Used when command is 'finger_primitive'
00070 string object_type # If command is 'reach_primitive', it will define how to grasp (orientation ...)
00071 uint64[] obstacle_ids # List of lo_id's corresponding to obstacles
00072 float32 distance # For reach_primitive: distance from grasp point to approach point (m). For 'lift', distance to lift up (m)
00073 float32 supporting_plane # Height of the table (m)
00074
00075 ================================================================================
00076 MSG: geometry_msgs/Pose
00077 # A representation of pose in free space, composed of postion and orientation.
00078 Point position
00079 Quaternion orientation
00080
00081 ================================================================================
00082 MSG: geometry_msgs/Point
00083 # This contains the position of a point in free space
00084 float64 x
00085 float64 y
00086 float64 z
00087
00088 ================================================================================
00089 MSG: geometry_msgs/Quaternion
00090 # This represents an orientation in free space in quaternion form.
00091
00092 float64 x
00093 float64 y
00094 float64 z
00095 float64 w
00096
00097 ================================================================================
00098 MSG: cogman_msgs/ArmHandActionResult
00099 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00100
00101 Header header
00102 actionlib_msgs/GoalStatus status
00103 ArmHandResult result
00104
00105 ================================================================================
00106 MSG: actionlib_msgs/GoalStatus
00107 GoalID goal_id
00108 uint8 status
00109 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00110 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00111 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00112 # and has since completed its execution (Terminal State)
00113 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00114 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00115 # to some failure (Terminal State)
00116 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00117 # because the goal was unattainable or invalid (Terminal State)
00118 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00119 # and has not yet completed execution
00120 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00121 # but the action server has not yet confirmed that the goal is canceled
00122 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00123 # and was successfully cancelled (Terminal State)
00124 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00125 # sent over the wire by an action server
00126
00127 #Allow for the user to associate a string with GoalStatus for debugging
00128 string text
00129
00130
00131 ================================================================================
00132 MSG: cogman_msgs/ArmHandResult
00133 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00134
00135 #result
00136 float32 distance_to_goal
00137 string situation #Allowed: grasped slipped released unreachable ik_deadlock need_to_move_base
00138 vision_msgs/system_error error #Description of error
00139 uint64[] better_base_ids #List of lo_id's where we could grasp better
00140
00141 ================================================================================
00142 MSG: vision_msgs/system_error
00143 uint64 MANIPULATION_POSE_UNREACHABLE = 64
00144 uint64 GRASP_FAILED = 128 # Grasp into the void
00145 uint64 OBJECT_NOT_FOUND = 256
00146 uint64 VISION_PRIMITIVE_FAILED = 512
00147 uint64 CONTRADICTING_TACTILE_FEEDBACK = 1024 # Collide without expecting it
00148 uint64 CONTRADICTING_VISION_RESULTS = 2048
00149 uint64 GRASP_FAILED_AND_CRASHED = 4096 # Throwing something out of the way
00150 uint64 JLO_ERROR = 8192 # Could not get position
00151 uint64 VECTOR_FIELD_CANT_REACH = 16384 # The arm got stuck along the way, did not reach the final grasping pose
00152
00153 uint64 error_id # One of the error constants defined above
00154 string node_name # The node causing this error
00155 string error_description # Further information about the error
00156
00157 ================================================================================
00158 MSG: cogman_msgs/ArmHandActionFeedback
00159 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00160
00161 Header header
00162 actionlib_msgs/GoalStatus status
00163 ArmHandFeedback feedback
00164
00165 ================================================================================
00166 MSG: cogman_msgs/ArmHandFeedback
00167 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00168 #feedback
00169 float32 distance_to_goal
00170
00171
00172
00173 """
00174 __slots__ = ['action_goal','action_result','action_feedback']
00175 _slot_types = ['cogman_msgs/ArmHandActionGoal','cogman_msgs/ArmHandActionResult','cogman_msgs/ArmHandActionFeedback']
00176
00177 def __init__(self, *args, **kwds):
00178 """
00179 Constructor. Any message fields that are implicitly/explicitly
00180 set to None will be assigned a default value. The recommend
00181 use is keyword arguments as this is more robust to future message
00182 changes. You cannot mix in-order arguments and keyword arguments.
00183
00184 The available fields are:
00185 action_goal,action_result,action_feedback
00186
00187 @param args: complete set of field values, in .msg order
00188 @param kwds: use keyword arguments corresponding to message field names
00189 to set specific fields.
00190 """
00191 if args or kwds:
00192 super(ArmHandAction, self).__init__(*args, **kwds)
00193
00194 if self.action_goal is None:
00195 self.action_goal = cogman_msgs.msg.ArmHandActionGoal()
00196 if self.action_result is None:
00197 self.action_result = cogman_msgs.msg.ArmHandActionResult()
00198 if self.action_feedback is None:
00199 self.action_feedback = cogman_msgs.msg.ArmHandActionFeedback()
00200 else:
00201 self.action_goal = cogman_msgs.msg.ArmHandActionGoal()
00202 self.action_result = cogman_msgs.msg.ArmHandActionResult()
00203 self.action_feedback = cogman_msgs.msg.ArmHandActionFeedback()
00204
00205 def _get_types(self):
00206 """
00207 internal API method
00208 """
00209 return self._slot_types
00210
00211 def serialize(self, buff):
00212 """
00213 serialize message into buffer
00214 @param buff: buffer
00215 @type buff: StringIO
00216 """
00217 try:
00218 _x = self
00219 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00220 _x = self.action_goal.header.frame_id
00221 length = len(_x)
00222 buff.write(struct.pack('<I%ss'%length, length, _x))
00223 _x = self
00224 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00225 _x = self.action_goal.goal_id.id
00226 length = len(_x)
00227 buff.write(struct.pack('<I%ss'%length, length, _x))
00228 _x = self.action_goal.goal.command
00229 length = len(_x)
00230 buff.write(struct.pack('<I%ss'%length, length, _x))
00231 _x = self.action_goal.goal.pose_name
00232 length = len(_x)
00233 buff.write(struct.pack('<I%ss'%length, length, _x))
00234 length = len(self.action_goal.goal.joint_angles)
00235 buff.write(_struct_I.pack(length))
00236 pattern = '<%sf'%length
00237 buff.write(struct.pack(pattern, *self.action_goal.goal.joint_angles))
00238 _x = self
00239 buff.write(_struct_7dQ.pack(_x.action_goal.goal.end_effector_pose.position.x, _x.action_goal.goal.end_effector_pose.position.y, _x.action_goal.goal.end_effector_pose.position.z, _x.action_goal.goal.end_effector_pose.orientation.x, _x.action_goal.goal.end_effector_pose.orientation.y, _x.action_goal.goal.end_effector_pose.orientation.z, _x.action_goal.goal.end_effector_pose.orientation.w, _x.action_goal.goal.end_effector_loid))
00240 _x = self.action_goal.goal.hand_primitive
00241 length = len(_x)
00242 buff.write(struct.pack('<I%ss'%length, length, _x))
00243 _x = self.action_goal.goal.object_type
00244 length = len(_x)
00245 buff.write(struct.pack('<I%ss'%length, length, _x))
00246 length = len(self.action_goal.goal.obstacle_ids)
00247 buff.write(_struct_I.pack(length))
00248 pattern = '<%sQ'%length
00249 buff.write(struct.pack(pattern, *self.action_goal.goal.obstacle_ids))
00250 _x = self
00251 buff.write(_struct_2f3I.pack(_x.action_goal.goal.distance, _x.action_goal.goal.supporting_plane, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00252 _x = self.action_result.header.frame_id
00253 length = len(_x)
00254 buff.write(struct.pack('<I%ss'%length, length, _x))
00255 _x = self
00256 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00257 _x = self.action_result.status.goal_id.id
00258 length = len(_x)
00259 buff.write(struct.pack('<I%ss'%length, length, _x))
00260 buff.write(_struct_B.pack(self.action_result.status.status))
00261 _x = self.action_result.status.text
00262 length = len(_x)
00263 buff.write(struct.pack('<I%ss'%length, length, _x))
00264 buff.write(_struct_f.pack(self.action_result.result.distance_to_goal))
00265 _x = self.action_result.result.situation
00266 length = len(_x)
00267 buff.write(struct.pack('<I%ss'%length, length, _x))
00268 buff.write(_struct_Q.pack(self.action_result.result.error.error_id))
00269 _x = self.action_result.result.error.node_name
00270 length = len(_x)
00271 buff.write(struct.pack('<I%ss'%length, length, _x))
00272 _x = self.action_result.result.error.error_description
00273 length = len(_x)
00274 buff.write(struct.pack('<I%ss'%length, length, _x))
00275 length = len(self.action_result.result.better_base_ids)
00276 buff.write(_struct_I.pack(length))
00277 pattern = '<%sQ'%length
00278 buff.write(struct.pack(pattern, *self.action_result.result.better_base_ids))
00279 _x = self
00280 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00281 _x = self.action_feedback.header.frame_id
00282 length = len(_x)
00283 buff.write(struct.pack('<I%ss'%length, length, _x))
00284 _x = self
00285 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00286 _x = self.action_feedback.status.goal_id.id
00287 length = len(_x)
00288 buff.write(struct.pack('<I%ss'%length, length, _x))
00289 buff.write(_struct_B.pack(self.action_feedback.status.status))
00290 _x = self.action_feedback.status.text
00291 length = len(_x)
00292 buff.write(struct.pack('<I%ss'%length, length, _x))
00293 buff.write(_struct_f.pack(self.action_feedback.feedback.distance_to_goal))
00294 except struct.error, se: self._check_types(se)
00295 except TypeError, te: self._check_types(te)
00296
00297 def deserialize(self, str):
00298 """
00299 unpack serialized message in str into this message instance
00300 @param str: byte array of serialized message
00301 @type str: str
00302 """
00303 try:
00304 if self.action_goal is None:
00305 self.action_goal = cogman_msgs.msg.ArmHandActionGoal()
00306 if self.action_result is None:
00307 self.action_result = cogman_msgs.msg.ArmHandActionResult()
00308 if self.action_feedback is None:
00309 self.action_feedback = cogman_msgs.msg.ArmHandActionFeedback()
00310 end = 0
00311 _x = self
00312 start = end
00313 end += 12
00314 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 start = end
00319 end += length
00320 self.action_goal.header.frame_id = str[start:end]
00321 _x = self
00322 start = end
00323 end += 8
00324 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00325 start = end
00326 end += 4
00327 (length,) = _struct_I.unpack(str[start:end])
00328 start = end
00329 end += length
00330 self.action_goal.goal_id.id = str[start:end]
00331 start = end
00332 end += 4
00333 (length,) = _struct_I.unpack(str[start:end])
00334 start = end
00335 end += length
00336 self.action_goal.goal.command = str[start:end]
00337 start = end
00338 end += 4
00339 (length,) = _struct_I.unpack(str[start:end])
00340 start = end
00341 end += length
00342 self.action_goal.goal.pose_name = str[start:end]
00343 start = end
00344 end += 4
00345 (length,) = _struct_I.unpack(str[start:end])
00346 pattern = '<%sf'%length
00347 start = end
00348 end += struct.calcsize(pattern)
00349 self.action_goal.goal.joint_angles = struct.unpack(pattern, str[start:end])
00350 _x = self
00351 start = end
00352 end += 64
00353 (_x.action_goal.goal.end_effector_pose.position.x, _x.action_goal.goal.end_effector_pose.position.y, _x.action_goal.goal.end_effector_pose.position.z, _x.action_goal.goal.end_effector_pose.orientation.x, _x.action_goal.goal.end_effector_pose.orientation.y, _x.action_goal.goal.end_effector_pose.orientation.z, _x.action_goal.goal.end_effector_pose.orientation.w, _x.action_goal.goal.end_effector_loid,) = _struct_7dQ.unpack(str[start:end])
00354 start = end
00355 end += 4
00356 (length,) = _struct_I.unpack(str[start:end])
00357 start = end
00358 end += length
00359 self.action_goal.goal.hand_primitive = str[start:end]
00360 start = end
00361 end += 4
00362 (length,) = _struct_I.unpack(str[start:end])
00363 start = end
00364 end += length
00365 self.action_goal.goal.object_type = str[start:end]
00366 start = end
00367 end += 4
00368 (length,) = _struct_I.unpack(str[start:end])
00369 pattern = '<%sQ'%length
00370 start = end
00371 end += struct.calcsize(pattern)
00372 self.action_goal.goal.obstacle_ids = struct.unpack(pattern, str[start:end])
00373 _x = self
00374 start = end
00375 end += 20
00376 (_x.action_goal.goal.distance, _x.action_goal.goal.supporting_plane, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_2f3I.unpack(str[start:end])
00377 start = end
00378 end += 4
00379 (length,) = _struct_I.unpack(str[start:end])
00380 start = end
00381 end += length
00382 self.action_result.header.frame_id = str[start:end]
00383 _x = self
00384 start = end
00385 end += 8
00386 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00387 start = end
00388 end += 4
00389 (length,) = _struct_I.unpack(str[start:end])
00390 start = end
00391 end += length
00392 self.action_result.status.goal_id.id = str[start:end]
00393 start = end
00394 end += 1
00395 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00396 start = end
00397 end += 4
00398 (length,) = _struct_I.unpack(str[start:end])
00399 start = end
00400 end += length
00401 self.action_result.status.text = str[start:end]
00402 start = end
00403 end += 4
00404 (self.action_result.result.distance_to_goal,) = _struct_f.unpack(str[start:end])
00405 start = end
00406 end += 4
00407 (length,) = _struct_I.unpack(str[start:end])
00408 start = end
00409 end += length
00410 self.action_result.result.situation = str[start:end]
00411 start = end
00412 end += 8
00413 (self.action_result.result.error.error_id,) = _struct_Q.unpack(str[start:end])
00414 start = end
00415 end += 4
00416 (length,) = _struct_I.unpack(str[start:end])
00417 start = end
00418 end += length
00419 self.action_result.result.error.node_name = str[start:end]
00420 start = end
00421 end += 4
00422 (length,) = _struct_I.unpack(str[start:end])
00423 start = end
00424 end += length
00425 self.action_result.result.error.error_description = str[start:end]
00426 start = end
00427 end += 4
00428 (length,) = _struct_I.unpack(str[start:end])
00429 pattern = '<%sQ'%length
00430 start = end
00431 end += struct.calcsize(pattern)
00432 self.action_result.result.better_base_ids = struct.unpack(pattern, str[start:end])
00433 _x = self
00434 start = end
00435 end += 12
00436 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00437 start = end
00438 end += 4
00439 (length,) = _struct_I.unpack(str[start:end])
00440 start = end
00441 end += length
00442 self.action_feedback.header.frame_id = str[start:end]
00443 _x = self
00444 start = end
00445 end += 8
00446 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00447 start = end
00448 end += 4
00449 (length,) = _struct_I.unpack(str[start:end])
00450 start = end
00451 end += length
00452 self.action_feedback.status.goal_id.id = str[start:end]
00453 start = end
00454 end += 1
00455 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00456 start = end
00457 end += 4
00458 (length,) = _struct_I.unpack(str[start:end])
00459 start = end
00460 end += length
00461 self.action_feedback.status.text = str[start:end]
00462 start = end
00463 end += 4
00464 (self.action_feedback.feedback.distance_to_goal,) = _struct_f.unpack(str[start:end])
00465 return self
00466 except struct.error, e:
00467 raise roslib.message.DeserializationError(e)
00468
00469
00470 def serialize_numpy(self, buff, numpy):
00471 """
00472 serialize message with numpy array types into buffer
00473 @param buff: buffer
00474 @type buff: StringIO
00475 @param numpy: numpy python module
00476 @type numpy module
00477 """
00478 try:
00479 _x = self
00480 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00481 _x = self.action_goal.header.frame_id
00482 length = len(_x)
00483 buff.write(struct.pack('<I%ss'%length, length, _x))
00484 _x = self
00485 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00486 _x = self.action_goal.goal_id.id
00487 length = len(_x)
00488 buff.write(struct.pack('<I%ss'%length, length, _x))
00489 _x = self.action_goal.goal.command
00490 length = len(_x)
00491 buff.write(struct.pack('<I%ss'%length, length, _x))
00492 _x = self.action_goal.goal.pose_name
00493 length = len(_x)
00494 buff.write(struct.pack('<I%ss'%length, length, _x))
00495 length = len(self.action_goal.goal.joint_angles)
00496 buff.write(_struct_I.pack(length))
00497 pattern = '<%sf'%length
00498 buff.write(self.action_goal.goal.joint_angles.tostring())
00499 _x = self
00500 buff.write(_struct_7dQ.pack(_x.action_goal.goal.end_effector_pose.position.x, _x.action_goal.goal.end_effector_pose.position.y, _x.action_goal.goal.end_effector_pose.position.z, _x.action_goal.goal.end_effector_pose.orientation.x, _x.action_goal.goal.end_effector_pose.orientation.y, _x.action_goal.goal.end_effector_pose.orientation.z, _x.action_goal.goal.end_effector_pose.orientation.w, _x.action_goal.goal.end_effector_loid))
00501 _x = self.action_goal.goal.hand_primitive
00502 length = len(_x)
00503 buff.write(struct.pack('<I%ss'%length, length, _x))
00504 _x = self.action_goal.goal.object_type
00505 length = len(_x)
00506 buff.write(struct.pack('<I%ss'%length, length, _x))
00507 length = len(self.action_goal.goal.obstacle_ids)
00508 buff.write(_struct_I.pack(length))
00509 pattern = '<%sQ'%length
00510 buff.write(self.action_goal.goal.obstacle_ids.tostring())
00511 _x = self
00512 buff.write(_struct_2f3I.pack(_x.action_goal.goal.distance, _x.action_goal.goal.supporting_plane, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00513 _x = self.action_result.header.frame_id
00514 length = len(_x)
00515 buff.write(struct.pack('<I%ss'%length, length, _x))
00516 _x = self
00517 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00518 _x = self.action_result.status.goal_id.id
00519 length = len(_x)
00520 buff.write(struct.pack('<I%ss'%length, length, _x))
00521 buff.write(_struct_B.pack(self.action_result.status.status))
00522 _x = self.action_result.status.text
00523 length = len(_x)
00524 buff.write(struct.pack('<I%ss'%length, length, _x))
00525 buff.write(_struct_f.pack(self.action_result.result.distance_to_goal))
00526 _x = self.action_result.result.situation
00527 length = len(_x)
00528 buff.write(struct.pack('<I%ss'%length, length, _x))
00529 buff.write(_struct_Q.pack(self.action_result.result.error.error_id))
00530 _x = self.action_result.result.error.node_name
00531 length = len(_x)
00532 buff.write(struct.pack('<I%ss'%length, length, _x))
00533 _x = self.action_result.result.error.error_description
00534 length = len(_x)
00535 buff.write(struct.pack('<I%ss'%length, length, _x))
00536 length = len(self.action_result.result.better_base_ids)
00537 buff.write(_struct_I.pack(length))
00538 pattern = '<%sQ'%length
00539 buff.write(self.action_result.result.better_base_ids.tostring())
00540 _x = self
00541 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00542 _x = self.action_feedback.header.frame_id
00543 length = len(_x)
00544 buff.write(struct.pack('<I%ss'%length, length, _x))
00545 _x = self
00546 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00547 _x = self.action_feedback.status.goal_id.id
00548 length = len(_x)
00549 buff.write(struct.pack('<I%ss'%length, length, _x))
00550 buff.write(_struct_B.pack(self.action_feedback.status.status))
00551 _x = self.action_feedback.status.text
00552 length = len(_x)
00553 buff.write(struct.pack('<I%ss'%length, length, _x))
00554 buff.write(_struct_f.pack(self.action_feedback.feedback.distance_to_goal))
00555 except struct.error, se: self._check_types(se)
00556 except TypeError, te: self._check_types(te)
00557
00558 def deserialize_numpy(self, str, numpy):
00559 """
00560 unpack serialized message in str into this message instance using numpy for array types
00561 @param str: byte array of serialized message
00562 @type str: str
00563 @param numpy: numpy python module
00564 @type numpy: module
00565 """
00566 try:
00567 if self.action_goal is None:
00568 self.action_goal = cogman_msgs.msg.ArmHandActionGoal()
00569 if self.action_result is None:
00570 self.action_result = cogman_msgs.msg.ArmHandActionResult()
00571 if self.action_feedback is None:
00572 self.action_feedback = cogman_msgs.msg.ArmHandActionFeedback()
00573 end = 0
00574 _x = self
00575 start = end
00576 end += 12
00577 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00578 start = end
00579 end += 4
00580 (length,) = _struct_I.unpack(str[start:end])
00581 start = end
00582 end += length
00583 self.action_goal.header.frame_id = str[start:end]
00584 _x = self
00585 start = end
00586 end += 8
00587 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00588 start = end
00589 end += 4
00590 (length,) = _struct_I.unpack(str[start:end])
00591 start = end
00592 end += length
00593 self.action_goal.goal_id.id = str[start:end]
00594 start = end
00595 end += 4
00596 (length,) = _struct_I.unpack(str[start:end])
00597 start = end
00598 end += length
00599 self.action_goal.goal.command = str[start:end]
00600 start = end
00601 end += 4
00602 (length,) = _struct_I.unpack(str[start:end])
00603 start = end
00604 end += length
00605 self.action_goal.goal.pose_name = str[start:end]
00606 start = end
00607 end += 4
00608 (length,) = _struct_I.unpack(str[start:end])
00609 pattern = '<%sf'%length
00610 start = end
00611 end += struct.calcsize(pattern)
00612 self.action_goal.goal.joint_angles = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00613 _x = self
00614 start = end
00615 end += 64
00616 (_x.action_goal.goal.end_effector_pose.position.x, _x.action_goal.goal.end_effector_pose.position.y, _x.action_goal.goal.end_effector_pose.position.z, _x.action_goal.goal.end_effector_pose.orientation.x, _x.action_goal.goal.end_effector_pose.orientation.y, _x.action_goal.goal.end_effector_pose.orientation.z, _x.action_goal.goal.end_effector_pose.orientation.w, _x.action_goal.goal.end_effector_loid,) = _struct_7dQ.unpack(str[start:end])
00617 start = end
00618 end += 4
00619 (length,) = _struct_I.unpack(str[start:end])
00620 start = end
00621 end += length
00622 self.action_goal.goal.hand_primitive = str[start:end]
00623 start = end
00624 end += 4
00625 (length,) = _struct_I.unpack(str[start:end])
00626 start = end
00627 end += length
00628 self.action_goal.goal.object_type = str[start:end]
00629 start = end
00630 end += 4
00631 (length,) = _struct_I.unpack(str[start:end])
00632 pattern = '<%sQ'%length
00633 start = end
00634 end += struct.calcsize(pattern)
00635 self.action_goal.goal.obstacle_ids = numpy.frombuffer(str[start:end], dtype=numpy.uint64, count=length)
00636 _x = self
00637 start = end
00638 end += 20
00639 (_x.action_goal.goal.distance, _x.action_goal.goal.supporting_plane, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_2f3I.unpack(str[start:end])
00640 start = end
00641 end += 4
00642 (length,) = _struct_I.unpack(str[start:end])
00643 start = end
00644 end += length
00645 self.action_result.header.frame_id = str[start:end]
00646 _x = self
00647 start = end
00648 end += 8
00649 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00650 start = end
00651 end += 4
00652 (length,) = _struct_I.unpack(str[start:end])
00653 start = end
00654 end += length
00655 self.action_result.status.goal_id.id = str[start:end]
00656 start = end
00657 end += 1
00658 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00659 start = end
00660 end += 4
00661 (length,) = _struct_I.unpack(str[start:end])
00662 start = end
00663 end += length
00664 self.action_result.status.text = str[start:end]
00665 start = end
00666 end += 4
00667 (self.action_result.result.distance_to_goal,) = _struct_f.unpack(str[start:end])
00668 start = end
00669 end += 4
00670 (length,) = _struct_I.unpack(str[start:end])
00671 start = end
00672 end += length
00673 self.action_result.result.situation = str[start:end]
00674 start = end
00675 end += 8
00676 (self.action_result.result.error.error_id,) = _struct_Q.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_result.result.error.node_name = str[start:end]
00683 start = end
00684 end += 4
00685 (length,) = _struct_I.unpack(str[start:end])
00686 start = end
00687 end += length
00688 self.action_result.result.error.error_description = str[start:end]
00689 start = end
00690 end += 4
00691 (length,) = _struct_I.unpack(str[start:end])
00692 pattern = '<%sQ'%length
00693 start = end
00694 end += struct.calcsize(pattern)
00695 self.action_result.result.better_base_ids = numpy.frombuffer(str[start:end], dtype=numpy.uint64, count=length)
00696 _x = self
00697 start = end
00698 end += 12
00699 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00700 start = end
00701 end += 4
00702 (length,) = _struct_I.unpack(str[start:end])
00703 start = end
00704 end += length
00705 self.action_feedback.header.frame_id = str[start:end]
00706 _x = self
00707 start = end
00708 end += 8
00709 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00710 start = end
00711 end += 4
00712 (length,) = _struct_I.unpack(str[start:end])
00713 start = end
00714 end += length
00715 self.action_feedback.status.goal_id.id = str[start:end]
00716 start = end
00717 end += 1
00718 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00719 start = end
00720 end += 4
00721 (length,) = _struct_I.unpack(str[start:end])
00722 start = end
00723 end += length
00724 self.action_feedback.status.text = str[start:end]
00725 start = end
00726 end += 4
00727 (self.action_feedback.feedback.distance_to_goal,) = _struct_f.unpack(str[start:end])
00728 return self
00729 except struct.error, e:
00730 raise roslib.message.DeserializationError(e)
00731
00732 _struct_I = roslib.message.struct_I
00733 _struct_B = struct.Struct("<B")
00734 _struct_2f3I = struct.Struct("<2f3I")
00735 _struct_f = struct.Struct("<f")
00736 _struct_Q = struct.Struct("<Q")
00737 _struct_7dQ = struct.Struct("<7dQ")
00738 _struct_3I = struct.Struct("<3I")
00739 _struct_2I = struct.Struct("<2I")