Skip to content

Commit 2de31d7

Browse files
author
Matt Hansen
authored
Port map_saver (#462)
* Straight copy of map saver from map_server 1.16.2 * First port of map_saver to ROS2 * map_saver builds for ROS2 * Make map_saver pass ament_cpplint * Install map_saver * Added tf2 to package.xml for rosdep * Remove commented out code from CMakeLists * Fix map_saver to exit correctly * Address code review feedback * Change CMakeLists to follow better flow * Disable uncrustify due to timeout * Re-enable uncrustify * Reformat for uncrustify to pass
1 parent 4cd0968 commit 2de31d7

File tree

3 files changed

+225
-9
lines changed

3 files changed

+225
-9
lines changed

nav2_map_server/CMakeLists.txt

Lines changed: 27 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ find_package(SDL REQUIRED)
1818
find_package(SDL_image REQUIRED)
1919
find_package(yaml_cpp_vendor REQUIRED)
2020
find_package(std_msgs REQUIRED)
21+
find_package(tf2 REQUIRED)
2122

2223
include_directories(
2324
include
@@ -26,35 +27,51 @@ include_directories(
2627
${SDL_IMAGE_INCLUDE_DIRS}
2728
)
2829

29-
set(executable_name map_server)
30+
set(map_server_executable map_server)
3031

31-
add_executable(${executable_name}
32+
set(map_saver_executable map_saver)
33+
34+
add_executable(${map_server_executable}
3235
src/main.cpp
3336
)
3437

35-
set(library_name ${executable_name}_core)
38+
add_executable(${map_saver_executable}
39+
src/map_saver.cpp
40+
)
41+
42+
set(library_name ${map_server_executable}_core)
3643

3744
add_library(${library_name} SHARED
3845
src/occ_grid_loader.cpp
3946
src/map_server.cpp
4047
)
4148

42-
set(dependencies
49+
set(map_server_dependencies
4350
rclcpp
4451
nav_msgs
4552
yaml_cpp_vendor
4653
std_msgs
4754
)
4855

49-
ament_target_dependencies(${executable_name}
50-
${dependencies}
56+
set(map_saver_dependencies
57+
rclcpp
58+
nav_msgs
59+
tf2
60+
)
61+
62+
ament_target_dependencies(${map_server_executable}
63+
${map_server_dependencies}
64+
)
65+
66+
ament_target_dependencies(${map_saver_executable}
67+
${map_saver_dependencies}
5168
)
5269

5370
ament_target_dependencies(${library_name}
54-
${dependencies}
71+
${map_server_dependencies}
5572
)
5673

57-
target_link_libraries(${executable_name}
74+
target_link_libraries(${map_server_executable}
5875
${library_name}
5976
)
6077

@@ -63,7 +80,8 @@ target_link_libraries(${library_name}
6380
${SDL_LIBRARY}
6481
${SDL_IMAGE_LIBRARIES}
6582
)
66-
install(TARGETS ${executable_name} ${library_name}
83+
84+
install(TARGETS ${map_server_executable} ${library_name} ${map_saver_executable}
6785
ARCHIVE DESTINATION lib
6886
LIBRARY DESTINATION lib
6987
RUNTIME DESTINATION lib/${PROJECT_NAME}

nav2_map_server/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
<depend>yaml_cpp_vendor</depend>
2121
<depend>launch_ros</depend>
2222
<depend>launch_testing</depend>
23+
<depend>tf2</depend>
2324

2425
<test_depend>ament_lint_common</test_depend>
2526
<test_depend>ament_lint_auto</test_depend>

nav2_map_server/src/map_saver.cpp

Lines changed: 197 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,197 @@
1+
/*
2+
* map_saver
3+
* Copyright (c) 2008, Willow Garage, Inc.
4+
* All rights reserved.
5+
*
6+
* Redistribution and use in source and binary forms, with or without
7+
* modification, are permitted provided that the following conditions are met:
8+
*
9+
* * Redistributions of source code must retain the above copyright
10+
* notice, this list of conditions and the following disclaimer.
11+
* * Redistributions in binary form must reproduce the above copyright
12+
* notice, this list of conditions and the following disclaimer in the
13+
* documentation and/or other materials provided with the distribution.
14+
* * Neither the name of the <ORGANIZATION> nor the names of its
15+
* contributors may be used to endorse or promote products derived from
16+
* this software without specific prior written permission.
17+
*
18+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22+
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
* POSSIBILITY OF SUCH DAMAGE.
29+
*/
30+
31+
#include <cstdio>
32+
#include <cstdlib>
33+
#include <cstring>
34+
#include <string>
35+
#include <memory>
36+
#include "rclcpp/rclcpp.hpp"
37+
#include "nav_msgs/srv/get_map.hpp"
38+
#include "nav_msgs/msg/occupancy_grid.h"
39+
#include "tf2/LinearMath/Matrix3x3.h"
40+
#include "tf2/LinearMath/Quaternion.h"
41+
42+
43+
/**
44+
* @brief Map generation node.
45+
*/
46+
class MapGenerator : public rclcpp::Node
47+
{
48+
public:
49+
MapGenerator(const std::string & mapname, int threshold_occupied, int threshold_free)
50+
: Node("map_saver"),
51+
mapname_(mapname),
52+
saved_map_(false),
53+
threshold_occupied_(threshold_occupied),
54+
threshold_free_(threshold_free)
55+
{
56+
RCLCPP_INFO(get_logger(), "Waiting for the map");
57+
map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
58+
"map", std::bind(&MapGenerator::mapCallback, this, std::placeholders::_1));
59+
}
60+
61+
void mapCallback(const nav_msgs::msg::OccupancyGrid::SharedPtr map)
62+
{
63+
rclcpp::Logger logger = get_logger();
64+
RCLCPP_INFO(logger, "Received a %d X %d map @ %.3f m/pix",
65+
map->info.width,
66+
map->info.height,
67+
map->info.resolution);
68+
69+
70+
std::string mapdatafile = mapname_ + ".pgm";
71+
RCLCPP_INFO(logger, "Writing map occupancy data to %s", mapdatafile.c_str());
72+
FILE * out = fopen(mapdatafile.c_str(), "w");
73+
if (!out) {
74+
RCLCPP_ERROR(logger, "Couldn't save map file to %s", mapdatafile.c_str());
75+
return;
76+
}
77+
78+
fprintf(out, "P5\n# CREATOR: map_saver.cpp %.3f m/pix\n%d %d\n255\n",
79+
map->info.resolution, map->info.width, map->info.height);
80+
for (unsigned int y = 0; y < map->info.height; y++) {
81+
for (unsigned int x = 0; x < map->info.width; x++) {
82+
unsigned int i = x + (map->info.height - y - 1) * map->info.width;
83+
if (map->data[i] >= 0 && map->data[i] <= threshold_free_) { // [0,free)
84+
fputc(254, out);
85+
} else if (map->data[i] >= threshold_occupied_) { // (occ,255]
86+
fputc(000, out);
87+
} else { // occ [0.25,0.65]
88+
fputc(205, out);
89+
}
90+
}
91+
}
92+
93+
fclose(out);
94+
95+
96+
std::string mapmetadatafile = mapname_ + ".yaml";
97+
RCLCPP_INFO(logger, "Writing map occupancy data to %s", mapmetadatafile.c_str());
98+
FILE * yaml = fopen(mapmetadatafile.c_str(), "w");
99+
100+
geometry_msgs::msg::Quaternion orientation = map->info.origin.orientation;
101+
tf2::Matrix3x3 mat(tf2::Quaternion(
102+
orientation.x,
103+
orientation.y,
104+
orientation.z,
105+
orientation.w
106+
));
107+
double yaw, pitch, roll;
108+
mat.getEulerYPR(yaw, pitch, roll);
109+
110+
fprintf(yaml, "image: %s\nresolution: %f\norigin: [%f, %f, %f]\n",
111+
mapdatafile.c_str(), map->info.resolution,
112+
map->info.origin.position.x, map->info.origin.position.y, yaw);
113+
fprintf(yaml, "negate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n");
114+
115+
fclose(yaml);
116+
117+
RCLCPP_INFO(logger, "Done\n");
118+
saved_map_ = true;
119+
}
120+
121+
std::string mapname_;
122+
rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::ConstSharedPtr map_sub_;
123+
bool saved_map_;
124+
int threshold_occupied_;
125+
int threshold_free_;
126+
};
127+
128+
#define USAGE "Usage: \n" \
129+
" map_saver -h\n" \
130+
" map_saver [--occ <threshold_occupied>] [--free <threshold_free>] " \
131+
"[-f <mapname>] [ROS remapping args]"
132+
133+
using namespace std::chrono_literals;
134+
135+
int main(int argc, char ** argv)
136+
{
137+
rclcpp::init(argc, argv);
138+
rclcpp::Logger logger = rclcpp::get_logger("map_saver");
139+
140+
std::string mapname = "map";
141+
int threshold_occupied = 65;
142+
int threshold_free = 25;
143+
144+
for (int i = 1; i < argc; i++) {
145+
if (!strcmp(argv[i], "-h")) {
146+
puts(USAGE);
147+
return 0;
148+
} else if (!strcmp(argv[i], "-f")) {
149+
if (++i < argc) {
150+
mapname = argv[i];
151+
} else {
152+
puts(USAGE);
153+
return 1;
154+
}
155+
} else if (!strcmp(argv[i], "--occ")) {
156+
if (++i < argc) {
157+
threshold_occupied = atoi(argv[i]);
158+
if (threshold_occupied < 1 || threshold_occupied > 100) {
159+
RCLCPP_ERROR(logger, "Threshold_occupied must be between 1 and 100");
160+
return 1;
161+
}
162+
} else {
163+
puts(USAGE);
164+
return 1;
165+
}
166+
} else if (!strcmp(argv[i], "--free")) {
167+
if (++i < argc) {
168+
threshold_free = atoi(argv[i]);
169+
if (threshold_free < 0 || threshold_free > 100) {
170+
RCLCPP_ERROR(logger, "Threshold_free must be between 0 and 100");
171+
return 1;
172+
}
173+
} else {
174+
puts(USAGE);
175+
return 1;
176+
}
177+
} else {
178+
puts(USAGE);
179+
return 1;
180+
}
181+
}
182+
183+
if (threshold_occupied <= threshold_free) {
184+
RCLCPP_ERROR(logger, "Threshold_free must be smaller than threshold_occupied");
185+
return 1;
186+
}
187+
188+
auto map_gen = std::make_shared<MapGenerator>(mapname, threshold_occupied, threshold_free);
189+
190+
while (!map_gen->saved_map_ && rclcpp::ok()) {
191+
rclcpp::spin_some(map_gen);
192+
rclcpp::sleep_for(100ms);
193+
}
194+
195+
rclcpp::shutdown();
196+
return 0;
197+
}

0 commit comments

Comments
 (0)