00001 """autogenerated by genmsg_py from PlaceActionResult.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import object_manipulation_msgs.msg
00007 import roslib.rostime
00008 import actionlib_msgs.msg
00009 import std_msgs.msg
00010
00011 class PlaceActionResult(roslib.message.Message):
00012 _md5sum = "df8a4d17f57aaf41c7039f0808224d11"
00013 _type = "object_manipulation_msgs/PlaceActionResult"
00014 _has_header = True
00015 _full_text = """
00016 Header header
00017 actionlib_msgs/GoalStatus status
00018 PlaceResult result
00019
00020 ================================================================================
00021 MSG: std_msgs/Header
00022 # Standard metadata for higher-level stamped data types.
00023 # This is generally used to communicate timestamped data
00024 # in a particular coordinate frame.
00025 #
00026 # sequence ID: consecutively increasing ID
00027 uint32 seq
00028 #Two-integer timestamp that is expressed as:
00029 # * stamp.secs: seconds (stamp_secs) since epoch
00030 # * stamp.nsecs: nanoseconds since stamp_secs
00031 # time-handling sugar is provided by the client library
00032 time stamp
00033 #Frame this data is associated with
00034 # 0: no frame
00035 # 1: global frame
00036 string frame_id
00037
00038 ================================================================================
00039 MSG: actionlib_msgs/GoalStatus
00040 GoalID goal_id
00041 uint8 status
00042 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00043 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00044 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00045 # and has since completed its execution (Terminal State)
00046 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00047 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00048 # to some failure (Terminal State)
00049 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00050 # because the goal was unattainable or invalid (Terminal State)
00051 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00052 # and has not yet completed execution
00053 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00054 # but the action server has not yet confirmed that the goal is canceled
00055 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00056 # and was successfully cancelled (Terminal State)
00057 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00058 # sent over the wire by an action server
00059
00060 #Allow for the user to associate a string with GoalStatus for debugging
00061 string text
00062
00063
00064 ================================================================================
00065 MSG: actionlib_msgs/GoalID
00066 # The stamp should store the time at which this goal was requested.
00067 # It is used by an action server when it tries to preempt all
00068 # goals that were requested before a certain time
00069 time stamp
00070
00071 # The id provides a way to associate feedback and
00072 # result message with specific goal requests. The id
00073 # specified must be unique.
00074 string id
00075
00076
00077 ================================================================================
00078 MSG: object_manipulation_msgs/PlaceResult
00079 # The result of the pickup attempt
00080 ManipulationResult manipulation_result
00081
00082 # The successful place location, if any
00083 geometry_msgs/PoseStamped place_location
00084
00085 # the list of attempted locations, in the order in which they were attempted
00086 # the successful one should be the last one in this list
00087 geometry_msgs/PoseStamped[] attempted_locations
00088
00089 # the outcomes of the attempted locations, in the same order as attempted_locations
00090 PlaceLocationResult[] attempted_location_results
00091 ================================================================================
00092 MSG: object_manipulation_msgs/ManipulationResult
00093 # Result codes for manipulation tasks
00094
00095 # task completed as expected
00096 # generally means you can proceed as planned
00097 int32 SUCCESS = 1
00098
00099 # task not possible (e.g. out of reach or obstacles in the way)
00100 # generally means that the world was not disturbed, so you can try another task
00101 int32 UNFEASIBLE = -1
00102
00103 # task was thought possible, but failed due to unexpected events during execution
00104 # it is likely that the world was disturbed, so you are encouraged to refresh
00105 # your sensed world model before proceeding to another task
00106 int32 FAILED = -2
00107
00108 # a lower level error prevented task completion (e.g. joint controller not responding)
00109 # generally requires human attention
00110 int32 ERROR = -3
00111
00112 # means that at some point during execution we ended up in a state that the collision-aware
00113 # arm navigation module will not move out of. The world was likely not disturbed, but you
00114 # probably need a new collision map to move the arm out of the stuck position
00115 int32 ARM_MOVEMENT_PREVENTED = -4
00116
00117 # specific to grasp actions
00118 # the object was grasped successfully, but the lift attempt could not achieve the minimum lift distance requested
00119 # it is likely that the collision environment will see collisions between the hand/object and the support surface
00120 int32 LIFT_FAILED = -5
00121
00122 # specific to place actions
00123 # the object was placed successfully, but the retreat attempt could not achieve the minimum retreat distance requested
00124 # it is likely that the collision environment will see collisions between the hand and the object
00125 int32 RETREAT_FAILED = -6
00126
00127 # indicates that somewhere along the line a human said "wait, stop, this is bad, go back and do something else"
00128 int32 CANCELLED = -7
00129
00130 # the actual value of this error code
00131 int32 value
00132
00133 ================================================================================
00134 MSG: geometry_msgs/PoseStamped
00135 # A Pose with reference coordinate frame and timestamp
00136 Header header
00137 Pose pose
00138
00139 ================================================================================
00140 MSG: geometry_msgs/Pose
00141 # A representation of pose in free space, composed of postion and orientation.
00142 Point position
00143 Quaternion orientation
00144
00145 ================================================================================
00146 MSG: geometry_msgs/Point
00147 # This contains the position of a point in free space
00148 float64 x
00149 float64 y
00150 float64 z
00151
00152 ================================================================================
00153 MSG: geometry_msgs/Quaternion
00154 # This represents an orientation in free space in quaternion form.
00155
00156 float64 x
00157 float64 y
00158 float64 z
00159 float64 w
00160
00161 ================================================================================
00162 MSG: object_manipulation_msgs/PlaceLocationResult
00163 int32 SUCCESS = 1
00164 int32 PLACE_OUT_OF_REACH = 2
00165 int32 PLACE_IN_COLLISION = 3
00166 int32 PLACE_UNFEASIBLE = 4
00167 int32 PREPLACE_OUT_OF_REACH = 5
00168 int32 PREPLACE_IN_COLLISION = 6
00169 int32 PREPLACE_UNFEASIBLE = 7
00170 int32 RETREAT_OUT_OF_REACH = 8
00171 int32 RETREAT_IN_COLLISION = 9
00172 int32 RETREAT_UNFEASIBLE = 10
00173 int32 MOVE_ARM_FAILED = 11
00174 int32 PLACE_FAILED = 12
00175 int32 RETREAT_FAILED = 13
00176 int32 result_code
00177
00178 # whether the state of the world was disturbed by this attempt. generally, this flag
00179 # shows if another task can be attempted, or a new sensed world model is recommeded
00180 # before proceeding
00181 bool continuation_possible
00182
00183 """
00184 __slots__ = ['header','status','result']
00185 _slot_types = ['Header','actionlib_msgs/GoalStatus','object_manipulation_msgs/PlaceResult']
00186
00187 def __init__(self, *args, **kwds):
00188 """
00189 Constructor. Any message fields that are implicitly/explicitly
00190 set to None will be assigned a default value. The recommend
00191 use is keyword arguments as this is more robust to future message
00192 changes. You cannot mix in-order arguments and keyword arguments.
00193
00194 The available fields are:
00195 header,status,result
00196
00197 @param args: complete set of field values, in .msg order
00198 @param kwds: use keyword arguments corresponding to message field names
00199 to set specific fields.
00200 """
00201 if args or kwds:
00202 super(PlaceActionResult, self).__init__(*args, **kwds)
00203
00204 if self.header is None:
00205 self.header = std_msgs.msg._Header.Header()
00206 if self.status is None:
00207 self.status = actionlib_msgs.msg.GoalStatus()
00208 if self.result is None:
00209 self.result = object_manipulation_msgs.msg.PlaceResult()
00210 else:
00211 self.header = std_msgs.msg._Header.Header()
00212 self.status = actionlib_msgs.msg.GoalStatus()
00213 self.result = object_manipulation_msgs.msg.PlaceResult()
00214
00215 def _get_types(self):
00216 """
00217 internal API method
00218 """
00219 return self._slot_types
00220
00221 def serialize(self, buff):
00222 """
00223 serialize message into buffer
00224 @param buff: buffer
00225 @type buff: StringIO
00226 """
00227 try:
00228 _x = self
00229 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00230 _x = self.header.frame_id
00231 length = len(_x)
00232 buff.write(struct.pack('<I%ss'%length, length, _x))
00233 _x = self
00234 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00235 _x = self.status.goal_id.id
00236 length = len(_x)
00237 buff.write(struct.pack('<I%ss'%length, length, _x))
00238 buff.write(_struct_B.pack(self.status.status))
00239 _x = self.status.text
00240 length = len(_x)
00241 buff.write(struct.pack('<I%ss'%length, length, _x))
00242 _x = self
00243 buff.write(_struct_i3I.pack(_x.result.manipulation_result.value, _x.result.place_location.header.seq, _x.result.place_location.header.stamp.secs, _x.result.place_location.header.stamp.nsecs))
00244 _x = self.result.place_location.header.frame_id
00245 length = len(_x)
00246 buff.write(struct.pack('<I%ss'%length, length, _x))
00247 _x = self
00248 buff.write(_struct_7d.pack(_x.result.place_location.pose.position.x, _x.result.place_location.pose.position.y, _x.result.place_location.pose.position.z, _x.result.place_location.pose.orientation.x, _x.result.place_location.pose.orientation.y, _x.result.place_location.pose.orientation.z, _x.result.place_location.pose.orientation.w))
00249 length = len(self.result.attempted_locations)
00250 buff.write(_struct_I.pack(length))
00251 for val1 in self.result.attempted_locations:
00252 _v1 = val1.header
00253 buff.write(_struct_I.pack(_v1.seq))
00254 _v2 = _v1.stamp
00255 _x = _v2
00256 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00257 _x = _v1.frame_id
00258 length = len(_x)
00259 buff.write(struct.pack('<I%ss'%length, length, _x))
00260 _v3 = val1.pose
00261 _v4 = _v3.position
00262 _x = _v4
00263 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00264 _v5 = _v3.orientation
00265 _x = _v5
00266 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00267 length = len(self.result.attempted_location_results)
00268 buff.write(_struct_I.pack(length))
00269 for val1 in self.result.attempted_location_results:
00270 _x = val1
00271 buff.write(_struct_iB.pack(_x.result_code, _x.continuation_possible))
00272 except struct.error, se: self._check_types(se)
00273 except TypeError, te: self._check_types(te)
00274
00275 def deserialize(self, str):
00276 """
00277 unpack serialized message in str into this message instance
00278 @param str: byte array of serialized message
00279 @type str: str
00280 """
00281 try:
00282 if self.header is None:
00283 self.header = std_msgs.msg._Header.Header()
00284 if self.status is None:
00285 self.status = actionlib_msgs.msg.GoalStatus()
00286 if self.result is None:
00287 self.result = object_manipulation_msgs.msg.PlaceResult()
00288 end = 0
00289 _x = self
00290 start = end
00291 end += 12
00292 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00293 start = end
00294 end += 4
00295 (length,) = _struct_I.unpack(str[start:end])
00296 start = end
00297 end += length
00298 self.header.frame_id = str[start:end]
00299 _x = self
00300 start = end
00301 end += 8
00302 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00303 start = end
00304 end += 4
00305 (length,) = _struct_I.unpack(str[start:end])
00306 start = end
00307 end += length
00308 self.status.goal_id.id = str[start:end]
00309 start = end
00310 end += 1
00311 (self.status.status,) = _struct_B.unpack(str[start:end])
00312 start = end
00313 end += 4
00314 (length,) = _struct_I.unpack(str[start:end])
00315 start = end
00316 end += length
00317 self.status.text = str[start:end]
00318 _x = self
00319 start = end
00320 end += 16
00321 (_x.result.manipulation_result.value, _x.result.place_location.header.seq, _x.result.place_location.header.stamp.secs, _x.result.place_location.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00322 start = end
00323 end += 4
00324 (length,) = _struct_I.unpack(str[start:end])
00325 start = end
00326 end += length
00327 self.result.place_location.header.frame_id = str[start:end]
00328 _x = self
00329 start = end
00330 end += 56
00331 (_x.result.place_location.pose.position.x, _x.result.place_location.pose.position.y, _x.result.place_location.pose.position.z, _x.result.place_location.pose.orientation.x, _x.result.place_location.pose.orientation.y, _x.result.place_location.pose.orientation.z, _x.result.place_location.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00332 start = end
00333 end += 4
00334 (length,) = _struct_I.unpack(str[start:end])
00335 self.result.attempted_locations = []
00336 for i in xrange(0, length):
00337 val1 = geometry_msgs.msg.PoseStamped()
00338 _v6 = val1.header
00339 start = end
00340 end += 4
00341 (_v6.seq,) = _struct_I.unpack(str[start:end])
00342 _v7 = _v6.stamp
00343 _x = _v7
00344 start = end
00345 end += 8
00346 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00347 start = end
00348 end += 4
00349 (length,) = _struct_I.unpack(str[start:end])
00350 start = end
00351 end += length
00352 _v6.frame_id = str[start:end]
00353 _v8 = val1.pose
00354 _v9 = _v8.position
00355 _x = _v9
00356 start = end
00357 end += 24
00358 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00359 _v10 = _v8.orientation
00360 _x = _v10
00361 start = end
00362 end += 32
00363 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00364 self.result.attempted_locations.append(val1)
00365 start = end
00366 end += 4
00367 (length,) = _struct_I.unpack(str[start:end])
00368 self.result.attempted_location_results = []
00369 for i in xrange(0, length):
00370 val1 = object_manipulation_msgs.msg.PlaceLocationResult()
00371 _x = val1
00372 start = end
00373 end += 5
00374 (_x.result_code, _x.continuation_possible,) = _struct_iB.unpack(str[start:end])
00375 val1.continuation_possible = bool(val1.continuation_possible)
00376 self.result.attempted_location_results.append(val1)
00377 return self
00378 except struct.error, e:
00379 raise roslib.message.DeserializationError(e)
00380
00381
00382 def serialize_numpy(self, buff, numpy):
00383 """
00384 serialize message with numpy array types into buffer
00385 @param buff: buffer
00386 @type buff: StringIO
00387 @param numpy: numpy python module
00388 @type numpy module
00389 """
00390 try:
00391 _x = self
00392 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00393 _x = self.header.frame_id
00394 length = len(_x)
00395 buff.write(struct.pack('<I%ss'%length, length, _x))
00396 _x = self
00397 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00398 _x = self.status.goal_id.id
00399 length = len(_x)
00400 buff.write(struct.pack('<I%ss'%length, length, _x))
00401 buff.write(_struct_B.pack(self.status.status))
00402 _x = self.status.text
00403 length = len(_x)
00404 buff.write(struct.pack('<I%ss'%length, length, _x))
00405 _x = self
00406 buff.write(_struct_i3I.pack(_x.result.manipulation_result.value, _x.result.place_location.header.seq, _x.result.place_location.header.stamp.secs, _x.result.place_location.header.stamp.nsecs))
00407 _x = self.result.place_location.header.frame_id
00408 length = len(_x)
00409 buff.write(struct.pack('<I%ss'%length, length, _x))
00410 _x = self
00411 buff.write(_struct_7d.pack(_x.result.place_location.pose.position.x, _x.result.place_location.pose.position.y, _x.result.place_location.pose.position.z, _x.result.place_location.pose.orientation.x, _x.result.place_location.pose.orientation.y, _x.result.place_location.pose.orientation.z, _x.result.place_location.pose.orientation.w))
00412 length = len(self.result.attempted_locations)
00413 buff.write(_struct_I.pack(length))
00414 for val1 in self.result.attempted_locations:
00415 _v11 = val1.header
00416 buff.write(_struct_I.pack(_v11.seq))
00417 _v12 = _v11.stamp
00418 _x = _v12
00419 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00420 _x = _v11.frame_id
00421 length = len(_x)
00422 buff.write(struct.pack('<I%ss'%length, length, _x))
00423 _v13 = val1.pose
00424 _v14 = _v13.position
00425 _x = _v14
00426 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00427 _v15 = _v13.orientation
00428 _x = _v15
00429 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00430 length = len(self.result.attempted_location_results)
00431 buff.write(_struct_I.pack(length))
00432 for val1 in self.result.attempted_location_results:
00433 _x = val1
00434 buff.write(_struct_iB.pack(_x.result_code, _x.continuation_possible))
00435 except struct.error, se: self._check_types(se)
00436 except TypeError, te: self._check_types(te)
00437
00438 def deserialize_numpy(self, str, numpy):
00439 """
00440 unpack serialized message in str into this message instance using numpy for array types
00441 @param str: byte array of serialized message
00442 @type str: str
00443 @param numpy: numpy python module
00444 @type numpy: module
00445 """
00446 try:
00447 if self.header is None:
00448 self.header = std_msgs.msg._Header.Header()
00449 if self.status is None:
00450 self.status = actionlib_msgs.msg.GoalStatus()
00451 if self.result is None:
00452 self.result = object_manipulation_msgs.msg.PlaceResult()
00453 end = 0
00454 _x = self
00455 start = end
00456 end += 12
00457 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00458 start = end
00459 end += 4
00460 (length,) = _struct_I.unpack(str[start:end])
00461 start = end
00462 end += length
00463 self.header.frame_id = str[start:end]
00464 _x = self
00465 start = end
00466 end += 8
00467 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00468 start = end
00469 end += 4
00470 (length,) = _struct_I.unpack(str[start:end])
00471 start = end
00472 end += length
00473 self.status.goal_id.id = str[start:end]
00474 start = end
00475 end += 1
00476 (self.status.status,) = _struct_B.unpack(str[start:end])
00477 start = end
00478 end += 4
00479 (length,) = _struct_I.unpack(str[start:end])
00480 start = end
00481 end += length
00482 self.status.text = str[start:end]
00483 _x = self
00484 start = end
00485 end += 16
00486 (_x.result.manipulation_result.value, _x.result.place_location.header.seq, _x.result.place_location.header.stamp.secs, _x.result.place_location.header.stamp.nsecs,) = _struct_i3I.unpack(str[start:end])
00487 start = end
00488 end += 4
00489 (length,) = _struct_I.unpack(str[start:end])
00490 start = end
00491 end += length
00492 self.result.place_location.header.frame_id = str[start:end]
00493 _x = self
00494 start = end
00495 end += 56
00496 (_x.result.place_location.pose.position.x, _x.result.place_location.pose.position.y, _x.result.place_location.pose.position.z, _x.result.place_location.pose.orientation.x, _x.result.place_location.pose.orientation.y, _x.result.place_location.pose.orientation.z, _x.result.place_location.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00497 start = end
00498 end += 4
00499 (length,) = _struct_I.unpack(str[start:end])
00500 self.result.attempted_locations = []
00501 for i in xrange(0, length):
00502 val1 = geometry_msgs.msg.PoseStamped()
00503 _v16 = val1.header
00504 start = end
00505 end += 4
00506 (_v16.seq,) = _struct_I.unpack(str[start:end])
00507 _v17 = _v16.stamp
00508 _x = _v17
00509 start = end
00510 end += 8
00511 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00512 start = end
00513 end += 4
00514 (length,) = _struct_I.unpack(str[start:end])
00515 start = end
00516 end += length
00517 _v16.frame_id = str[start:end]
00518 _v18 = val1.pose
00519 _v19 = _v18.position
00520 _x = _v19
00521 start = end
00522 end += 24
00523 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00524 _v20 = _v18.orientation
00525 _x = _v20
00526 start = end
00527 end += 32
00528 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00529 self.result.attempted_locations.append(val1)
00530 start = end
00531 end += 4
00532 (length,) = _struct_I.unpack(str[start:end])
00533 self.result.attempted_location_results = []
00534 for i in xrange(0, length):
00535 val1 = object_manipulation_msgs.msg.PlaceLocationResult()
00536 _x = val1
00537 start = end
00538 end += 5
00539 (_x.result_code, _x.continuation_possible,) = _struct_iB.unpack(str[start:end])
00540 val1.continuation_possible = bool(val1.continuation_possible)
00541 self.result.attempted_location_results.append(val1)
00542 return self
00543 except struct.error, e:
00544 raise roslib.message.DeserializationError(e)
00545
00546 _struct_I = roslib.message.struct_I
00547 _struct_B = struct.Struct("<B")
00548 _struct_i3I = struct.Struct("<i3I")
00549 _struct_3I = struct.Struct("<3I")
00550 _struct_7d = struct.Struct("<7d")
00551 _struct_4d = struct.Struct("<4d")
00552 _struct_iB = struct.Struct("<iB")
00553 _struct_2I = struct.Struct("<2I")
00554 _struct_3d = struct.Struct("<3d")