Class: Nav_msgs::GetMapResponse

Inherits:
ROS::Message
  • Object
show all
Defined in:
lib/nav_msgs/GetMap.rb

Constant Summary collapse

@@struct_L3 =
::ROS::Struct.new("L3")
@@struct_L2fL2d7 =
::ROS::Struct.new("L2fL2d7")
@@struct_L =
::ROS::Struct.new("L")
@@slot_types =
['nav_msgs/OccupancyGrid']

Instance Attribute Summary collapse

Class Method Summary collapse

Instance Method Summary collapse

Constructor Details

#initialize(args = {}) ⇒ GetMapResponse

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

Parameters:

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

    keyword for initializing values

Options Hash (args):



180
181
182
183
184
185
186
187
# File 'lib/nav_msgs/GetMap.rb', line 180

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

Instance Attribute Details

#mapObject

Returns the value of attribute map.



168
169
170
# File 'lib/nav_msgs/GetMap.rb', line 168

def map
  @map
end

Class Method Details

.md5sumObject



81
82
83
# File 'lib/nav_msgs/GetMap.rb', line 81

def self.md5sum
  "6cdd0a18e0aff5b0a3ca2326a89b54ff"
end

.typeObject



85
86
87
# File 'lib/nav_msgs/GetMap.rb', line 85

def self.type
  "nav_msgs/GetMapResponse"
end

Instance Method Details

#_get_typesString

internal API method

Returns:

  • (String)

    Message type string.



191
192
193
# File 'lib/nav_msgs/GetMap.rb', line 191

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


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
# File 'lib/nav_msgs/GetMap.rb', line 216

def deserialize(str)

  begin
    if @map == nil
      @map = Nav_msgs::OccupancyGrid.new
    end
    end_point = 0
    start = end_point
    end_point += ROS::Struct::calc_size('L3')
    (@map.header.seq, @map.header.stamp.secs, @map.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
    @map.header.frame_id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('L2fL2d7')
    (@map.info.map_load_time.secs, @map.info.map_load_time.nsecs, @map.info.resolution, @map.info.width, @map.info.height, @map.info.origin.position.x, @map.info.origin.position.y, @map.info.origin.position.z, @map.info.origin.orientation.x, @map.info.origin.orientation.y, @map.info.origin.orientation.z, @map.info.origin.orientation.w,) = @@struct_L2fL2d7.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    pattern = "c#{length}"
    start = end_point
    end_point += ROS::Struct::calc_size("#{pattern}")
    @map.data = str[start..(end_point-1)].unpack(pattern)
    return self
  rescue => exception
    raise "message DeserializationError: #{exception}" #most likely buffer underfill
  end
end

#has_header?Boolean

Returns:

  • (Boolean)


89
90
91
# File 'lib/nav_msgs/GetMap.rb', line 89

def has_header?
  false
end

#message_definitionObject



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
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
160
161
162
163
164
165
166
167
# File 'lib/nav_msgs/GetMap.rb', line 93

def message_definition
  "nav_msgs/OccupancyGrid map


================================================================================
MSG: nav_msgs/OccupancyGrid
# This represents a 2-D grid map, in which each cell represents the probability of
# occupancy.

Header header 

#MetaData for the map
MapMetaData info

# The map data, in row-major order, starting with (0,0).  Occupancy
# probabilities are in the range [0,100].  Unknown is -1.
int8[] data

================================================================================
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: nav_msgs/MapMetaData
# This hold basic information about the characterists of the OccupancyGrid

# The time at which the map was loaded
time map_load_time
# The map resolution [m/cell]
float32 resolution
# Map width [cells]
uint32 width
# Map height [cells]
uint32 height
# The origin of the map [m, m, rad].  This is the real-world pose of the
# cell (0,0) in the map.
geometry_msgs/Pose origin
================================================================================
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

"
end

#serialize(buff) ⇒ Object

serialize message into buffer

Parameters:

  • buff (IO)

    buffer



197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
# File 'lib/nav_msgs/GetMap.rb', line 197

def serialize(buff)
  begin
    buff.write(@@struct_L3.pack(@map.header.seq, @map.header.stamp.secs, @map.header.stamp.nsecs))
    _x = @map.header.frame_id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_L2fL2d7.pack(@map.info.map_load_time.secs, @map.info.map_load_time.nsecs, @map.info.resolution, @map.info.width, @map.info.height, @map.info.origin.position.x, @map.info.origin.position.y, @map.info.origin.position.z, @map.info.origin.orientation.x, @map.info.origin.orientation.y, @map.info.origin.orientation.z, @map.info.origin.orientation.w))
    length = @map.data.length
    buff.write(@@struct_L.pack(length))
    pattern = "c#{length}"
    buff.write(*@map.data.pack(pattern))
  rescue => exception
    raise "some erro in serialize: #{exception}"

  end
end