Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

map_saver: fix saved raw image being too dark #4712

27 changes: 20 additions & 7 deletions nav2_map_server/src/map_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -501,14 +501,27 @@ void tryWriteMapToFile(
}
break;
case MapMode::Raw:
Magick::Quantum q;
if (map_cell < 0 || 100 < map_cell) {
q = MaxRGB;
} else {
q = map_cell / 255.0 * MaxRGB;
{
double cell_cost;
if (map_cell >= nav2_util::OCC_GRID_FREE &&
map_cell <= nav2_util::OCC_GRID_OCCUPIED)
{
// Linear conversion from OccupancyGrid data range[OCC_GRID_FREE-OCC_GRID_OCCUPIED]
// to costmap data range [FREE_SPACE-LETHAL_OBSTACLE]
uint8_t lethal_obstacle_cost = 254; // nav2_costmap_2d::LETHAL_OBSTACLE
uint8_t free_space_cost = 0; // nav2_costmap_2d::FREE_SPACE
cell_cost = static_cast<double>(map_cell) *
(lethal_obstacle_cost - free_space_cost) /
(nav2_util::OCC_GRID_OCCUPIED - nav2_util::OCC_GRID_FREE);
} else {
// nav2_util::OCC_GRID_UNKNOWN or other invalid values
uint8_t no_information_cost = 255; // nav2_costmap_2d::NO_INFORMATION
cell_cost = no_information_cost;
}
Magick::Quantum q = std::round((cell_cost / 255.) * MaxRGB);
pixel = Magick::Color(q, q, q);
break;
}
pixel = Magick::Color(q, q, q);
break;
default:
std::cerr << "[ERROR] [map_io]: Map mode should be Trinary, Scale or Raw" << std::endl;
throw std::runtime_error("Invalid map mode");
Expand Down
Loading