Class: Visualization_msgs::MarkerArray

Inherits:
ROS::Message
  • Object
show all
Defined in:
lib/visualization_msgs/MarkerArray.rb

Constant Summary collapse

@@struct_C =
::ROS::Struct.new("C")
@@struct_l2 =
::ROS::Struct.new("l2")
@@struct_l3 =
::ROS::Struct.new("l3")
@@struct_f4 =
::ROS::Struct.new("f4")
@@struct_d4 =
::ROS::Struct.new("d4")
@@struct_L2 =
::ROS::Struct.new("L2")
@@struct_d3 =
::ROS::Struct.new("d3")
@@struct_L =
::ROS::Struct.new("L")
@@slot_types =
['visualization_msgs/Marker[]']

Instance Attribute Summary collapse

Class Method Summary collapse

Instance Method Summary collapse

Constructor Details

#initialize(args = {}) ⇒ MarkerArray

Constructor. You can set the default values using keyword operators.

Parameters:

  • args (Hash) (defaults to: {})

    keyword for initializing values

Options Hash (args):

  • :markers (visualization_msgs/Marker[])

    initialize value



150
151
152
153
154
155
156
157
# File 'lib/visualization_msgs/MarkerArray.rb', line 150

def initialize(args={})
  # message fields cannot be None, assign default values for those that are
  if args[:markers]
    @markers = args[:markers]
  else
    @markers = []
  end
end

Instance Attribute Details

#markersObject

Returns the value of attribute markers.



133
134
135
# File 'lib/visualization_msgs/MarkerArray.rb', line 133

def markers
  @markers
end

Class Method Details

.md5sumObject



16
17
18
# File 'lib/visualization_msgs/MarkerArray.rb', line 16

def self.md5sum
  "90da67007c26525f655c1c269094e39f"
end

.typeObject



20
21
22
# File 'lib/visualization_msgs/MarkerArray.rb', line 20

def self.type
  "visualization_msgs/MarkerArray"
end

Instance Method Details

#_get_typesString

internal API method

Returns:

  • (String)

    Message type string.



161
162
163
# File 'lib/visualization_msgs/MarkerArray.rb', line 161

def _get_types
  @slot_types
end

#deserialize(str) ⇒ Object

unpack serialized message in str into this message instance

@param [String] str: byte array of serialized message


230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
# File 'lib/visualization_msgs/MarkerArray.rb', line 230

def deserialize(str)

  begin
    end_point = 0
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    @markers = []
    length.times do
      val1 = Visualization_msgs::Marker.new
      _v35 = val1.header
      start = end_point
      end_point += ROS::Struct::calc_size('L')
      (_v35.seq,) = @@struct_L.unpack(str[start..(end_point-1)])
      _v36 = _v35.stamp
      _x = _v36
      start = end_point
      end_point += ROS::Struct::calc_size('L2')
      (_x.secs, _x.nsecs,) = @@struct_L2.unpack(str[start..(end_point-1)])
      start = end_point
      end_point += 4
      (length,) = @@struct_L.unpack(str[start..(end_point-1)])
      start = end_point
      end_point += length
      _v35.frame_id = str[start..(end_point-1)]
      start = end_point
      end_point += 4
      (length,) = @@struct_L.unpack(str[start..(end_point-1)])
      start = end_point
      end_point += length
      val1.ns = str[start..(end_point-1)]
      _x = val1
      start = end_point
      end_point += ROS::Struct::calc_size('l3')
      (_x.id, _x.type, _x.action,) = @@struct_l3.unpack(str[start..(end_point-1)])
      _v37 = val1.pose
      _v38 = _v37.position
      _x = _v38
      start = end_point
      end_point += ROS::Struct::calc_size('d3')
      (_x.x, _x.y, _x.z,) = @@struct_d3.unpack(str[start..(end_point-1)])
      _v39 = _v37.orientation
      _x = _v39
      start = end_point
      end_point += ROS::Struct::calc_size('d4')
      (_x.x, _x.y, _x.z, _x.w,) = @@struct_d4.unpack(str[start..(end_point-1)])
      _v40 = val1.scale
      _x = _v40
      start = end_point
      end_point += ROS::Struct::calc_size('d3')
      (_x.x, _x.y, _x.z,) = @@struct_d3.unpack(str[start..(end_point-1)])
      _v41 = val1.color
      _x = _v41
      start = end_point
      end_point += ROS::Struct::calc_size('f4')
      (_x.r, _x.g, _x.b, _x.a,) = @@struct_f4.unpack(str[start..(end_point-1)])
      _v42 = val1.lifetime
      _x = _v42
      start = end_point
      end_point += ROS::Struct::calc_size('l2')
      (_x.secs, _x.nsecs,) = @@struct_l2.unpack(str[start..(end_point-1)])
      start = end_point
      end_point += ROS::Struct::calc_size('C')
      (val1.frame_locked,) = @@struct_C.unpack(str[start..(end_point-1)])
      val1.frame_locked = bool(val1.frame_locked)
      start = end_point
      end_point += 4
      (length,) = @@struct_L.unpack(str[start..(end_point-1)])
      val1.points = []
      length.times do
        val2 = Geometry_msgs::Point.new
        _x = val2
        start = end_point
        end_point += ROS::Struct::calc_size('d3')
        (_x.x, _x.y, _x.z,) = @@struct_d3.unpack(str[start..(end_point-1)])
        val1.points.push(val2)
      end
      start = end_point
      end_point += 4
      (length,) = @@struct_L.unpack(str[start..(end_point-1)])
      val1.colors = []
      length.times do
        val2 = Std_msgs::ColorRGBA.new
        _x = val2
        start = end_point
        end_point += ROS::Struct::calc_size('f4')
        (_x.r, _x.g, _x.b, _x.a,) = @@struct_f4.unpack(str[start..(end_point-1)])
        val1.colors.push(val2)
      end
      start = end_point
      end_point += 4
      (length,) = @@struct_L.unpack(str[start..(end_point-1)])
      start = end_point
      end_point += length
      val1.text = str[start..(end_point-1)]
      start = end_point
      end_point += 4
      (length,) = @@struct_L.unpack(str[start..(end_point-1)])
      start = end_point
      end_point += length
      val1.mesh_resource = str[start..(end_point-1)]
      start = end_point
      end_point += ROS::Struct::calc_size('C')
      (val1.mesh_use_embedded_materials,) = @@struct_C.unpack(str[start..(end_point-1)])
      val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
      @markers.push(val1)
    end
    return self
  rescue => exception
    raise "message DeserializationError: #{exception}" #most likely buffer underfill
  end
end

#has_header?Boolean

Returns:

  • (Boolean)


24
25
26
# File 'lib/visualization_msgs/MarkerArray.rb', line 24

def has_header?
  false
end

#message_definitionObject



28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
# File 'lib/visualization_msgs/MarkerArray.rb', line 28

def message_definition
  "Marker[] markers

================================================================================
MSG: visualization_msgs/Marker
# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz

uint8 ARROW=0
uint8 CUBE=1
uint8 SPHERE=2
uint8 CYLINDER=3
uint8 LINE_STRIP=4
uint8 LINE_LIST=5
uint8 CUBE_LIST=6
uint8 SPHERE_LIST=7
uint8 POINTS=8
uint8 TEXT_VIEW_FACING=9
uint8 MESH_RESOURCE=10
uint8 TRIANGLE_LIST=11

uint8 ADD=0
uint8 MODIFY=0
uint8 DELETE=2

Header header                        # header for time/frame information
string ns                            # Namespace to place this object in... used in conjunction with id to create a unique name for the object
int32 id 		                         # object ID useful in conjunction with the namespace for manipulating and deleting the object later
int32 type 		                       # Type of object
int32 action 	                       # 0 add/modify an object, 1 (deprecated), 2 deletes an object
geometry_msgs/Pose pose                 # Pose of the object
geometry_msgs/Vector3 scale             # Scale of the object 1,1,1 means default (usually 1 meter square)
std_msgs/ColorRGBA color             # Color [0.0-1.0]
duration lifetime                    # How long the object should last before being automatically deleted.  0 means forever
bool frame_locked                    # If this marker should be frame-locked, i.e. retransformed into its frame every timestep

#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
geometry_msgs/Point[] points
#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
#number of colors must either be 0 or equal to the number of points
#NOTE: alpha is not yet used
std_msgs/ColorRGBA[] colors

# NOTE: only used for text markers
string text

# NOTE: only used for MESH_RESOURCE markers
string mesh_resource
bool mesh_use_embedded_materials

================================================================================
MSG: std_msgs/Header
# Standard metadata for higher-level stamped data types.
# This is generally used to communicate timestamped data 
# in a particular coordinate frame.
# 
# sequence ID: consecutively increasing ID 
uint32 seq
#Two-integer timestamp that is expressed as:
# * stamp.secs: seconds (stamp_secs) since epoch
# * stamp.nsecs: nanoseconds since stamp_secs
# time-handling sugar is provided by the client library
time stamp
#Frame this data is associated with
# 0: no frame
# 1: global frame
string frame_id

================================================================================
MSG: geometry_msgs/Pose
# A representation of pose in free space, composed of postion and orientation. 
Point position
Quaternion orientation

================================================================================
MSG: geometry_msgs/Point
# This contains the position of a point in free space
float64 x
float64 y
float64 z

================================================================================
MSG: geometry_msgs/Quaternion
# This represents an orientation in free space in quaternion form.

float64 x
float64 y
float64 z
float64 w

================================================================================
MSG: geometry_msgs/Vector3
# This represents a vector in free space. 

float64 x
float64 y
float64 z
================================================================================
MSG: std_msgs/ColorRGBA
float32 r
float32 g
float32 b
float32 a

"
end

#serialize(buff) ⇒ Object

serialize message into buffer

Parameters:

  • buff (IO)

    buffer



167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
# File 'lib/visualization_msgs/MarkerArray.rb', line 167

def serialize(buff)
  begin
    length = @markers.length
    buff.write(@@struct_L.pack(length))
    for val1 in @markers
      _v27 = val1.header
      buff.write(@@struct_L.pack(_v27.seq))
      _v28 = _v27.stamp
      _x = _v28
      buff.write(@@struct_L2.pack(_x.secs, _x.nsecs))
      _x = _v27.frame_id
      length = _x.length
      buff.write([length, _x].pack("La#{length}"))
      _x = val1.ns
      length = _x.length
      buff.write([length, _x].pack("La#{length}"))
      _x = val1
      buff.write(@@struct_l3.pack(_x.id, _x.type, _x.action))
      _v29 = val1.pose
      _v30 = _v29.position
      _x = _v30
      buff.write(@@struct_d3.pack(_x.x, _x.y, _x.z))
      _v31 = _v29.orientation
      _x = _v31
      buff.write(@@struct_d4.pack(_x.x, _x.y, _x.z, _x.w))
      _v32 = val1.scale
      _x = _v32
      buff.write(@@struct_d3.pack(_x.x, _x.y, _x.z))
      _v33 = val1.color
      _x = _v33
      buff.write(@@struct_f4.pack(_x.r, _x.g, _x.b, _x.a))
      _v34 = val1.lifetime
      _x = _v34
      buff.write(@@struct_l2.pack(_x.secs, _x.nsecs))
      buff.write(@@struct_C.pack(val1.frame_locked))
      length = val1.points.length
      buff.write(@@struct_L.pack(length))
      for val2 in val1.points
        _x = val2
        buff.write(@@struct_d3.pack(_x.x, _x.y, _x.z))
      end
      length = val1.colors.length
      buff.write(@@struct_L.pack(length))
      for val2 in val1.colors
        _x = val2
        buff.write(@@struct_f4.pack(_x.r, _x.g, _x.b, _x.a))
      end
      _x = val1.text
      length = _x.length
      buff.write([length, _x].pack("La#{length}"))
      _x = val1.mesh_resource
      length = _x.length
      buff.write([length, _x].pack("La#{length}"))
      buff.write(@@struct_C.pack(val1.mesh_use_embedded_materials))
    end
  rescue => exception
    raise "some erro in serialize: #{exception}"

  end
end