00001 """autogenerated by genmsg_py from ModelObjectInHandGoal.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import std_msgs.msg
00007
00008 class ModelObjectInHandGoal(roslib.message.Message):
00009 _md5sum = "dbd0a8f991b14588bbd523abc948c0b6"
00010 _type = "pr2_create_object_model/ModelObjectInHandGoal"
00011 _has_header = False
00012 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00013 # which arm to use
00014 string arm_name
00015
00016 # the relative motion in which to move the gripper to get it clear of objects
00017 #(if left unfilled, will not move)
00018 geometry_msgs/Vector3Stamped clear_move
00019
00020 # the pose to go to for rotating (if left unfilled, will not go)
00021 geometry_msgs/PoseStamped rotate_pose
00022
00023 # whether to rotate the object at rotate_pose to build up the model
00024 uint8 rotate_object
00025
00026 # whether to add the object to the collision map
00027 uint8 add_to_collision_map
00028
00029 # whether to keep the object level while rotating
00030 uint8 keep_level
00031
00032
00033 ================================================================================
00034 MSG: geometry_msgs/Vector3Stamped
00035 # This represents a Vector3 with reference coordinate frame and timestamp
00036 Header header
00037 Vector3 vector
00038
00039 ================================================================================
00040 MSG: std_msgs/Header
00041 # Standard metadata for higher-level stamped data types.
00042 # This is generally used to communicate timestamped data
00043 # in a particular coordinate frame.
00044 #
00045 # sequence ID: consecutively increasing ID
00046 uint32 seq
00047 #Two-integer timestamp that is expressed as:
00048 # * stamp.secs: seconds (stamp_secs) since epoch
00049 # * stamp.nsecs: nanoseconds since stamp_secs
00050 # time-handling sugar is provided by the client library
00051 time stamp
00052 #Frame this data is associated with
00053 # 0: no frame
00054 # 1: global frame
00055 string frame_id
00056
00057 ================================================================================
00058 MSG: geometry_msgs/Vector3
00059 # This represents a vector in free space.
00060
00061 float64 x
00062 float64 y
00063 float64 z
00064 ================================================================================
00065 MSG: geometry_msgs/PoseStamped
00066 # A Pose with reference coordinate frame and timestamp
00067 Header header
00068 Pose pose
00069
00070 ================================================================================
00071 MSG: geometry_msgs/Pose
00072 # A representation of pose in free space, composed of postion and orientation.
00073 Point position
00074 Quaternion orientation
00075
00076 ================================================================================
00077 MSG: geometry_msgs/Point
00078 # This contains the position of a point in free space
00079 float64 x
00080 float64 y
00081 float64 z
00082
00083 ================================================================================
00084 MSG: geometry_msgs/Quaternion
00085 # This represents an orientation in free space in quaternion form.
00086
00087 float64 x
00088 float64 y
00089 float64 z
00090 float64 w
00091
00092 """
00093 __slots__ = ['arm_name','clear_move','rotate_pose','rotate_object','add_to_collision_map','keep_level']
00094 _slot_types = ['string','geometry_msgs/Vector3Stamped','geometry_msgs/PoseStamped','uint8','uint8','uint8']
00095
00096 def __init__(self, *args, **kwds):
00097 """
00098 Constructor. Any message fields that are implicitly/explicitly
00099 set to None will be assigned a default value. The recommend
00100 use is keyword arguments as this is more robust to future message
00101 changes. You cannot mix in-order arguments and keyword arguments.
00102
00103 The available fields are:
00104 arm_name,clear_move,rotate_pose,rotate_object,add_to_collision_map,keep_level
00105
00106 @param args: complete set of field values, in .msg order
00107 @param kwds: use keyword arguments corresponding to message field names
00108 to set specific fields.
00109 """
00110 if args or kwds:
00111 super(ModelObjectInHandGoal, self).__init__(*args, **kwds)
00112
00113 if self.arm_name is None:
00114 self.arm_name = ''
00115 if self.clear_move is None:
00116 self.clear_move = geometry_msgs.msg.Vector3Stamped()
00117 if self.rotate_pose is None:
00118 self.rotate_pose = geometry_msgs.msg.PoseStamped()
00119 if self.rotate_object is None:
00120 self.rotate_object = 0
00121 if self.add_to_collision_map is None:
00122 self.add_to_collision_map = 0
00123 if self.keep_level is None:
00124 self.keep_level = 0
00125 else:
00126 self.arm_name = ''
00127 self.clear_move = geometry_msgs.msg.Vector3Stamped()
00128 self.rotate_pose = geometry_msgs.msg.PoseStamped()
00129 self.rotate_object = 0
00130 self.add_to_collision_map = 0
00131 self.keep_level = 0
00132
00133 def _get_types(self):
00134 """
00135 internal API method
00136 """
00137 return self._slot_types
00138
00139 def serialize(self, buff):
00140 """
00141 serialize message into buffer
00142 @param buff: buffer
00143 @type buff: StringIO
00144 """
00145 try:
00146 _x = self.arm_name
00147 length = len(_x)
00148 buff.write(struct.pack('<I%ss'%length, length, _x))
00149 _x = self
00150 buff.write(_struct_3I.pack(_x.clear_move.header.seq, _x.clear_move.header.stamp.secs, _x.clear_move.header.stamp.nsecs))
00151 _x = self.clear_move.header.frame_id
00152 length = len(_x)
00153 buff.write(struct.pack('<I%ss'%length, length, _x))
00154 _x = self
00155 buff.write(_struct_3d3I.pack(_x.clear_move.vector.x, _x.clear_move.vector.y, _x.clear_move.vector.z, _x.rotate_pose.header.seq, _x.rotate_pose.header.stamp.secs, _x.rotate_pose.header.stamp.nsecs))
00156 _x = self.rotate_pose.header.frame_id
00157 length = len(_x)
00158 buff.write(struct.pack('<I%ss'%length, length, _x))
00159 _x = self
00160 buff.write(_struct_7d3B.pack(_x.rotate_pose.pose.position.x, _x.rotate_pose.pose.position.y, _x.rotate_pose.pose.position.z, _x.rotate_pose.pose.orientation.x, _x.rotate_pose.pose.orientation.y, _x.rotate_pose.pose.orientation.z, _x.rotate_pose.pose.orientation.w, _x.rotate_object, _x.add_to_collision_map, _x.keep_level))
00161 except struct.error as se: self._check_types(se)
00162 except TypeError as te: self._check_types(te)
00163
00164 def deserialize(self, str):
00165 """
00166 unpack serialized message in str into this message instance
00167 @param str: byte array of serialized message
00168 @type str: str
00169 """
00170 try:
00171 if self.clear_move is None:
00172 self.clear_move = geometry_msgs.msg.Vector3Stamped()
00173 if self.rotate_pose is None:
00174 self.rotate_pose = geometry_msgs.msg.PoseStamped()
00175 end = 0
00176 start = end
00177 end += 4
00178 (length,) = _struct_I.unpack(str[start:end])
00179 start = end
00180 end += length
00181 self.arm_name = str[start:end]
00182 _x = self
00183 start = end
00184 end += 12
00185 (_x.clear_move.header.seq, _x.clear_move.header.stamp.secs, _x.clear_move.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00186 start = end
00187 end += 4
00188 (length,) = _struct_I.unpack(str[start:end])
00189 start = end
00190 end += length
00191 self.clear_move.header.frame_id = str[start:end]
00192 _x = self
00193 start = end
00194 end += 36
00195 (_x.clear_move.vector.x, _x.clear_move.vector.y, _x.clear_move.vector.z, _x.rotate_pose.header.seq, _x.rotate_pose.header.stamp.secs, _x.rotate_pose.header.stamp.nsecs,) = _struct_3d3I.unpack(str[start:end])
00196 start = end
00197 end += 4
00198 (length,) = _struct_I.unpack(str[start:end])
00199 start = end
00200 end += length
00201 self.rotate_pose.header.frame_id = str[start:end]
00202 _x = self
00203 start = end
00204 end += 59
00205 (_x.rotate_pose.pose.position.x, _x.rotate_pose.pose.position.y, _x.rotate_pose.pose.position.z, _x.rotate_pose.pose.orientation.x, _x.rotate_pose.pose.orientation.y, _x.rotate_pose.pose.orientation.z, _x.rotate_pose.pose.orientation.w, _x.rotate_object, _x.add_to_collision_map, _x.keep_level,) = _struct_7d3B.unpack(str[start:end])
00206 return self
00207 except struct.error as e:
00208 raise roslib.message.DeserializationError(e)
00209
00210
00211 def serialize_numpy(self, buff, numpy):
00212 """
00213 serialize message with numpy array types into buffer
00214 @param buff: buffer
00215 @type buff: StringIO
00216 @param numpy: numpy python module
00217 @type numpy module
00218 """
00219 try:
00220 _x = self.arm_name
00221 length = len(_x)
00222 buff.write(struct.pack('<I%ss'%length, length, _x))
00223 _x = self
00224 buff.write(_struct_3I.pack(_x.clear_move.header.seq, _x.clear_move.header.stamp.secs, _x.clear_move.header.stamp.nsecs))
00225 _x = self.clear_move.header.frame_id
00226 length = len(_x)
00227 buff.write(struct.pack('<I%ss'%length, length, _x))
00228 _x = self
00229 buff.write(_struct_3d3I.pack(_x.clear_move.vector.x, _x.clear_move.vector.y, _x.clear_move.vector.z, _x.rotate_pose.header.seq, _x.rotate_pose.header.stamp.secs, _x.rotate_pose.header.stamp.nsecs))
00230 _x = self.rotate_pose.header.frame_id
00231 length = len(_x)
00232 buff.write(struct.pack('<I%ss'%length, length, _x))
00233 _x = self
00234 buff.write(_struct_7d3B.pack(_x.rotate_pose.pose.position.x, _x.rotate_pose.pose.position.y, _x.rotate_pose.pose.position.z, _x.rotate_pose.pose.orientation.x, _x.rotate_pose.pose.orientation.y, _x.rotate_pose.pose.orientation.z, _x.rotate_pose.pose.orientation.w, _x.rotate_object, _x.add_to_collision_map, _x.keep_level))
00235 except struct.error as se: self._check_types(se)
00236 except TypeError as te: self._check_types(te)
00237
00238 def deserialize_numpy(self, str, numpy):
00239 """
00240 unpack serialized message in str into this message instance using numpy for array types
00241 @param str: byte array of serialized message
00242 @type str: str
00243 @param numpy: numpy python module
00244 @type numpy: module
00245 """
00246 try:
00247 if self.clear_move is None:
00248 self.clear_move = geometry_msgs.msg.Vector3Stamped()
00249 if self.rotate_pose is None:
00250 self.rotate_pose = geometry_msgs.msg.PoseStamped()
00251 end = 0
00252 start = end
00253 end += 4
00254 (length,) = _struct_I.unpack(str[start:end])
00255 start = end
00256 end += length
00257 self.arm_name = str[start:end]
00258 _x = self
00259 start = end
00260 end += 12
00261 (_x.clear_move.header.seq, _x.clear_move.header.stamp.secs, _x.clear_move.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00262 start = end
00263 end += 4
00264 (length,) = _struct_I.unpack(str[start:end])
00265 start = end
00266 end += length
00267 self.clear_move.header.frame_id = str[start:end]
00268 _x = self
00269 start = end
00270 end += 36
00271 (_x.clear_move.vector.x, _x.clear_move.vector.y, _x.clear_move.vector.z, _x.rotate_pose.header.seq, _x.rotate_pose.header.stamp.secs, _x.rotate_pose.header.stamp.nsecs,) = _struct_3d3I.unpack(str[start:end])
00272 start = end
00273 end += 4
00274 (length,) = _struct_I.unpack(str[start:end])
00275 start = end
00276 end += length
00277 self.rotate_pose.header.frame_id = str[start:end]
00278 _x = self
00279 start = end
00280 end += 59
00281 (_x.rotate_pose.pose.position.x, _x.rotate_pose.pose.position.y, _x.rotate_pose.pose.position.z, _x.rotate_pose.pose.orientation.x, _x.rotate_pose.pose.orientation.y, _x.rotate_pose.pose.orientation.z, _x.rotate_pose.pose.orientation.w, _x.rotate_object, _x.add_to_collision_map, _x.keep_level,) = _struct_7d3B.unpack(str[start:end])
00282 return self
00283 except struct.error as e:
00284 raise roslib.message.DeserializationError(e)
00285
00286 _struct_I = roslib.message.struct_I
00287 _struct_3d3I = struct.Struct("<3d3I")
00288 _struct_3I = struct.Struct("<3I")
00289 _struct_7d3B = struct.Struct("<7d3B")