Skip to content

Commit f2faa6d

Browse files
vickzkmasf7g
authored andcommitted
Update map_io library to use Eigen method for faster map loading (ros-navigation#5071)
* Update map_io library to use opencv method for faster map loading Signed-off-by: Vignesh T <[email protected]> * Update pre-commit config changes Signed-off-by: Vignesh T <[email protected]> * Use Eigen approach instead of OpenCV Signed-off-by: Vignesh T <[email protected]> * Update pre-commit changes Signed-off-by: Vignesh T <[email protected]> * Update include header include order Signed-off-by: Vignesh T <[email protected]> * Remove intermediary alpha matrix Signed-off-by: Vignesh T <[email protected]> * Add comments for the code understanding Signed-off-by: Vignesh T <[email protected]> * Fix else braces rule issue Signed-off-by: Vignesh T <[email protected]> * Create and use alpha_matrix when applying mask Signed-off-by: Vignesh T <[email protected]> * Update pre-commit changes Signed-off-by: Vignesh T <[email protected]> * Take flip part out of if-else Signed-off-by: Vignesh T <[email protected]> * Update pre-commit changes Signed-off-by: Vignesh T <[email protected]> --------- Signed-off-by: Vignesh T <[email protected]>
1 parent dacfc42 commit f2faa6d

File tree

1 file changed

+100
-62
lines changed

1 file changed

+100
-62
lines changed

nav2_map_server/src/map_io.cpp

Lines changed: 100 additions & 62 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,9 @@
3434
#ifndef _WIN32
3535
#include <libgen.h>
3636
#endif
37+
38+
#include <Eigen/Dense>
39+
3740
#include <iostream>
3841
#include <string>
3942
#include <vector>
@@ -224,72 +227,107 @@ void loadMapFromFile(
224227
// Allocate space to hold the data
225228
msg.data.resize(msg.info.width * msg.info.height);
226229

227-
// Copy pixel data into the map structure
228-
for (size_t y = 0; y < msg.info.height; y++) {
229-
for (size_t x = 0; x < msg.info.width; x++) {
230-
auto pixel = img.pixelColor(x, y);
231-
232-
std::vector<Magick::Quantum> channels = {pixel.redQuantum(), pixel.greenQuantum(),
233-
pixel.blueQuantum()};
234-
if (load_parameters.mode == MapMode::Trinary && img.matte()) {
235-
// To preserve existing behavior, average in alpha with color channels in Trinary mode.
236-
// CAREFUL. alpha is inverted from what you might expect. High = transparent, low = opaque
237-
channels.push_back(MaxRGB - pixel.alphaQuantum());
238-
}
239-
double sum = 0;
240-
for (auto c : channels) {
241-
sum += c;
242-
}
243-
/// on a scale from 0.0 to 1.0 how bright is the pixel?
244-
double shade = Magick::ColorGray::scaleQuantumToDouble(sum / channels.size());
245-
246-
// If negate is true, we consider blacker pixels free, and whiter
247-
// pixels occupied. Otherwise, it's vice versa.
248-
/// on a scale from 0.0 to 1.0, how occupied is the map cell (before thresholding)?
249-
double occ = (load_parameters.negate ? shade : 1.0 - shade);
250-
251-
int8_t map_cell;
252-
switch (load_parameters.mode) {
253-
case MapMode::Trinary:
254-
if (load_parameters.occupied_thresh < occ) {
255-
map_cell = nav2_util::OCC_GRID_OCCUPIED;
256-
} else if (occ < load_parameters.free_thresh) {
257-
map_cell = nav2_util::OCC_GRID_FREE;
258-
} else {
259-
map_cell = nav2_util::OCC_GRID_UNKNOWN;
260-
}
261-
break;
262-
case MapMode::Scale:
263-
if (pixel.alphaQuantum() != OpaqueOpacity) {
264-
map_cell = nav2_util::OCC_GRID_UNKNOWN;
265-
} else if (load_parameters.occupied_thresh < occ) {
266-
map_cell = nav2_util::OCC_GRID_OCCUPIED;
267-
} else if (occ < load_parameters.free_thresh) {
268-
map_cell = nav2_util::OCC_GRID_FREE;
269-
} else {
270-
map_cell = std::rint(
271-
(occ - load_parameters.free_thresh) /
272-
(load_parameters.occupied_thresh - load_parameters.free_thresh) * 100.0);
273-
}
274-
break;
275-
case MapMode::Raw: {
276-
double occ_percent = std::round(shade * 255);
277-
if (nav2_util::OCC_GRID_FREE <= occ_percent &&
278-
occ_percent <= nav2_util::OCC_GRID_OCCUPIED)
279-
{
280-
map_cell = static_cast<int8_t>(occ_percent);
281-
} else {
282-
map_cell = nav2_util::OCC_GRID_UNKNOWN;
283-
}
284-
break;
285-
}
286-
default:
287-
throw std::runtime_error("Invalid map mode");
230+
// Convert the image to grayscale
231+
Magick::Image gray = img;
232+
gray.type(Magick::GrayscaleType);
233+
234+
// Prepare grayscale matrix from image
235+
size_t width = gray.columns();
236+
size_t height = gray.rows();
237+
238+
std::vector<uint8_t> buffer(width * height);
239+
gray.write(0, 0, width, height, "I", Magick::CharPixel, buffer.data());
240+
241+
// Map the grayscale buffer to an Eigen matrix (row-major layout)
242+
Eigen::Map<Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>>
243+
gray_matrix(buffer.data(), height, width);
244+
245+
bool has_alpha = img.matte();
246+
247+
// Handle different map modes with if else condition
248+
// Trinary and Scale modes are handled together
249+
// because they share a lot of code
250+
// Raw mode is handled separately in else if block
251+
Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> result(height, width);
252+
253+
if (load_parameters.mode == MapMode::Trinary || load_parameters.mode == MapMode::Scale) {
254+
// Convert grayscale to float in range [0.0, 1.0]
255+
Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic,
256+
Eigen::RowMajor> normalized = gray_matrix.cast<float>() / 255.0f;
257+
258+
// Negate the image if specified (e.g. for black=occupied vs. white=occupied convention)
259+
if (!load_parameters.negate) {
260+
normalized = (1.0f - normalized.array()).matrix();
261+
}
262+
263+
// Compute binary occupancy masks
264+
Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> occupied =
265+
(normalized.array() >= load_parameters.occupied_thresh).cast<uint8_t>();
266+
267+
Eigen::Matrix<uint8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> free =
268+
(normalized.array() <= load_parameters.free_thresh).cast<uint8_t>();
269+
270+
// Initialize occupancy grid with UNKNOWN values (-1)
271+
result.setConstant(nav2_util::OCC_GRID_UNKNOWN);
272+
273+
// Apply occupied and free cell updates
274+
result = (occupied.array() > 0).select(nav2_util::OCC_GRID_OCCUPIED, result);
275+
result = (free.array() > 0).select(nav2_util::OCC_GRID_FREE, result);
276+
277+
// Handle intermediate (gray) values if in Scale mode
278+
if (load_parameters.mode == MapMode::Scale) {
279+
// Create in-between mask
280+
auto in_between_mask = (normalized.array() > load_parameters.free_thresh) &&
281+
(normalized.array() < load_parameters.occupied_thresh);
282+
283+
if (in_between_mask.any()) {
284+
// Scale in-between values to [0,100] range
285+
Eigen::ArrayXXf scaled_float = ((normalized.array() - load_parameters.free_thresh) /
286+
(load_parameters.occupied_thresh - load_parameters.free_thresh)) * 100.0f;
287+
288+
// Round and cast to int8_t
289+
Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> scaled_int =
290+
scaled_float.array().round().cast<int8_t>();
291+
292+
result = in_between_mask.select(scaled_int, result);
288293
}
289-
msg.data[msg.info.width * (msg.info.height - y - 1) + x] = map_cell;
290294
}
295+
296+
// Apply alpha transparency mask: mark transparent cells as UNKNOWN
297+
if (has_alpha) {
298+
// Allocate buffer only once and map directly to Eigen without extra copy
299+
std::vector<uint8_t> alpha_buf(width * height);
300+
img.write(0, 0, width, height, "A", Magick::CharPixel, alpha_buf.data());
301+
302+
// Map alpha buffer as Eigen::Array for efficient elementwise ops
303+
Eigen::Map<Eigen::Array<uint8_t, Eigen::Dynamic, Eigen::Dynamic,
304+
Eigen::RowMajor>> alpha_array(
305+
alpha_buf.data(), height, width);
306+
307+
// Apply mask directly with Eigen::select
308+
result = (alpha_array < 255).select(nav2_util::OCC_GRID_UNKNOWN, result);
309+
}
310+
311+
} else if (load_parameters.mode == MapMode::Raw) {
312+
// Raw mode: interpret raw image pixel values directly as occupancy values
313+
result = gray_matrix.cast<int8_t>();
314+
315+
// Clamp out-of-bound values (outside [-1, 100]) to UNKNOWN (-1)
316+
auto out_of_bounds = (result.array() < nav2_util::OCC_GRID_FREE) ||
317+
(result.array() > nav2_util::OCC_GRID_OCCUPIED);
318+
319+
result = out_of_bounds.select(nav2_util::OCC_GRID_UNKNOWN, result);
320+
321+
} else {
322+
// If the map mode is not recognized, throw an error
323+
throw std::runtime_error("Invalid map mode");
291324
}
292325

326+
// Flip image vertically (as ROS expects origin at bottom-left)
327+
Eigen::Matrix<int8_t, Eigen::Dynamic, Eigen::Dynamic,
328+
Eigen::RowMajor> flipped = result.colwise().reverse();
329+
std::memcpy(msg.data.data(), flipped.data(), width * height);
330+
293331
// Since loadMapFromFile() does not belong to any node, publishing in a system time.
294332
rclcpp::Clock clock(RCL_SYSTEM_TIME);
295333
msg.info.map_load_time = clock.now();

0 commit comments

Comments
 (0)