00001 """autogenerated by genmsg_py from Shape.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006
00007 class Shape(roslib.message.Message):
00008 _md5sum = "59935940044147de75e7523b5d37c4d7"
00009 _type = "geometric_shapes_msgs/Shape"
00010 _has_header = False
00011 _full_text = """byte SPHERE=0
00012 byte BOX=1
00013 byte CYLINDER=2
00014 byte MESH=3
00015
00016 byte type
00017
00018
00019 #### define sphere, box, cylinder ####
00020 # the origin of each shape is considered at the shape's center
00021
00022 # for sphere
00023 # radius := dimensions[0]
00024
00025 # for cylinder
00026 # radius := dimensions[0]
00027 # length := dimensions[1]
00028 # the length is along the Z axis
00029
00030 # for box
00031 # size_x := dimensions[0]
00032 # size_y := dimensions[1]
00033 # size_z := dimensions[2]
00034 float64[] dimensions
00035
00036
00037 #### define mesh ####
00038
00039 # list of triangles; triangle k is defined by tre vertices located
00040 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]
00041 int32[] triangles
00042 geometry_msgs/Point[] vertices
00043
00044 ================================================================================
00045 MSG: geometry_msgs/Point
00046 # This contains the position of a point in free space
00047 float64 x
00048 float64 y
00049 float64 z
00050
00051 """
00052
00053 SPHERE = 0
00054 BOX = 1
00055 CYLINDER = 2
00056 MESH = 3
00057
00058 __slots__ = ['type','dimensions','triangles','vertices']
00059 _slot_types = ['byte','float64[]','int32[]','geometry_msgs/Point[]']
00060
00061 def __init__(self, *args, **kwds):
00062 """
00063 Constructor. Any message fields that are implicitly/explicitly
00064 set to None will be assigned a default value. The recommend
00065 use is keyword arguments as this is more robust to future message
00066 changes. You cannot mix in-order arguments and keyword arguments.
00067
00068 The available fields are:
00069 type,dimensions,triangles,vertices
00070
00071 @param args: complete set of field values, in .msg order
00072 @param kwds: use keyword arguments corresponding to message field names
00073 to set specific fields.
00074 """
00075 if args or kwds:
00076 super(Shape, self).__init__(*args, **kwds)
00077
00078 if self.type is None:
00079 self.type = 0
00080 if self.dimensions is None:
00081 self.dimensions = []
00082 if self.triangles is None:
00083 self.triangles = []
00084 if self.vertices is None:
00085 self.vertices = []
00086 else:
00087 self.type = 0
00088 self.dimensions = []
00089 self.triangles = []
00090 self.vertices = []
00091
00092 def _get_types(self):
00093 """
00094 internal API method
00095 """
00096 return self._slot_types
00097
00098 def serialize(self, buff):
00099 """
00100 serialize message into buffer
00101 @param buff: buffer
00102 @type buff: StringIO
00103 """
00104 try:
00105 buff.write(_struct_b.pack(self.type))
00106 length = len(self.dimensions)
00107 buff.write(_struct_I.pack(length))
00108 pattern = '<%sd'%length
00109 buff.write(struct.pack(pattern, *self.dimensions))
00110 length = len(self.triangles)
00111 buff.write(_struct_I.pack(length))
00112 pattern = '<%si'%length
00113 buff.write(struct.pack(pattern, *self.triangles))
00114 length = len(self.vertices)
00115 buff.write(_struct_I.pack(length))
00116 for val1 in self.vertices:
00117 _x = val1
00118 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00119 except struct.error, se: self._check_types(se)
00120 except TypeError, te: self._check_types(te)
00121
00122 def deserialize(self, str):
00123 """
00124 unpack serialized message in str into this message instance
00125 @param str: byte array of serialized message
00126 @type str: str
00127 """
00128 try:
00129 end = 0
00130 start = end
00131 end += 1
00132 (self.type,) = _struct_b.unpack(str[start:end])
00133 start = end
00134 end += 4
00135 (length,) = _struct_I.unpack(str[start:end])
00136 pattern = '<%sd'%length
00137 start = end
00138 end += struct.calcsize(pattern)
00139 self.dimensions = struct.unpack(pattern, str[start:end])
00140 start = end
00141 end += 4
00142 (length,) = _struct_I.unpack(str[start:end])
00143 pattern = '<%si'%length
00144 start = end
00145 end += struct.calcsize(pattern)
00146 self.triangles = struct.unpack(pattern, str[start:end])
00147 start = end
00148 end += 4
00149 (length,) = _struct_I.unpack(str[start:end])
00150 self.vertices = []
00151 for i in xrange(0, length):
00152 val1 = geometry_msgs.msg.Point()
00153 _x = val1
00154 start = end
00155 end += 24
00156 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00157 self.vertices.append(val1)
00158 return self
00159 except struct.error, e:
00160 raise roslib.message.DeserializationError(e)
00161
00162
00163 def serialize_numpy(self, buff, numpy):
00164 """
00165 serialize message with numpy array types into buffer
00166 @param buff: buffer
00167 @type buff: StringIO
00168 @param numpy: numpy python module
00169 @type numpy module
00170 """
00171 try:
00172 buff.write(_struct_b.pack(self.type))
00173 length = len(self.dimensions)
00174 buff.write(_struct_I.pack(length))
00175 pattern = '<%sd'%length
00176 buff.write(self.dimensions.tostring())
00177 length = len(self.triangles)
00178 buff.write(_struct_I.pack(length))
00179 pattern = '<%si'%length
00180 buff.write(self.triangles.tostring())
00181 length = len(self.vertices)
00182 buff.write(_struct_I.pack(length))
00183 for val1 in self.vertices:
00184 _x = val1
00185 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00186 except struct.error, se: self._check_types(se)
00187 except TypeError, te: self._check_types(te)
00188
00189 def deserialize_numpy(self, str, numpy):
00190 """
00191 unpack serialized message in str into this message instance using numpy for array types
00192 @param str: byte array of serialized message
00193 @type str: str
00194 @param numpy: numpy python module
00195 @type numpy: module
00196 """
00197 try:
00198 end = 0
00199 start = end
00200 end += 1
00201 (self.type,) = _struct_b.unpack(str[start:end])
00202 start = end
00203 end += 4
00204 (length,) = _struct_I.unpack(str[start:end])
00205 pattern = '<%sd'%length
00206 start = end
00207 end += struct.calcsize(pattern)
00208 self.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00209 start = end
00210 end += 4
00211 (length,) = _struct_I.unpack(str[start:end])
00212 pattern = '<%si'%length
00213 start = end
00214 end += struct.calcsize(pattern)
00215 self.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00216 start = end
00217 end += 4
00218 (length,) = _struct_I.unpack(str[start:end])
00219 self.vertices = []
00220 for i in xrange(0, length):
00221 val1 = geometry_msgs.msg.Point()
00222 _x = val1
00223 start = end
00224 end += 24
00225 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00226 self.vertices.append(val1)
00227 return self
00228 except struct.error, e:
00229 raise roslib.message.DeserializationError(e)
00230
00231 _struct_I = roslib.message.struct_I
00232 _struct_b = struct.Struct("<b")
00233 _struct_3d = struct.Struct("<3d")