00001 """autogenerated by genmsg_py from PolygonStamped.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 PolygonStamped(roslib.message.Message):
00009 _md5sum = "c6be8f7dc3bee7fe9e8d296070f53340"
00010 _type = "geometry_msgs/PolygonStamped"
00011 _has_header = True
00012 _full_text = """# This represents a Polygon with reference coordinate frame and timestamp
00013 Header header
00014 Polygon polygon
00015
00016 ================================================================================
00017 MSG: std_msgs/Header
00018 # Standard metadata for higher-level stamped data types.
00019 # This is generally used to communicate timestamped data
00020 # in a particular coordinate frame.
00021 #
00022 # sequence ID: consecutively increasing ID
00023 uint32 seq
00024 #Two-integer timestamp that is expressed as:
00025 # * stamp.secs: seconds (stamp_secs) since epoch
00026 # * stamp.nsecs: nanoseconds since stamp_secs
00027 # time-handling sugar is provided by the client library
00028 time stamp
00029 #Frame this data is associated with
00030 # 0: no frame
00031 # 1: global frame
00032 string frame_id
00033
00034 ================================================================================
00035 MSG: geometry_msgs/Polygon
00036 #A specification of a polygon where the first and last points are assumed to be connected
00037 geometry_msgs/Point32[] points
00038
00039 ================================================================================
00040 MSG: geometry_msgs/Point32
00041 # This contains the position of a point in free space(with 32 bits of precision).
00042 # It is recommeded to use Point wherever possible instead of Point32.
00043 #
00044 # This recommendation is to promote interoperability.
00045 #
00046 # This message is designed to take up less space when sending
00047 # lots of points at once, as in the case of a PointCloud.
00048
00049 float32 x
00050 float32 y
00051 float32 z
00052 """
00053 __slots__ = ['header','polygon']
00054 _slot_types = ['Header','geometry_msgs/Polygon']
00055
00056 def __init__(self, *args, **kwds):
00057 """
00058 Constructor. Any message fields that are implicitly/explicitly
00059 set to None will be assigned a default value. The recommend
00060 use is keyword arguments as this is more robust to future message
00061 changes. You cannot mix in-order arguments and keyword arguments.
00062
00063 The available fields are:
00064 header,polygon
00065
00066 @param args: complete set of field values, in .msg order
00067 @param kwds: use keyword arguments corresponding to message field names
00068 to set specific fields.
00069 """
00070 if args or kwds:
00071 super(PolygonStamped, self).__init__(*args, **kwds)
00072
00073 if self.header is None:
00074 self.header = std_msgs.msg._Header.Header()
00075 if self.polygon is None:
00076 self.polygon = geometry_msgs.msg.Polygon()
00077 else:
00078 self.header = std_msgs.msg._Header.Header()
00079 self.polygon = geometry_msgs.msg.Polygon()
00080
00081 def _get_types(self):
00082 """
00083 internal API method
00084 """
00085 return self._slot_types
00086
00087 def serialize(self, buff):
00088 """
00089 serialize message into buffer
00090 @param buff: buffer
00091 @type buff: StringIO
00092 """
00093 try:
00094 _x = self
00095 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00096 _x = self.header.frame_id
00097 length = len(_x)
00098 buff.write(struct.pack('<I%ss'%length, length, _x))
00099 length = len(self.polygon.points)
00100 buff.write(_struct_I.pack(length))
00101 for val1 in self.polygon.points:
00102 _x = val1
00103 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00104 except struct.error, se: self._check_types(se)
00105 except TypeError, te: self._check_types(te)
00106
00107 def deserialize(self, str):
00108 """
00109 unpack serialized message in str into this message instance
00110 @param str: byte array of serialized message
00111 @type str: str
00112 """
00113 try:
00114 if self.header is None:
00115 self.header = std_msgs.msg._Header.Header()
00116 if self.polygon is None:
00117 self.polygon = geometry_msgs.msg.Polygon()
00118 end = 0
00119 _x = self
00120 start = end
00121 end += 12
00122 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00123 start = end
00124 end += 4
00125 (length,) = _struct_I.unpack(str[start:end])
00126 start = end
00127 end += length
00128 self.header.frame_id = str[start:end]
00129 start = end
00130 end += 4
00131 (length,) = _struct_I.unpack(str[start:end])
00132 self.polygon.points = []
00133 for i in xrange(0, length):
00134 val1 = geometry_msgs.msg.Point32()
00135 _x = val1
00136 start = end
00137 end += 12
00138 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00139 self.polygon.points.append(val1)
00140 return self
00141 except struct.error, e:
00142 raise roslib.message.DeserializationError(e)
00143
00144
00145 def serialize_numpy(self, buff, numpy):
00146 """
00147 serialize message with numpy array types into buffer
00148 @param buff: buffer
00149 @type buff: StringIO
00150 @param numpy: numpy python module
00151 @type numpy module
00152 """
00153 try:
00154 _x = self
00155 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00156 _x = self.header.frame_id
00157 length = len(_x)
00158 buff.write(struct.pack('<I%ss'%length, length, _x))
00159 length = len(self.polygon.points)
00160 buff.write(_struct_I.pack(length))
00161 for val1 in self.polygon.points:
00162 _x = val1
00163 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00164 except struct.error, se: self._check_types(se)
00165 except TypeError, te: self._check_types(te)
00166
00167 def deserialize_numpy(self, str, numpy):
00168 """
00169 unpack serialized message in str into this message instance using numpy for array types
00170 @param str: byte array of serialized message
00171 @type str: str
00172 @param numpy: numpy python module
00173 @type numpy: module
00174 """
00175 try:
00176 if self.header is None:
00177 self.header = std_msgs.msg._Header.Header()
00178 if self.polygon is None:
00179 self.polygon = geometry_msgs.msg.Polygon()
00180 end = 0
00181 _x = self
00182 start = end
00183 end += 12
00184 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00185 start = end
00186 end += 4
00187 (length,) = _struct_I.unpack(str[start:end])
00188 start = end
00189 end += length
00190 self.header.frame_id = str[start:end]
00191 start = end
00192 end += 4
00193 (length,) = _struct_I.unpack(str[start:end])
00194 self.polygon.points = []
00195 for i in xrange(0, length):
00196 val1 = geometry_msgs.msg.Point32()
00197 _x = val1
00198 start = end
00199 end += 12
00200 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00201 self.polygon.points.append(val1)
00202 return self
00203 except struct.error, e:
00204 raise roslib.message.DeserializationError(e)
00205
00206 _struct_I = roslib.message.struct_I
00207 _struct_3I = struct.Struct("<3I")
00208 _struct_3f = struct.Struct("<3f")