32 #define USAGE "\nUSAGE: map_server <map.yaml>\n" \
33 " map.yaml: map description file\n" \
34 "DEPRECATED USAGE: map_server <map> <resolution>\n" \
35 " map: image file to load\n"\
36 " resolution: map resolution [meters/pixel]"
41 #include <boost/filesystem.hpp>
46 #include "nav_msgs/MapMetaData.h"
47 #include "nav_msgs/LoadMap.h"
48 #include "yaml-cpp/yaml.h"
50 #ifdef HAVE_YAMLCPP_GT_0_5_0
54 void operator >> (
const YAML::Node& node, T& i)
66 std::string mapfname =
"";
69 double occ_th, free_th;
111 nav_msgs::GetMap::Response &res )
124 nav_msgs::LoadMap::Response &response )
129 ROS_INFO(
"Changed map to %s", request.map_url.c_str());
141 int negate,
double occ_th,
double free_th,
142 double origin[3],
MapMode mode)
144 ROS_INFO(
"Loading map from image \"%s\"", map_file_name.c_str());
147 resolution, negate, occ_th, free_th,
149 }
catch (std::runtime_error& e) {
159 ROS_INFO(
"Read a %d X %d map @ %.3lf m/cell",
180 private_nh.
param(
"negate", negate, 0);
181 private_nh.
param(
"occupied_thresh", occ_th, 0.65);
182 private_nh.
param(
"free_thresh", free_th, 0.196);
183 origin[0] = origin[1] = origin[2] = 0.0;
191 std::string mapfname;
198 std::ifstream fin(path_to_yaml.c_str());
200 ROS_ERROR(
"Map_server could not open %s.", path_to_yaml.c_str());
203 #ifdef HAVE_YAMLCPP_GT_0_5_0
205 YAML::Node doc = YAML::Load(fin);
207 YAML::Parser parser(fin);
209 parser.GetNextDocument(doc);
212 doc[
"resolution"] >> res;
213 }
catch (YAML::InvalidScalar &) {
214 ROS_ERROR(
"The map does not contain a resolution tag or it is invalid.");
218 doc[
"negate"] >> negate;
219 }
catch (YAML::InvalidScalar &) {
220 ROS_ERROR(
"The map does not contain a negate tag or it is invalid.");
224 doc[
"occupied_thresh"] >> occ_th;
225 }
catch (YAML::InvalidScalar &) {
226 ROS_ERROR(
"The map does not contain an occupied_thresh tag or it is invalid.");
230 doc[
"free_thresh"] >> free_th;
231 }
catch (YAML::InvalidScalar &) {
232 ROS_ERROR(
"The map does not contain a free_thresh tag or it is invalid.");
236 std::string modeS =
"";
237 doc[
"mode"] >> modeS;
241 else if(modeS==
"scale")
243 else if(modeS==
"raw")
246 ROS_ERROR(
"Invalid mode tag \"%s\".", modeS.c_str());
249 }
catch (YAML::Exception &) {
250 ROS_DEBUG(
"The map does not contain a mode tag or it is invalid... assuming Trinary");
254 doc[
"origin"][0] >> origin[0];
255 doc[
"origin"][1] >> origin[1];
256 doc[
"origin"][2] >> origin[2];
257 }
catch (YAML::InvalidScalar &) {
258 ROS_ERROR(
"The map does not contain an origin tag or it is invalid.");
262 doc[
"image"] >> mapfname;
264 if(mapfname.size() == 0)
266 ROS_ERROR(
"The image tag cannot be an empty string.");
270 boost::filesystem::path mapfpath(mapfname);
271 if (!mapfpath.is_absolute())
273 boost::filesystem::path dir(path_to_yaml);
274 dir = dir.parent_path();
275 mapfpath = dir / mapfpath;
276 mapfname = mapfpath.string();
278 }
catch (YAML::InvalidScalar &) {
279 ROS_ERROR(
"The map does not contain an image tag or it is invalid.");
299 int main(
int argc,
char **argv)
303 if(argc != 3 && argc != 2)
309 ROS_WARN(
"Using deprecated map server interface. Please switch to new interface.");
311 std::string fname(argv[1]);
312 double res = (argc == 2) ? 0.0 : atof(argv[2]);
319 catch(std::runtime_error& e)
321 ROS_ERROR(
"map_server exception: %s", e.what());