00001 """autogenerated by genmsg_py from PositionConstraint.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import geometric_shapes_msgs.msg
00007 import std_msgs.msg
00008
00009 class PositionConstraint(roslib.message.Message):
00010 _md5sum = "7e3d9697e64b346b9d3cb7311bb88ccb"
00011 _type = "motion_planning_msgs/PositionConstraint"
00012 _has_header = True
00013 _full_text = """# This message contains the definition of a position constraint.
00014 Header header
00015
00016 # The robot link this constraint refers to
00017 string link_name
00018
00019 # The offset (in the link frame) for the target point on the link we are planning for
00020 geometry_msgs/Point target_point_offset
00021
00022 # The nominal/target position for the point we are planning for
00023 geometry_msgs/Point position
00024
00025 # The shape of the bounded region that constrains the position of the end-effector
00026 # This region is always centered at the position defined above
00027 geometric_shapes_msgs/Shape constraint_region_shape
00028
00029 # The orientation of the bounded region that constrains the position of the end-effector.
00030 # This allows the specification of non-axis aligned constraints
00031 geometry_msgs/Quaternion constraint_region_orientation
00032
00033 # Constraint weighting factor - a weight for this constraint
00034 float64 weight
00035 ================================================================================
00036 MSG: std_msgs/Header
00037 # Standard metadata for higher-level stamped data types.
00038 # This is generally used to communicate timestamped data
00039 # in a particular coordinate frame.
00040 #
00041 # sequence ID: consecutively increasing ID
00042 uint32 seq
00043 #Two-integer timestamp that is expressed as:
00044 # * stamp.secs: seconds (stamp_secs) since epoch
00045 # * stamp.nsecs: nanoseconds since stamp_secs
00046 # time-handling sugar is provided by the client library
00047 time stamp
00048 #Frame this data is associated with
00049 # 0: no frame
00050 # 1: global frame
00051 string frame_id
00052
00053 ================================================================================
00054 MSG: geometry_msgs/Point
00055 # This contains the position of a point in free space
00056 float64 x
00057 float64 y
00058 float64 z
00059
00060 ================================================================================
00061 MSG: geometric_shapes_msgs/Shape
00062 byte SPHERE=0
00063 byte BOX=1
00064 byte CYLINDER=2
00065 byte MESH=3
00066
00067 byte type
00068
00069
00070 #### define sphere, box, cylinder ####
00071 # the origin of each shape is considered at the shape's center
00072
00073 # for sphere
00074 # radius := dimensions[0]
00075
00076 # for cylinder
00077 # radius := dimensions[0]
00078 # length := dimensions[1]
00079 # the length is along the Z axis
00080
00081 # for box
00082 # size_x := dimensions[0]
00083 # size_y := dimensions[1]
00084 # size_z := dimensions[2]
00085 float64[] dimensions
00086
00087
00088 #### define mesh ####
00089
00090 # list of triangles; triangle k is defined by tre vertices located
00091 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00092 int32[] triangles
00093 geometry_msgs/Point[] vertices
00094
00095 ================================================================================
00096 MSG: geometry_msgs/Quaternion
00097 # This represents an orientation in free space in quaternion form.
00098
00099 float64 x
00100 float64 y
00101 float64 z
00102 float64 w
00103
00104 """
00105 __slots__ = ['header','link_name','target_point_offset','position','constraint_region_shape','constraint_region_orientation','weight']
00106 _slot_types = ['Header','string','geometry_msgs/Point','geometry_msgs/Point','geometric_shapes_msgs/Shape','geometry_msgs/Quaternion','float64']
00107
00108 def __init__(self, *args, **kwds):
00109 """
00110 Constructor. Any message fields that are implicitly/explicitly
00111 set to None will be assigned a default value. The recommend
00112 use is keyword arguments as this is more robust to future message
00113 changes. You cannot mix in-order arguments and keyword arguments.
00114
00115 The available fields are:
00116 header,link_name,target_point_offset,position,constraint_region_shape,constraint_region_orientation,weight
00117
00118 @param args: complete set of field values, in .msg order
00119 @param kwds: use keyword arguments corresponding to message field names
00120 to set specific fields.
00121 """
00122 if args or kwds:
00123 super(PositionConstraint, self).__init__(*args, **kwds)
00124
00125 if self.header is None:
00126 self.header = std_msgs.msg._Header.Header()
00127 if self.link_name is None:
00128 self.link_name = ''
00129 if self.target_point_offset is None:
00130 self.target_point_offset = geometry_msgs.msg.Point()
00131 if self.position is None:
00132 self.position = geometry_msgs.msg.Point()
00133 if self.constraint_region_shape is None:
00134 self.constraint_region_shape = geometric_shapes_msgs.msg.Shape()
00135 if self.constraint_region_orientation is None:
00136 self.constraint_region_orientation = geometry_msgs.msg.Quaternion()
00137 if self.weight is None:
00138 self.weight = 0.
00139 else:
00140 self.header = std_msgs.msg._Header.Header()
00141 self.link_name = ''
00142 self.target_point_offset = geometry_msgs.msg.Point()
00143 self.position = geometry_msgs.msg.Point()
00144 self.constraint_region_shape = geometric_shapes_msgs.msg.Shape()
00145 self.constraint_region_orientation = geometry_msgs.msg.Quaternion()
00146 self.weight = 0.
00147
00148 def _get_types(self):
00149 """
00150 internal API method
00151 """
00152 return self._slot_types
00153
00154 def serialize(self, buff):
00155 """
00156 serialize message into buffer
00157 @param buff: buffer
00158 @type buff: StringIO
00159 """
00160 try:
00161 _x = self
00162 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00163 _x = self.header.frame_id
00164 length = len(_x)
00165 buff.write(struct.pack('<I%ss'%length, length, _x))
00166 _x = self.link_name
00167 length = len(_x)
00168 buff.write(struct.pack('<I%ss'%length, length, _x))
00169 _x = self
00170 buff.write(_struct_6db.pack(_x.target_point_offset.x, _x.target_point_offset.y, _x.target_point_offset.z, _x.position.x, _x.position.y, _x.position.z, _x.constraint_region_shape.type))
00171 length = len(self.constraint_region_shape.dimensions)
00172 buff.write(_struct_I.pack(length))
00173 pattern = '<%sd'%length
00174 buff.write(struct.pack(pattern, *self.constraint_region_shape.dimensions))
00175 length = len(self.constraint_region_shape.triangles)
00176 buff.write(_struct_I.pack(length))
00177 pattern = '<%si'%length
00178 buff.write(struct.pack(pattern, *self.constraint_region_shape.triangles))
00179 length = len(self.constraint_region_shape.vertices)
00180 buff.write(_struct_I.pack(length))
00181 for val1 in self.constraint_region_shape.vertices:
00182 _x = val1
00183 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00184 _x = self
00185 buff.write(_struct_5d.pack(_x.constraint_region_orientation.x, _x.constraint_region_orientation.y, _x.constraint_region_orientation.z, _x.constraint_region_orientation.w, _x.weight))
00186 except struct.error, se: self._check_types(se)
00187 except TypeError, te: self._check_types(te)
00188
00189 def deserialize(self, str):
00190 """
00191 unpack serialized message in str into this message instance
00192 @param str: byte array of serialized message
00193 @type str: str
00194 """
00195 try:
00196 if self.header is None:
00197 self.header = std_msgs.msg._Header.Header()
00198 if self.target_point_offset is None:
00199 self.target_point_offset = geometry_msgs.msg.Point()
00200 if self.position is None:
00201 self.position = geometry_msgs.msg.Point()
00202 if self.constraint_region_shape is None:
00203 self.constraint_region_shape = geometric_shapes_msgs.msg.Shape()
00204 if self.constraint_region_orientation is None:
00205 self.constraint_region_orientation = geometry_msgs.msg.Quaternion()
00206 end = 0
00207 _x = self
00208 start = end
00209 end += 12
00210 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00211 start = end
00212 end += 4
00213 (length,) = _struct_I.unpack(str[start:end])
00214 start = end
00215 end += length
00216 self.header.frame_id = str[start:end]
00217 start = end
00218 end += 4
00219 (length,) = _struct_I.unpack(str[start:end])
00220 start = end
00221 end += length
00222 self.link_name = str[start:end]
00223 _x = self
00224 start = end
00225 end += 49
00226 (_x.target_point_offset.x, _x.target_point_offset.y, _x.target_point_offset.z, _x.position.x, _x.position.y, _x.position.z, _x.constraint_region_shape.type,) = _struct_6db.unpack(str[start:end])
00227 start = end
00228 end += 4
00229 (length,) = _struct_I.unpack(str[start:end])
00230 pattern = '<%sd'%length
00231 start = end
00232 end += struct.calcsize(pattern)
00233 self.constraint_region_shape.dimensions = struct.unpack(pattern, str[start:end])
00234 start = end
00235 end += 4
00236 (length,) = _struct_I.unpack(str[start:end])
00237 pattern = '<%si'%length
00238 start = end
00239 end += struct.calcsize(pattern)
00240 self.constraint_region_shape.triangles = struct.unpack(pattern, str[start:end])
00241 start = end
00242 end += 4
00243 (length,) = _struct_I.unpack(str[start:end])
00244 self.constraint_region_shape.vertices = []
00245 for i in xrange(0, length):
00246 val1 = geometry_msgs.msg.Point()
00247 _x = val1
00248 start = end
00249 end += 24
00250 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00251 self.constraint_region_shape.vertices.append(val1)
00252 _x = self
00253 start = end
00254 end += 40
00255 (_x.constraint_region_orientation.x, _x.constraint_region_orientation.y, _x.constraint_region_orientation.z, _x.constraint_region_orientation.w, _x.weight,) = _struct_5d.unpack(str[start:end])
00256 return self
00257 except struct.error, e:
00258 raise roslib.message.DeserializationError(e)
00259
00260
00261 def serialize_numpy(self, buff, numpy):
00262 """
00263 serialize message with numpy array types into buffer
00264 @param buff: buffer
00265 @type buff: StringIO
00266 @param numpy: numpy python module
00267 @type numpy module
00268 """
00269 try:
00270 _x = self
00271 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00272 _x = self.header.frame_id
00273 length = len(_x)
00274 buff.write(struct.pack('<I%ss'%length, length, _x))
00275 _x = self.link_name
00276 length = len(_x)
00277 buff.write(struct.pack('<I%ss'%length, length, _x))
00278 _x = self
00279 buff.write(_struct_6db.pack(_x.target_point_offset.x, _x.target_point_offset.y, _x.target_point_offset.z, _x.position.x, _x.position.y, _x.position.z, _x.constraint_region_shape.type))
00280 length = len(self.constraint_region_shape.dimensions)
00281 buff.write(_struct_I.pack(length))
00282 pattern = '<%sd'%length
00283 buff.write(self.constraint_region_shape.dimensions.tostring())
00284 length = len(self.constraint_region_shape.triangles)
00285 buff.write(_struct_I.pack(length))
00286 pattern = '<%si'%length
00287 buff.write(self.constraint_region_shape.triangles.tostring())
00288 length = len(self.constraint_region_shape.vertices)
00289 buff.write(_struct_I.pack(length))
00290 for val1 in self.constraint_region_shape.vertices:
00291 _x = val1
00292 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00293 _x = self
00294 buff.write(_struct_5d.pack(_x.constraint_region_orientation.x, _x.constraint_region_orientation.y, _x.constraint_region_orientation.z, _x.constraint_region_orientation.w, _x.weight))
00295 except struct.error, se: self._check_types(se)
00296 except TypeError, te: self._check_types(te)
00297
00298 def deserialize_numpy(self, str, numpy):
00299 """
00300 unpack serialized message in str into this message instance using numpy for array types
00301 @param str: byte array of serialized message
00302 @type str: str
00303 @param numpy: numpy python module
00304 @type numpy: module
00305 """
00306 try:
00307 if self.header is None:
00308 self.header = std_msgs.msg._Header.Header()
00309 if self.target_point_offset is None:
00310 self.target_point_offset = geometry_msgs.msg.Point()
00311 if self.position is None:
00312 self.position = geometry_msgs.msg.Point()
00313 if self.constraint_region_shape is None:
00314 self.constraint_region_shape = geometric_shapes_msgs.msg.Shape()
00315 if self.constraint_region_orientation is None:
00316 self.constraint_region_orientation = geometry_msgs.msg.Quaternion()
00317 end = 0
00318 _x = self
00319 start = end
00320 end += 12
00321 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.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.header.frame_id = str[start:end]
00328 start = end
00329 end += 4
00330 (length,) = _struct_I.unpack(str[start:end])
00331 start = end
00332 end += length
00333 self.link_name = str[start:end]
00334 _x = self
00335 start = end
00336 end += 49
00337 (_x.target_point_offset.x, _x.target_point_offset.y, _x.target_point_offset.z, _x.position.x, _x.position.y, _x.position.z, _x.constraint_region_shape.type,) = _struct_6db.unpack(str[start:end])
00338 start = end
00339 end += 4
00340 (length,) = _struct_I.unpack(str[start:end])
00341 pattern = '<%sd'%length
00342 start = end
00343 end += struct.calcsize(pattern)
00344 self.constraint_region_shape.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00345 start = end
00346 end += 4
00347 (length,) = _struct_I.unpack(str[start:end])
00348 pattern = '<%si'%length
00349 start = end
00350 end += struct.calcsize(pattern)
00351 self.constraint_region_shape.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00352 start = end
00353 end += 4
00354 (length,) = _struct_I.unpack(str[start:end])
00355 self.constraint_region_shape.vertices = []
00356 for i in xrange(0, length):
00357 val1 = geometry_msgs.msg.Point()
00358 _x = val1
00359 start = end
00360 end += 24
00361 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00362 self.constraint_region_shape.vertices.append(val1)
00363 _x = self
00364 start = end
00365 end += 40
00366 (_x.constraint_region_orientation.x, _x.constraint_region_orientation.y, _x.constraint_region_orientation.z, _x.constraint_region_orientation.w, _x.weight,) = _struct_5d.unpack(str[start:end])
00367 return self
00368 except struct.error, e:
00369 raise roslib.message.DeserializationError(e)
00370
00371 _struct_I = roslib.message.struct_I
00372 _struct_5d = struct.Struct("<5d")
00373 _struct_3I = struct.Struct("<3I")
00374 _struct_6db = struct.Struct("<6db")
00375 _struct_3d = struct.Struct("<3d")