Class: Sensor_msgs::PointCloud2

Inherits:
ROS::Message
  • Object
show all
Defined in:
lib/sensor_msgs/PointCloud2.rb

Constant Summary collapse

@@struct_LCL =
::ROS::Struct.new("LCL")
@@struct_L3 =
::ROS::Struct.new("L3")
@@struct_C =
::ROS::Struct.new("C")
@@struct_L2 =
::ROS::Struct.new("L2")
@@struct_CL2 =
::ROS::Struct.new("CL2")
@@struct_L =
::ROS::Struct.new("L")
@@slot_types =
['Header','uint32','uint32','sensor_msgs/PointField[]','bool','uint32','uint32','uint8[]','bool']

Instance Attribute Summary collapse

Class Method Summary collapse

Instance Method Summary collapse

Constructor Details

#initialize(args = {}) ⇒ PointCloud2

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

Parameters:

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

    keyword for initializing values

Options Hash (args):

  • :header (Header)

    initialize value

  • :height (uint32)

    initialize value

  • :width (uint32)

    initialize value

  • :fields (sensor_msgs/PointField[])

    initialize value

  • :is_bigendian (bool)

    initialize value

  • :point_step (uint32)

    initialize value

  • :row_step (uint32)

    initialize value

  • :data (uint8[])

    initialize value

  • :is_dense (bool)

    initialize value



112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
# File 'lib/sensor_msgs/PointCloud2.rb', line 112

def initialize(args={})
  # message fields cannot be None, assign default values for those that are
  if args[:header]
    @header = args[:header]
  else
    @header = Std_msgs::Header.new
  end
  if args[:height]
    @height = args[:height]
  else
    @height = 0
  end
  if args[:width]
    @width = args[:width]
  else
    @width = 0
  end
  if args[:fields]
    @fields = args[:fields]
  else
    @fields = []
  end
  if args[:is_bigendian]
    @is_bigendian = args[:is_bigendian]
  else
    @is_bigendian = false
  end
  if args[:point_step]
    @point_step = args[:point_step]
  else
    @point_step = 0
  end
  if args[:row_step]
    @row_step = args[:row_step]
  else
    @row_step = 0
  end
  if args[:data]
    @data = args[:data]
  else
    @data = ''
  end
  if args[:is_dense]
    @is_dense = args[:is_dense]
  else
    @is_dense = false
  end
end

Instance Attribute Details

#dataObject

Returns the value of attribute data.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def data
  @data
end

#fieldsObject

Returns the value of attribute fields.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def fields
  @fields
end

#headerObject

Returns the value of attribute header.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def header
  @header
end

#heightObject

Returns the value of attribute height.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def height
  @height
end

#is_bigendianObject

Returns the value of attribute is_bigendian.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def is_bigendian
  @is_bigendian
end

#is_denseObject

Returns the value of attribute is_dense.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def is_dense
  @is_dense
end

#point_stepObject

Returns the value of attribute point_step.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def point_step
  @point_step
end

#row_stepObject

Returns the value of attribute row_step.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def row_step
  @row_step
end

#widthObject

Returns the value of attribute width.



89
90
91
# File 'lib/sensor_msgs/PointCloud2.rb', line 89

def width
  @width
end

Class Method Details

.md5sumObject



10
11
12
# File 'lib/sensor_msgs/PointCloud2.rb', line 10

def self.md5sum
  "1158d486dd51d683ce2f1be655c3c181"
end

.typeObject



14
15
16
# File 'lib/sensor_msgs/PointCloud2.rb', line 14

def self.type
  "sensor_msgs/PointCloud2"
end

Instance Method Details

#_get_typesString

internal API method

Returns:

  • (String)

    Message type string.



163
164
165
# File 'lib/sensor_msgs/PointCloud2.rb', line 163

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


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
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
# File 'lib/sensor_msgs/PointCloud2.rb', line 198

def deserialize(str)

  begin
    if @header == nil
      @header = Std_msgs::Header.new
    end
    end_point = 0
    start = end_point
    end_point += ROS::Struct::calc_size('L3')
    (@header.seq, @header.stamp.secs, @header.stamp.nsecs,) = @@struct_L3.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
    @header.frame_id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('L2')
    (@height, @width,) = @@struct_L2.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    @fields = []
    length.times do
      val1 = Sensor_msgs::PointField.new
      start = end_point
      end_point += 4
      (length,) = @@struct_L.unpack(str[start..(end_point-1)])
      start = end_point
      end_point += length
      val1.name = str[start..(end_point-1)]
      _x = val1
      start = end_point
      end_point += ROS::Struct::calc_size('LCL')
      (_x.offset, _x.datatype, _x.count,) = @@struct_LCL.unpack(str[start..(end_point-1)])
      @fields.push(val1)
    end
    start = end_point
    end_point += ROS::Struct::calc_size('CL2')
    (@is_bigendian, @point_step, @row_step,) = @@struct_CL2.unpack(str[start..(end_point-1)])
    @is_bigendian = bool(@is_bigendian)
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @data = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('C')
    (@is_dense,) = @@struct_C.unpack(str[start..(end_point-1)])
    @is_dense = bool(@is_dense)
    return self
  rescue => exception
    raise "message DeserializationError: #{exception}" #most likely buffer underfill
  end
end

#has_header?Boolean

Returns:

  • (Boolean)


18
19
20
# File 'lib/sensor_msgs/PointCloud2.rb', line 18

def has_header?
  true
end

#message_definitionObject



22
23
24
25
26
27
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
# File 'lib/sensor_msgs/PointCloud2.rb', line 22

def message_definition
  "# This message holds a collection of N-dimensional points, which may
# contain additional information such as normals, intensity, etc. The
# point data is stored as a binary blob, its layout described by the
# contents of the \"fields\" array.

# The point cloud data may be organized 2d (image-like) or 1d
# (unordered). Point clouds organized as 2d images may be produced by
# camera depth sensors such as stereo or time-of-flight.

# Time of sensor data acquisition, and the coordinate frame ID (for 3d
# points).
Header header

# 2D structure of the point cloud. If the cloud is unordered, height is
# 1 and width is the length of the point cloud.
uint32 height
uint32 width

# Describes the channels and their layout in the binary data blob.
PointField[] fields

bool    is_bigendian # Is this data bigendian?
uint32  point_step   # Length of a point in bytes
uint32  row_step     # Length of a row in bytes
uint8[] data         # Actual point data, size is (row_step*height)

bool is_dense        # True if there are no invalid points

================================================================================
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: sensor_msgs/PointField
# This message holds the description of one point entry in the
# PointCloud2 message format.
uint8 INT8    = 1
uint8 UINT8   = 2
uint8 INT16   = 3
uint8 UINT16  = 4
uint8 INT32   = 5
uint8 UINT32  = 6
uint8 FLOAT32 = 7
uint8 FLOAT64 = 8

string name      # Name of field
uint32 offset    # Offset from start of point struct
uint8  datatype  # Datatype enumeration, see above
uint32 count     # How many elements in the field

"
end

#serialize(buff) ⇒ Object

serialize message into buffer

Parameters:

  • buff (IO)

    buffer



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
# File 'lib/sensor_msgs/PointCloud2.rb', line 169

def serialize(buff)
  begin
    buff.write(@@struct_L3.pack(@header.seq, @header.stamp.secs, @header.stamp.nsecs))
    _x = @header.frame_id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_L2.pack(@height, @width))
    length = @fields.length
    buff.write(@@struct_L.pack(length))
    for val1 in @fields
      _x = val1.name
      length = _x.length
      buff.write([length, _x].pack("La#{length}"))
      _x = val1
      buff.write(@@struct_LCL.pack(_x.offset, _x.datatype, _x.count))
    end
    buff.write(@@struct_CL2.pack(@is_bigendian, @point_step, @row_step))
    _x = @data
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_C.pack(@is_dense))
  rescue => exception
    raise "some erro in serialize: #{exception}"

  end
end