Skip to content

Commit 049ed8f

Browse files
committed
Add comments for the code understanding
Signed-off-by: Vignesh T <[email protected]>
1 parent a1e2e55 commit 049ed8f

File tree

1 file changed

+30
-4
lines changed

1 file changed

+30
-4
lines changed

nav2_map_server/src/map_io.cpp

Lines changed: 30 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -232,81 +232,107 @@ void loadMapFromFile(
232232
Magick::Image gray = img;
233233
gray.type(Magick::GrayscaleType);
234234

235-
// Convert image data into occupancy grid data
235+
// Prepare grayscale matrix from image
236236
size_t width = gray.columns();
237237
size_t height = gray.rows();
238238

239239
std::vector<uint8_t> buffer(width * height);
240240
gray.write(0, 0, width, height, "I", Magick::CharPixel, buffer.data());
241241

242+
// Map the grayscale buffer to an Eigen matrix (row-major layout)
242243
Eigen::Map<Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>
243244
gray_matrix(buffer.data(), height, width);
244245

246+
// Prepare alpha (transparency) matrix, if present
245247
bool has_alpha = img.matte();
246248
Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> alpha_matrix;
247249

248250
if (has_alpha) {
249251
std::vector<uint8_t> alpha_buf(width * height);
250252
img.write(0, 0, width, height, "A", Magick::CharPixel, alpha_buf.data());
251253

252-
alpha_matrix = Eigen::Map<Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>(
254+
alpha_matrix = Eigen::Map<Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic,
255+
Eigen::RowMajor>>(
253256
alpha_buf.data(), height, width);
254257
}
255258

259+
// Handle different map modes with if else condition
260+
// Trinary and Scale modes are handled together
261+
// because they share a lot of code
256262
if (load_parameters.mode == MapMode::Trinary || load_parameters.mode == MapMode::Scale) {
263+
// Convert grayscale to float in range [0.0, 1.0]
257264
Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic,
258265
Eigen::RowMajor> normalized = gray_matrix.cast<float>() / 255.0f;
266+
267+
// Negate the image if specified (e.g. for black=occupied vs. white=occupied convention)
259268
if (!load_parameters.negate) {
260269
normalized = (1.0f - normalized.array()).matrix();
261270
}
262271

272+
// Compute binary occupancy masks
263273
Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> occupied =
264274
(normalized.array() >= load_parameters.occupied_thresh).cast<uint8_t>();
265275

266276
Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> free =
267277
(normalized.array() <= load_parameters.free_thresh).cast<uint8_t>();
268278

279+
// Initialize occupancy grid with UNKNOWN values (-1)
269280
Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> result(height, width);
270281
result.setConstant(nav2_util::OCC_GRID_UNKNOWN);
271282

283+
// Apply occupied and free cell updates
272284
result = (occupied.array() > 0).select(nav2_util::OCC_GRID_OCCUPIED, result);
273285
result = (free.array() > 0).select(nav2_util::OCC_GRID_FREE, result);
274286

287+
// Handle intermediate (gray) values if in Scale mode
275288
if (load_parameters.mode == MapMode::Scale) {
276289
// Create in-between mask
277290
auto in_between_mask = (normalized.array() > load_parameters.free_thresh) &&
278291
(normalized.array() < load_parameters.occupied_thresh);
279292

280293
if (in_between_mask.any()) {
294+
// Scale in-between values to [0,100] range
281295
Eigen::ArrayXXf scaled_float = ((normalized.array() - load_parameters.free_thresh) /
282296
(load_parameters.occupied_thresh - load_parameters.free_thresh)) * 100.0f;
297+
298+
// Round and cast to int8_t
283299
Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> scaled_int =
284300
scaled_float.array().round().cast<int8_t>();
301+
285302
result = in_between_mask.select(scaled_int, result);
286303
}
287304
}
288305

306+
// Apply alpha transparency mask: mark transparent cells as UNKNOWN
289307
if (has_alpha) {
290308
auto transparent_mask = (alpha_matrix.array() < 255);
291309
result = transparent_mask.select(nav2_util::OCC_GRID_UNKNOWN, result);
292310
}
293311

312+
// Flip image vertically (as ROS expects origin at bottom-left)
294313
Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic,
295314
Eigen::RowMajor> flipped = result.colwise().reverse();
296315
std::memcpy(msg.data.data(), flipped.data(), width * height);
297-
} else if (load_parameters.mode == MapMode::Raw) {
316+
}
317+
// Raw mode is handled separately in else if block
318+
else if (load_parameters.mode == MapMode::Raw) {
319+
// Raw mode: interpret raw image pixel values directly as occupancy values
298320
Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> result =
299321
gray_matrix.cast<int8_t>();
300322

323+
// Clamp out-of-bound values (outside [-1, 100]) to UNKNOWN (-1)
301324
auto out_of_bounds = (result.array() < nav2_util::OCC_GRID_FREE) ||
302325
(result.array() > nav2_util::OCC_GRID_OCCUPIED);
303326

304327
result = out_of_bounds.select(nav2_util::OCC_GRID_UNKNOWN, result);
305328

329+
// Flip image vertically (as ROS expects origin at bottom-left)
306330
Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic,
307331
Eigen::RowMajor> flipped = result.colwise().reverse();
308332
std::memcpy(msg.data.data(), flipped.data(), width * height);
309-
} else {
333+
}
334+
// If the map mode is not recognized, throw an error
335+
else {
310336
throw std::runtime_error("Invalid map mode");
311337
}
312338

0 commit comments

Comments
 (0)