00001 """autogenerated by genmsg_py from ImageMarker.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import roslib.rostime
00007 import std_msgs.msg
00008
00009 class ImageMarker(roslib.message.Message):
00010 _md5sum = "e185c670c5f817486e6a216cbee30f1c"
00011 _type = "visualization_msgs/ImageMarker"
00012 _has_header = True
00013 _full_text = """byte CIRCLE=0
00014 byte LINE_STRIP=1
00015 byte LINE_LIST=2
00016 byte POLYGON=3
00017 byte POINTS=4
00018
00019 byte ADD=0
00020 byte REMOVE=1
00021
00022 Header header
00023 string ns # namespace, used with id to form a unique id
00024 int32 id # unique id within the namespace
00025 int32 type # CIRCLE/LINE_STRIP/etc.
00026 int32 action # ADD/REMOVE
00027 geometry_msgs/Point position # 2D, in pixel-coords
00028 float32 scale # the diameter for a circle, etc.
00029 std_msgs/ColorRGBA outline_color
00030 byte filled # whether to fill in the shape with color
00031 std_msgs/ColorRGBA fill_color # color [0.0-1.0]
00032 duration lifetime # How long the object should last before being automatically deleted. 0 means forever
00033
00034
00035 geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords
00036 std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc.
00037 ================================================================================
00038 MSG: std_msgs/Header
00039 # Standard metadata for higher-level stamped data types.
00040 # This is generally used to communicate timestamped data
00041 # in a particular coordinate frame.
00042 #
00043 # sequence ID: consecutively increasing ID
00044 uint32 seq
00045 #Two-integer timestamp that is expressed as:
00046 # * stamp.secs: seconds (stamp_secs) since epoch
00047 # * stamp.nsecs: nanoseconds since stamp_secs
00048 # time-handling sugar is provided by the client library
00049 time stamp
00050 #Frame this data is associated with
00051 # 0: no frame
00052 # 1: global frame
00053 string frame_id
00054
00055 ================================================================================
00056 MSG: geometry_msgs/Point
00057 # This contains the position of a point in free space
00058 float64 x
00059 float64 y
00060 float64 z
00061
00062 ================================================================================
00063 MSG: std_msgs/ColorRGBA
00064 float32 r
00065 float32 g
00066 float32 b
00067 float32 a
00068
00069 """
00070
00071 CIRCLE = 0
00072 LINE_STRIP = 1
00073 LINE_LIST = 2
00074 POLYGON = 3
00075 POINTS = 4
00076 ADD = 0
00077 REMOVE = 1
00078
00079 __slots__ = ['header','ns','id','type','action','position','scale','outline_color','filled','fill_color','lifetime','points','outline_colors']
00080 _slot_types = ['Header','string','int32','int32','int32','geometry_msgs/Point','float32','std_msgs/ColorRGBA','byte','std_msgs/ColorRGBA','duration','geometry_msgs/Point[]','std_msgs/ColorRGBA[]']
00081
00082 def __init__(self, *args, **kwds):
00083 """
00084 Constructor. Any message fields that are implicitly/explicitly
00085 set to None will be assigned a default value. The recommend
00086 use is keyword arguments as this is more robust to future message
00087 changes. You cannot mix in-order arguments and keyword arguments.
00088
00089 The available fields are:
00090 header,ns,id,type,action,position,scale,outline_color,filled,fill_color,lifetime,points,outline_colors
00091
00092 @param args: complete set of field values, in .msg order
00093 @param kwds: use keyword arguments corresponding to message field names
00094 to set specific fields.
00095 """
00096 if args or kwds:
00097 super(ImageMarker, self).__init__(*args, **kwds)
00098
00099 if self.header is None:
00100 self.header = std_msgs.msg._Header.Header()
00101 if self.ns is None:
00102 self.ns = ''
00103 if self.id is None:
00104 self.id = 0
00105 if self.type is None:
00106 self.type = 0
00107 if self.action is None:
00108 self.action = 0
00109 if self.position is None:
00110 self.position = geometry_msgs.msg.Point()
00111 if self.scale is None:
00112 self.scale = 0.
00113 if self.outline_color is None:
00114 self.outline_color = std_msgs.msg.ColorRGBA()
00115 if self.filled is None:
00116 self.filled = 0
00117 if self.fill_color is None:
00118 self.fill_color = std_msgs.msg.ColorRGBA()
00119 if self.lifetime is None:
00120 self.lifetime = roslib.rostime.Duration()
00121 if self.points is None:
00122 self.points = []
00123 if self.outline_colors is None:
00124 self.outline_colors = []
00125 else:
00126 self.header = std_msgs.msg._Header.Header()
00127 self.ns = ''
00128 self.id = 0
00129 self.type = 0
00130 self.action = 0
00131 self.position = geometry_msgs.msg.Point()
00132 self.scale = 0.
00133 self.outline_color = std_msgs.msg.ColorRGBA()
00134 self.filled = 0
00135 self.fill_color = std_msgs.msg.ColorRGBA()
00136 self.lifetime = roslib.rostime.Duration()
00137 self.points = []
00138 self.outline_colors = []
00139
00140 def _get_types(self):
00141 """
00142 internal API method
00143 """
00144 return self._slot_types
00145
00146 def serialize(self, buff):
00147 """
00148 serialize message into buffer
00149 @param buff: buffer
00150 @type buff: StringIO
00151 """
00152 try:
00153 _x = self
00154 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00155 _x = self.header.frame_id
00156 length = len(_x)
00157 buff.write(struct.pack('<I%ss'%length, length, _x))
00158 _x = self.ns
00159 length = len(_x)
00160 buff.write(struct.pack('<I%ss'%length, length, _x))
00161 _x = self
00162 buff.write(_struct_3i3d5fb4f2i.pack(_x.id, _x.type, _x.action, _x.position.x, _x.position.y, _x.position.z, _x.scale, _x.outline_color.r, _x.outline_color.g, _x.outline_color.b, _x.outline_color.a, _x.filled, _x.fill_color.r, _x.fill_color.g, _x.fill_color.b, _x.fill_color.a, _x.lifetime.secs, _x.lifetime.nsecs))
00163 length = len(self.points)
00164 buff.write(_struct_I.pack(length))
00165 for val1 in self.points:
00166 _x = val1
00167 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00168 length = len(self.outline_colors)
00169 buff.write(_struct_I.pack(length))
00170 for val1 in self.outline_colors:
00171 _x = val1
00172 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00173 except struct.error, se: self._check_types(se)
00174 except TypeError, te: self._check_types(te)
00175
00176 def deserialize(self, str):
00177 """
00178 unpack serialized message in str into this message instance
00179 @param str: byte array of serialized message
00180 @type str: str
00181 """
00182 try:
00183 if self.header is None:
00184 self.header = std_msgs.msg._Header.Header()
00185 if self.position is None:
00186 self.position = geometry_msgs.msg.Point()
00187 if self.outline_color is None:
00188 self.outline_color = std_msgs.msg.ColorRGBA()
00189 if self.fill_color is None:
00190 self.fill_color = std_msgs.msg.ColorRGBA()
00191 if self.lifetime is None:
00192 self.lifetime = roslib.rostime.Duration()
00193 end = 0
00194 _x = self
00195 start = end
00196 end += 12
00197 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00198 start = end
00199 end += 4
00200 (length,) = _struct_I.unpack(str[start:end])
00201 start = end
00202 end += length
00203 self.header.frame_id = str[start:end]
00204 start = end
00205 end += 4
00206 (length,) = _struct_I.unpack(str[start:end])
00207 start = end
00208 end += length
00209 self.ns = str[start:end]
00210 _x = self
00211 start = end
00212 end += 81
00213 (_x.id, _x.type, _x.action, _x.position.x, _x.position.y, _x.position.z, _x.scale, _x.outline_color.r, _x.outline_color.g, _x.outline_color.b, _x.outline_color.a, _x.filled, _x.fill_color.r, _x.fill_color.g, _x.fill_color.b, _x.fill_color.a, _x.lifetime.secs, _x.lifetime.nsecs,) = _struct_3i3d5fb4f2i.unpack(str[start:end])
00214 start = end
00215 end += 4
00216 (length,) = _struct_I.unpack(str[start:end])
00217 self.points = []
00218 for i in xrange(0, length):
00219 val1 = geometry_msgs.msg.Point()
00220 _x = val1
00221 start = end
00222 end += 24
00223 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00224 self.points.append(val1)
00225 start = end
00226 end += 4
00227 (length,) = _struct_I.unpack(str[start:end])
00228 self.outline_colors = []
00229 for i in xrange(0, length):
00230 val1 = std_msgs.msg.ColorRGBA()
00231 _x = val1
00232 start = end
00233 end += 16
00234 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00235 self.outline_colors.append(val1)
00236 self.lifetime.canon()
00237 return self
00238 except struct.error, e:
00239 raise roslib.message.DeserializationError(e)
00240
00241
00242 def serialize_numpy(self, buff, numpy):
00243 """
00244 serialize message with numpy array types into buffer
00245 @param buff: buffer
00246 @type buff: StringIO
00247 @param numpy: numpy python module
00248 @type numpy module
00249 """
00250 try:
00251 _x = self
00252 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00253 _x = self.header.frame_id
00254 length = len(_x)
00255 buff.write(struct.pack('<I%ss'%length, length, _x))
00256 _x = self.ns
00257 length = len(_x)
00258 buff.write(struct.pack('<I%ss'%length, length, _x))
00259 _x = self
00260 buff.write(_struct_3i3d5fb4f2i.pack(_x.id, _x.type, _x.action, _x.position.x, _x.position.y, _x.position.z, _x.scale, _x.outline_color.r, _x.outline_color.g, _x.outline_color.b, _x.outline_color.a, _x.filled, _x.fill_color.r, _x.fill_color.g, _x.fill_color.b, _x.fill_color.a, _x.lifetime.secs, _x.lifetime.nsecs))
00261 length = len(self.points)
00262 buff.write(_struct_I.pack(length))
00263 for val1 in self.points:
00264 _x = val1
00265 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00266 length = len(self.outline_colors)
00267 buff.write(_struct_I.pack(length))
00268 for val1 in self.outline_colors:
00269 _x = val1
00270 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00271 except struct.error, se: self._check_types(se)
00272 except TypeError, te: self._check_types(te)
00273
00274 def deserialize_numpy(self, str, numpy):
00275 """
00276 unpack serialized message in str into this message instance using numpy for array types
00277 @param str: byte array of serialized message
00278 @type str: str
00279 @param numpy: numpy python module
00280 @type numpy: module
00281 """
00282 try:
00283 if self.header is None:
00284 self.header = std_msgs.msg._Header.Header()
00285 if self.position is None:
00286 self.position = geometry_msgs.msg.Point()
00287 if self.outline_color is None:
00288 self.outline_color = std_msgs.msg.ColorRGBA()
00289 if self.fill_color is None:
00290 self.fill_color = std_msgs.msg.ColorRGBA()
00291 if self.lifetime is None:
00292 self.lifetime = roslib.rostime.Duration()
00293 end = 0
00294 _x = self
00295 start = end
00296 end += 12
00297 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00298 start = end
00299 end += 4
00300 (length,) = _struct_I.unpack(str[start:end])
00301 start = end
00302 end += length
00303 self.header.frame_id = str[start:end]
00304 start = end
00305 end += 4
00306 (length,) = _struct_I.unpack(str[start:end])
00307 start = end
00308 end += length
00309 self.ns = str[start:end]
00310 _x = self
00311 start = end
00312 end += 81
00313 (_x.id, _x.type, _x.action, _x.position.x, _x.position.y, _x.position.z, _x.scale, _x.outline_color.r, _x.outline_color.g, _x.outline_color.b, _x.outline_color.a, _x.filled, _x.fill_color.r, _x.fill_color.g, _x.fill_color.b, _x.fill_color.a, _x.lifetime.secs, _x.lifetime.nsecs,) = _struct_3i3d5fb4f2i.unpack(str[start:end])
00314 start = end
00315 end += 4
00316 (length,) = _struct_I.unpack(str[start:end])
00317 self.points = []
00318 for i in xrange(0, length):
00319 val1 = geometry_msgs.msg.Point()
00320 _x = val1
00321 start = end
00322 end += 24
00323 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00324 self.points.append(val1)
00325 start = end
00326 end += 4
00327 (length,) = _struct_I.unpack(str[start:end])
00328 self.outline_colors = []
00329 for i in xrange(0, length):
00330 val1 = std_msgs.msg.ColorRGBA()
00331 _x = val1
00332 start = end
00333 end += 16
00334 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00335 self.outline_colors.append(val1)
00336 self.lifetime.canon()
00337 return self
00338 except struct.error, e:
00339 raise roslib.message.DeserializationError(e)
00340
00341 _struct_I = roslib.message.struct_I
00342 _struct_4f = struct.Struct("<4f")
00343 _struct_3I = struct.Struct("<3I")
00344 _struct_3i3d5fb4f2i = struct.Struct("<3i3d5fb4f2i")
00345 _struct_3d = struct.Struct("<3d")