00001 """autogenerated by genpy from tidyup_msgs/PlaceObjectAction.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007 import arm_navigation_msgs.msg
00008 import actionlib_msgs.msg
00009 import tidyup_msgs.msg
00010 import geometry_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013
00014 class PlaceObjectAction(genpy.Message):
00015 _md5sum = "d748498a1bb99fff32807855d8d37608"
00016 _type = "tidyup_msgs/PlaceObjectAction"
00017 _has_header = False
00018 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00019
00020 PlaceObjectActionGoal action_goal
00021 PlaceObjectActionResult action_result
00022 PlaceObjectActionFeedback action_feedback
00023
00024 ================================================================================
00025 MSG: tidyup_msgs/PlaceObjectActionGoal
00026 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00027
00028 Header header
00029 actionlib_msgs/GoalID goal_id
00030 PlaceObjectGoal goal
00031
00032 ================================================================================
00033 MSG: std_msgs/Header
00034 # Standard metadata for higher-level stamped data types.
00035 # This is generally used to communicate timestamped data
00036 # in a particular coordinate frame.
00037 #
00038 # sequence ID: consecutively increasing ID
00039 uint32 seq
00040 #Two-integer timestamp that is expressed as:
00041 # * stamp.secs: seconds (stamp_secs) since epoch
00042 # * stamp.nsecs: nanoseconds since stamp_secs
00043 # time-handling sugar is provided by the client library
00044 time stamp
00045 #Frame this data is associated with
00046 # 0: no frame
00047 # 1: global frame
00048 string frame_id
00049
00050 ================================================================================
00051 MSG: actionlib_msgs/GoalID
00052 # The stamp should store the time at which this goal was requested.
00053 # It is used by an action server when it tries to preempt all
00054 # goals that were requested before a certain time
00055 time stamp
00056
00057 # The id provides a way to associate feedback and
00058 # result message with specific goal requests. The id
00059 # specified must be unique.
00060 string id
00061
00062
00063 ================================================================================
00064 MSG: tidyup_msgs/PlaceObjectGoal
00065 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00066 # name of the table or shelf
00067 string static_object
00068 # name of the object to place
00069 string putdown_object
00070 # name of the arm, which holds the object
00071 string arm
00072
00073 ================================================================================
00074 MSG: tidyup_msgs/PlaceObjectActionResult
00075 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00076
00077 Header header
00078 actionlib_msgs/GoalStatus status
00079 PlaceObjectResult result
00080
00081 ================================================================================
00082 MSG: actionlib_msgs/GoalStatus
00083 GoalID goal_id
00084 uint8 status
00085 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00086 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00087 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00088 # and has since completed its execution (Terminal State)
00089 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00090 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00091 # to some failure (Terminal State)
00092 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00093 # because the goal was unattainable or invalid (Terminal State)
00094 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00095 # and has not yet completed execution
00096 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00097 # but the action server has not yet confirmed that the goal is canceled
00098 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00099 # and was successfully cancelled (Terminal State)
00100 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00101 # sent over the wire by an action server
00102
00103 #Allow for the user to associate a string with GoalStatus for debugging
00104 string text
00105
00106
00107 ================================================================================
00108 MSG: tidyup_msgs/PlaceObjectResult
00109 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00110 # the new pose of the object
00111 geometry_msgs/PoseStamped putdown_pose
00112 arm_navigation_msgs/ArmNavigationErrorCodes error_code
00113
00114 ================================================================================
00115 MSG: geometry_msgs/PoseStamped
00116 # A Pose with reference coordinate frame and timestamp
00117 Header header
00118 Pose pose
00119
00120 ================================================================================
00121 MSG: geometry_msgs/Pose
00122 # A representation of pose in free space, composed of postion and orientation.
00123 Point position
00124 Quaternion orientation
00125
00126 ================================================================================
00127 MSG: geometry_msgs/Point
00128 # This contains the position of a point in free space
00129 float64 x
00130 float64 y
00131 float64 z
00132
00133 ================================================================================
00134 MSG: geometry_msgs/Quaternion
00135 # This represents an orientation in free space in quaternion form.
00136
00137 float64 x
00138 float64 y
00139 float64 z
00140 float64 w
00141
00142 ================================================================================
00143 MSG: arm_navigation_msgs/ArmNavigationErrorCodes
00144 int32 val
00145
00146 # overall behavior
00147 int32 PLANNING_FAILED=-1
00148 int32 SUCCESS=1
00149 int32 TIMED_OUT=-2
00150
00151 # start state errors
00152 int32 START_STATE_IN_COLLISION=-3
00153 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
00154
00155 # goal errors
00156 int32 GOAL_IN_COLLISION=-5
00157 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
00158
00159 # robot state
00160 int32 INVALID_ROBOT_STATE=-7
00161 int32 INCOMPLETE_ROBOT_STATE=-8
00162
00163 # planning request errors
00164 int32 INVALID_PLANNER_ID=-9
00165 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
00166 int32 INVALID_ALLOWED_PLANNING_TIME=-11
00167 int32 INVALID_GROUP_NAME=-12
00168 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
00169 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
00170 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
00171 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
00172 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
00173 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
00174
00175 # state/trajectory monitor errors
00176 int32 INVALID_TRAJECTORY=-19
00177 int32 INVALID_INDEX=-20
00178 int32 JOINT_LIMITS_VIOLATED=-21
00179 int32 PATH_CONSTRAINTS_VIOLATED=-22
00180 int32 COLLISION_CONSTRAINTS_VIOLATED=-23
00181 int32 GOAL_CONSTRAINTS_VIOLATED=-24
00182 int32 JOINTS_NOT_MOVING=-25
00183 int32 TRAJECTORY_CONTROLLER_FAILED=-26
00184
00185 # system errors
00186 int32 FRAME_TRANSFORM_FAILURE=-27
00187 int32 COLLISION_CHECKING_UNAVAILABLE=-28
00188 int32 ROBOT_STATE_STALE=-29
00189 int32 SENSOR_INFO_STALE=-30
00190
00191 # kinematics errors
00192 int32 NO_IK_SOLUTION=-31
00193 int32 INVALID_LINK_NAME=-32
00194 int32 IK_LINK_IN_COLLISION=-33
00195 int32 NO_FK_SOLUTION=-34
00196 int32 KINEMATICS_STATE_IN_COLLISION=-35
00197
00198 # general errors
00199 int32 INVALID_TIMEOUT=-36
00200
00201
00202 ================================================================================
00203 MSG: tidyup_msgs/PlaceObjectActionFeedback
00204 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00205
00206 Header header
00207 actionlib_msgs/GoalStatus status
00208 PlaceObjectFeedback feedback
00209
00210 ================================================================================
00211 MSG: tidyup_msgs/PlaceObjectFeedback
00212 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00213
00214
00215 """
00216 __slots__ = ['action_goal','action_result','action_feedback']
00217 _slot_types = ['tidyup_msgs/PlaceObjectActionGoal','tidyup_msgs/PlaceObjectActionResult','tidyup_msgs/PlaceObjectActionFeedback']
00218
00219 def __init__(self, *args, **kwds):
00220 """
00221 Constructor. Any message fields that are implicitly/explicitly
00222 set to None will be assigned a default value. The recommend
00223 use is keyword arguments as this is more robust to future message
00224 changes. You cannot mix in-order arguments and keyword arguments.
00225
00226 The available fields are:
00227 action_goal,action_result,action_feedback
00228
00229 :param args: complete set of field values, in .msg order
00230 :param kwds: use keyword arguments corresponding to message field names
00231 to set specific fields.
00232 """
00233 if args or kwds:
00234 super(PlaceObjectAction, self).__init__(*args, **kwds)
00235
00236 if self.action_goal is None:
00237 self.action_goal = tidyup_msgs.msg.PlaceObjectActionGoal()
00238 if self.action_result is None:
00239 self.action_result = tidyup_msgs.msg.PlaceObjectActionResult()
00240 if self.action_feedback is None:
00241 self.action_feedback = tidyup_msgs.msg.PlaceObjectActionFeedback()
00242 else:
00243 self.action_goal = tidyup_msgs.msg.PlaceObjectActionGoal()
00244 self.action_result = tidyup_msgs.msg.PlaceObjectActionResult()
00245 self.action_feedback = tidyup_msgs.msg.PlaceObjectActionFeedback()
00246
00247 def _get_types(self):
00248 """
00249 internal API method
00250 """
00251 return self._slot_types
00252
00253 def serialize(self, buff):
00254 """
00255 serialize message into buffer
00256 :param buff: buffer, ``StringIO``
00257 """
00258 try:
00259 _x = self
00260 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00261 _x = self.action_goal.header.frame_id
00262 length = len(_x)
00263 if python3 or type(_x) == unicode:
00264 _x = _x.encode('utf-8')
00265 length = len(_x)
00266 buff.write(struct.pack('<I%ss'%length, length, _x))
00267 _x = self
00268 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00269 _x = self.action_goal.goal_id.id
00270 length = len(_x)
00271 if python3 or type(_x) == unicode:
00272 _x = _x.encode('utf-8')
00273 length = len(_x)
00274 buff.write(struct.pack('<I%ss'%length, length, _x))
00275 _x = self.action_goal.goal.static_object
00276 length = len(_x)
00277 if python3 or type(_x) == unicode:
00278 _x = _x.encode('utf-8')
00279 length = len(_x)
00280 buff.write(struct.pack('<I%ss'%length, length, _x))
00281 _x = self.action_goal.goal.putdown_object
00282 length = len(_x)
00283 if python3 or type(_x) == unicode:
00284 _x = _x.encode('utf-8')
00285 length = len(_x)
00286 buff.write(struct.pack('<I%ss'%length, length, _x))
00287 _x = self.action_goal.goal.arm
00288 length = len(_x)
00289 if python3 or type(_x) == unicode:
00290 _x = _x.encode('utf-8')
00291 length = len(_x)
00292 buff.write(struct.pack('<I%ss'%length, length, _x))
00293 _x = self
00294 buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00295 _x = self.action_result.header.frame_id
00296 length = len(_x)
00297 if python3 or type(_x) == unicode:
00298 _x = _x.encode('utf-8')
00299 length = len(_x)
00300 buff.write(struct.pack('<I%ss'%length, length, _x))
00301 _x = self
00302 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00303 _x = self.action_result.status.goal_id.id
00304 length = len(_x)
00305 if python3 or type(_x) == unicode:
00306 _x = _x.encode('utf-8')
00307 length = len(_x)
00308 buff.write(struct.pack('<I%ss'%length, length, _x))
00309 buff.write(_struct_B.pack(self.action_result.status.status))
00310 _x = self.action_result.status.text
00311 length = len(_x)
00312 if python3 or type(_x) == unicode:
00313 _x = _x.encode('utf-8')
00314 length = len(_x)
00315 buff.write(struct.pack('<I%ss'%length, length, _x))
00316 _x = self
00317 buff.write(_struct_3I.pack(_x.action_result.result.putdown_pose.header.seq, _x.action_result.result.putdown_pose.header.stamp.secs, _x.action_result.result.putdown_pose.header.stamp.nsecs))
00318 _x = self.action_result.result.putdown_pose.header.frame_id
00319 length = len(_x)
00320 if python3 or type(_x) == unicode:
00321 _x = _x.encode('utf-8')
00322 length = len(_x)
00323 buff.write(struct.pack('<I%ss'%length, length, _x))
00324 _x = self
00325 buff.write(_struct_7di3I.pack(_x.action_result.result.putdown_pose.pose.position.x, _x.action_result.result.putdown_pose.pose.position.y, _x.action_result.result.putdown_pose.pose.position.z, _x.action_result.result.putdown_pose.pose.orientation.x, _x.action_result.result.putdown_pose.pose.orientation.y, _x.action_result.result.putdown_pose.pose.orientation.z, _x.action_result.result.putdown_pose.pose.orientation.w, _x.action_result.result.error_code.val, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00326 _x = self.action_feedback.header.frame_id
00327 length = len(_x)
00328 if python3 or type(_x) == unicode:
00329 _x = _x.encode('utf-8')
00330 length = len(_x)
00331 buff.write(struct.pack('<I%ss'%length, length, _x))
00332 _x = self
00333 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00334 _x = self.action_feedback.status.goal_id.id
00335 length = len(_x)
00336 if python3 or type(_x) == unicode:
00337 _x = _x.encode('utf-8')
00338 length = len(_x)
00339 buff.write(struct.pack('<I%ss'%length, length, _x))
00340 buff.write(_struct_B.pack(self.action_feedback.status.status))
00341 _x = self.action_feedback.status.text
00342 length = len(_x)
00343 if python3 or type(_x) == unicode:
00344 _x = _x.encode('utf-8')
00345 length = len(_x)
00346 buff.write(struct.pack('<I%ss'%length, length, _x))
00347 except struct.error as se: self._check_types(se)
00348 except TypeError as te: self._check_types(te)
00349
00350 def deserialize(self, str):
00351 """
00352 unpack serialized message in str into this message instance
00353 :param str: byte array of serialized message, ``str``
00354 """
00355 try:
00356 if self.action_goal is None:
00357 self.action_goal = tidyup_msgs.msg.PlaceObjectActionGoal()
00358 if self.action_result is None:
00359 self.action_result = tidyup_msgs.msg.PlaceObjectActionResult()
00360 if self.action_feedback is None:
00361 self.action_feedback = tidyup_msgs.msg.PlaceObjectActionFeedback()
00362 end = 0
00363 _x = self
00364 start = end
00365 end += 12
00366 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00367 start = end
00368 end += 4
00369 (length,) = _struct_I.unpack(str[start:end])
00370 start = end
00371 end += length
00372 if python3:
00373 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00374 else:
00375 self.action_goal.header.frame_id = str[start:end]
00376 _x = self
00377 start = end
00378 end += 8
00379 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00380 start = end
00381 end += 4
00382 (length,) = _struct_I.unpack(str[start:end])
00383 start = end
00384 end += length
00385 if python3:
00386 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00387 else:
00388 self.action_goal.goal_id.id = str[start:end]
00389 start = end
00390 end += 4
00391 (length,) = _struct_I.unpack(str[start:end])
00392 start = end
00393 end += length
00394 if python3:
00395 self.action_goal.goal.static_object = str[start:end].decode('utf-8')
00396 else:
00397 self.action_goal.goal.static_object = str[start:end]
00398 start = end
00399 end += 4
00400 (length,) = _struct_I.unpack(str[start:end])
00401 start = end
00402 end += length
00403 if python3:
00404 self.action_goal.goal.putdown_object = str[start:end].decode('utf-8')
00405 else:
00406 self.action_goal.goal.putdown_object = str[start:end]
00407 start = end
00408 end += 4
00409 (length,) = _struct_I.unpack(str[start:end])
00410 start = end
00411 end += length
00412 if python3:
00413 self.action_goal.goal.arm = str[start:end].decode('utf-8')
00414 else:
00415 self.action_goal.goal.arm = str[start:end]
00416 _x = self
00417 start = end
00418 end += 12
00419 (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00420 start = end
00421 end += 4
00422 (length,) = _struct_I.unpack(str[start:end])
00423 start = end
00424 end += length
00425 if python3:
00426 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00427 else:
00428 self.action_result.header.frame_id = str[start:end]
00429 _x = self
00430 start = end
00431 end += 8
00432 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00433 start = end
00434 end += 4
00435 (length,) = _struct_I.unpack(str[start:end])
00436 start = end
00437 end += length
00438 if python3:
00439 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00440 else:
00441 self.action_result.status.goal_id.id = str[start:end]
00442 start = end
00443 end += 1
00444 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00445 start = end
00446 end += 4
00447 (length,) = _struct_I.unpack(str[start:end])
00448 start = end
00449 end += length
00450 if python3:
00451 self.action_result.status.text = str[start:end].decode('utf-8')
00452 else:
00453 self.action_result.status.text = str[start:end]
00454 _x = self
00455 start = end
00456 end += 12
00457 (_x.action_result.result.putdown_pose.header.seq, _x.action_result.result.putdown_pose.header.stamp.secs, _x.action_result.result.putdown_pose.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 if python3:
00464 self.action_result.result.putdown_pose.header.frame_id = str[start:end].decode('utf-8')
00465 else:
00466 self.action_result.result.putdown_pose.header.frame_id = str[start:end]
00467 _x = self
00468 start = end
00469 end += 72
00470 (_x.action_result.result.putdown_pose.pose.position.x, _x.action_result.result.putdown_pose.pose.position.y, _x.action_result.result.putdown_pose.pose.position.z, _x.action_result.result.putdown_pose.pose.orientation.x, _x.action_result.result.putdown_pose.pose.orientation.y, _x.action_result.result.putdown_pose.pose.orientation.z, _x.action_result.result.putdown_pose.pose.orientation.w, _x.action_result.result.error_code.val, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_7di3I.unpack(str[start:end])
00471 start = end
00472 end += 4
00473 (length,) = _struct_I.unpack(str[start:end])
00474 start = end
00475 end += length
00476 if python3:
00477 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00478 else:
00479 self.action_feedback.header.frame_id = str[start:end]
00480 _x = self
00481 start = end
00482 end += 8
00483 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00484 start = end
00485 end += 4
00486 (length,) = _struct_I.unpack(str[start:end])
00487 start = end
00488 end += length
00489 if python3:
00490 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00491 else:
00492 self.action_feedback.status.goal_id.id = str[start:end]
00493 start = end
00494 end += 1
00495 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00496 start = end
00497 end += 4
00498 (length,) = _struct_I.unpack(str[start:end])
00499 start = end
00500 end += length
00501 if python3:
00502 self.action_feedback.status.text = str[start:end].decode('utf-8')
00503 else:
00504 self.action_feedback.status.text = str[start:end]
00505 return self
00506 except struct.error as e:
00507 raise genpy.DeserializationError(e)
00508
00509
00510 def serialize_numpy(self, buff, numpy):
00511 """
00512 serialize message with numpy array types into buffer
00513 :param buff: buffer, ``StringIO``
00514 :param numpy: numpy python module
00515 """
00516 try:
00517 _x = self
00518 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00519 _x = self.action_goal.header.frame_id
00520 length = len(_x)
00521 if python3 or type(_x) == unicode:
00522 _x = _x.encode('utf-8')
00523 length = len(_x)
00524 buff.write(struct.pack('<I%ss'%length, length, _x))
00525 _x = self
00526 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00527 _x = self.action_goal.goal_id.id
00528 length = len(_x)
00529 if python3 or type(_x) == unicode:
00530 _x = _x.encode('utf-8')
00531 length = len(_x)
00532 buff.write(struct.pack('<I%ss'%length, length, _x))
00533 _x = self.action_goal.goal.static_object
00534 length = len(_x)
00535 if python3 or type(_x) == unicode:
00536 _x = _x.encode('utf-8')
00537 length = len(_x)
00538 buff.write(struct.pack('<I%ss'%length, length, _x))
00539 _x = self.action_goal.goal.putdown_object
00540 length = len(_x)
00541 if python3 or type(_x) == unicode:
00542 _x = _x.encode('utf-8')
00543 length = len(_x)
00544 buff.write(struct.pack('<I%ss'%length, length, _x))
00545 _x = self.action_goal.goal.arm
00546 length = len(_x)
00547 if python3 or type(_x) == unicode:
00548 _x = _x.encode('utf-8')
00549 length = len(_x)
00550 buff.write(struct.pack('<I%ss'%length, length, _x))
00551 _x = self
00552 buff.write(_struct_3I.pack(_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00553 _x = self.action_result.header.frame_id
00554 length = len(_x)
00555 if python3 or type(_x) == unicode:
00556 _x = _x.encode('utf-8')
00557 length = len(_x)
00558 buff.write(struct.pack('<I%ss'%length, length, _x))
00559 _x = self
00560 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00561 _x = self.action_result.status.goal_id.id
00562 length = len(_x)
00563 if python3 or type(_x) == unicode:
00564 _x = _x.encode('utf-8')
00565 length = len(_x)
00566 buff.write(struct.pack('<I%ss'%length, length, _x))
00567 buff.write(_struct_B.pack(self.action_result.status.status))
00568 _x = self.action_result.status.text
00569 length = len(_x)
00570 if python3 or type(_x) == unicode:
00571 _x = _x.encode('utf-8')
00572 length = len(_x)
00573 buff.write(struct.pack('<I%ss'%length, length, _x))
00574 _x = self
00575 buff.write(_struct_3I.pack(_x.action_result.result.putdown_pose.header.seq, _x.action_result.result.putdown_pose.header.stamp.secs, _x.action_result.result.putdown_pose.header.stamp.nsecs))
00576 _x = self.action_result.result.putdown_pose.header.frame_id
00577 length = len(_x)
00578 if python3 or type(_x) == unicode:
00579 _x = _x.encode('utf-8')
00580 length = len(_x)
00581 buff.write(struct.pack('<I%ss'%length, length, _x))
00582 _x = self
00583 buff.write(_struct_7di3I.pack(_x.action_result.result.putdown_pose.pose.position.x, _x.action_result.result.putdown_pose.pose.position.y, _x.action_result.result.putdown_pose.pose.position.z, _x.action_result.result.putdown_pose.pose.orientation.x, _x.action_result.result.putdown_pose.pose.orientation.y, _x.action_result.result.putdown_pose.pose.orientation.z, _x.action_result.result.putdown_pose.pose.orientation.w, _x.action_result.result.error_code.val, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00584 _x = self.action_feedback.header.frame_id
00585 length = len(_x)
00586 if python3 or type(_x) == unicode:
00587 _x = _x.encode('utf-8')
00588 length = len(_x)
00589 buff.write(struct.pack('<I%ss'%length, length, _x))
00590 _x = self
00591 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00592 _x = self.action_feedback.status.goal_id.id
00593 length = len(_x)
00594 if python3 or type(_x) == unicode:
00595 _x = _x.encode('utf-8')
00596 length = len(_x)
00597 buff.write(struct.pack('<I%ss'%length, length, _x))
00598 buff.write(_struct_B.pack(self.action_feedback.status.status))
00599 _x = self.action_feedback.status.text
00600 length = len(_x)
00601 if python3 or type(_x) == unicode:
00602 _x = _x.encode('utf-8')
00603 length = len(_x)
00604 buff.write(struct.pack('<I%ss'%length, length, _x))
00605 except struct.error as se: self._check_types(se)
00606 except TypeError as te: self._check_types(te)
00607
00608 def deserialize_numpy(self, str, numpy):
00609 """
00610 unpack serialized message in str into this message instance using numpy for array types
00611 :param str: byte array of serialized message, ``str``
00612 :param numpy: numpy python module
00613 """
00614 try:
00615 if self.action_goal is None:
00616 self.action_goal = tidyup_msgs.msg.PlaceObjectActionGoal()
00617 if self.action_result is None:
00618 self.action_result = tidyup_msgs.msg.PlaceObjectActionResult()
00619 if self.action_feedback is None:
00620 self.action_feedback = tidyup_msgs.msg.PlaceObjectActionFeedback()
00621 end = 0
00622 _x = self
00623 start = end
00624 end += 12
00625 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00626 start = end
00627 end += 4
00628 (length,) = _struct_I.unpack(str[start:end])
00629 start = end
00630 end += length
00631 if python3:
00632 self.action_goal.header.frame_id = str[start:end].decode('utf-8')
00633 else:
00634 self.action_goal.header.frame_id = str[start:end]
00635 _x = self
00636 start = end
00637 end += 8
00638 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00639 start = end
00640 end += 4
00641 (length,) = _struct_I.unpack(str[start:end])
00642 start = end
00643 end += length
00644 if python3:
00645 self.action_goal.goal_id.id = str[start:end].decode('utf-8')
00646 else:
00647 self.action_goal.goal_id.id = str[start:end]
00648 start = end
00649 end += 4
00650 (length,) = _struct_I.unpack(str[start:end])
00651 start = end
00652 end += length
00653 if python3:
00654 self.action_goal.goal.static_object = str[start:end].decode('utf-8')
00655 else:
00656 self.action_goal.goal.static_object = str[start:end]
00657 start = end
00658 end += 4
00659 (length,) = _struct_I.unpack(str[start:end])
00660 start = end
00661 end += length
00662 if python3:
00663 self.action_goal.goal.putdown_object = str[start:end].decode('utf-8')
00664 else:
00665 self.action_goal.goal.putdown_object = str[start:end]
00666 start = end
00667 end += 4
00668 (length,) = _struct_I.unpack(str[start:end])
00669 start = end
00670 end += length
00671 if python3:
00672 self.action_goal.goal.arm = str[start:end].decode('utf-8')
00673 else:
00674 self.action_goal.goal.arm = str[start:end]
00675 _x = self
00676 start = end
00677 end += 12
00678 (_x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00679 start = end
00680 end += 4
00681 (length,) = _struct_I.unpack(str[start:end])
00682 start = end
00683 end += length
00684 if python3:
00685 self.action_result.header.frame_id = str[start:end].decode('utf-8')
00686 else:
00687 self.action_result.header.frame_id = str[start:end]
00688 _x = self
00689 start = end
00690 end += 8
00691 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00692 start = end
00693 end += 4
00694 (length,) = _struct_I.unpack(str[start:end])
00695 start = end
00696 end += length
00697 if python3:
00698 self.action_result.status.goal_id.id = str[start:end].decode('utf-8')
00699 else:
00700 self.action_result.status.goal_id.id = str[start:end]
00701 start = end
00702 end += 1
00703 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00704 start = end
00705 end += 4
00706 (length,) = _struct_I.unpack(str[start:end])
00707 start = end
00708 end += length
00709 if python3:
00710 self.action_result.status.text = str[start:end].decode('utf-8')
00711 else:
00712 self.action_result.status.text = str[start:end]
00713 _x = self
00714 start = end
00715 end += 12
00716 (_x.action_result.result.putdown_pose.header.seq, _x.action_result.result.putdown_pose.header.stamp.secs, _x.action_result.result.putdown_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00717 start = end
00718 end += 4
00719 (length,) = _struct_I.unpack(str[start:end])
00720 start = end
00721 end += length
00722 if python3:
00723 self.action_result.result.putdown_pose.header.frame_id = str[start:end].decode('utf-8')
00724 else:
00725 self.action_result.result.putdown_pose.header.frame_id = str[start:end]
00726 _x = self
00727 start = end
00728 end += 72
00729 (_x.action_result.result.putdown_pose.pose.position.x, _x.action_result.result.putdown_pose.pose.position.y, _x.action_result.result.putdown_pose.pose.position.z, _x.action_result.result.putdown_pose.pose.orientation.x, _x.action_result.result.putdown_pose.pose.orientation.y, _x.action_result.result.putdown_pose.pose.orientation.z, _x.action_result.result.putdown_pose.pose.orientation.w, _x.action_result.result.error_code.val, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_7di3I.unpack(str[start:end])
00730 start = end
00731 end += 4
00732 (length,) = _struct_I.unpack(str[start:end])
00733 start = end
00734 end += length
00735 if python3:
00736 self.action_feedback.header.frame_id = str[start:end].decode('utf-8')
00737 else:
00738 self.action_feedback.header.frame_id = str[start:end]
00739 _x = self
00740 start = end
00741 end += 8
00742 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00743 start = end
00744 end += 4
00745 (length,) = _struct_I.unpack(str[start:end])
00746 start = end
00747 end += length
00748 if python3:
00749 self.action_feedback.status.goal_id.id = str[start:end].decode('utf-8')
00750 else:
00751 self.action_feedback.status.goal_id.id = str[start:end]
00752 start = end
00753 end += 1
00754 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00755 start = end
00756 end += 4
00757 (length,) = _struct_I.unpack(str[start:end])
00758 start = end
00759 end += length
00760 if python3:
00761 self.action_feedback.status.text = str[start:end].decode('utf-8')
00762 else:
00763 self.action_feedback.status.text = str[start:end]
00764 return self
00765 except struct.error as e:
00766 raise genpy.DeserializationError(e)
00767
00768 _struct_I = genpy.struct_I
00769 _struct_7di3I = struct.Struct("<7di3I")
00770 _struct_3I = struct.Struct("<3I")
00771 _struct_B = struct.Struct("<B")
00772 _struct_2I = struct.Struct("<2I")