Skip to content

Commit 8d69483

Browse files
authored
Update map_io library to use Eigen method for faster map loading (#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 5423eba commit 8d69483

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>
@@ -225,72 +228,107 @@ void loadMapFromFile(
225228
// Allocate space to hold the data
226229
msg.data.resize(msg.info.width * msg.info.height);
227230

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

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

0 commit comments

Comments
 (0)