main.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* Author: Brian Gerkey */
31 
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]"
37 
38 #include <stdio.h>
39 #include <stdlib.h>
40 #include <libgen.h>
41 #include <fstream>
42 
43 #include "ros/ros.h"
44 #include "ros/console.h"
46 #include "std_msgs/String.h"
47 #include "nav_msgs/MapMetaData.h"
48 #include "yaml-cpp/yaml.h"
49 
50 #ifdef HAVE_NEW_YAMLCPP
51 // The >> operator disappeared in yaml-cpp 0.5, so this function is
52 // added to provide support for code written under the yaml-cpp 0.3 API.
53 template<typename T>
54 void operator >> (const YAML::Node& node, T& i)
55 {
56  i = node.as<T>();
57 }
58 #endif
59 
60 class MapServer
61 {
62  public:
64  MapServer(const std::string& fname, double res)
65  {
66  std::string mapfname = "";
67  double origin[3];
68  int negate;
69  double occ_th, free_th;
70  std::string frame_id;
71  ros::NodeHandle private_nh("~");
72  private_nh.param("frame_id", frame_id, std::string("map"));
73  deprecated = (res != 0);
74  if (!deprecated) {
75  //mapfname = fname + ".pgm";
76  //std::ifstream fin((fname + ".yaml").c_str());
77  std::ifstream fin(fname.c_str());
78  if (fin.fail()) {
79  ROS_ERROR("Map_server could not open %s.", fname.c_str());
80  exit(-1);
81  }
82 #ifdef HAVE_NEW_YAMLCPP
83  // The document loading process changed in yaml-cpp 0.5.
84  YAML::Node doc = YAML::Load(fin);
85 #else
86  YAML::Parser parser(fin);
87  YAML::Node doc;
88  parser.GetNextDocument(doc);
89 #endif
90  try {
91  doc["resolution"] >> res;
92  } catch (YAML::InvalidScalar) {
93  ROS_ERROR("The map does not contain a resolution tag or it is invalid.");
94  exit(-1);
95  }
96  try {
97  doc["negate"] >> negate;
98  } catch (YAML::InvalidScalar) {
99  ROS_ERROR("The map does not contain a negate tag or it is invalid.");
100  exit(-1);
101  }
102  try {
103  doc["occupied_thresh"] >> occ_th;
104  } catch (YAML::InvalidScalar) {
105  ROS_ERROR("The map does not contain an occupied_thresh tag or it is invalid.");
106  exit(-1);
107  }
108  try {
109  doc["free_thresh"] >> free_th;
110  } catch (YAML::InvalidScalar) {
111  ROS_ERROR("The map does not contain a free_thresh tag or it is invalid.");
112  exit(-1);
113  }
114  try {
115  doc["map_id"] >> map_id;
116  } catch (YAML::InvalidScalar) {
117  ROS_WARN("The map does not contain a map_id tag or it is invalid.");
118  map_id = fname;
119  }
120  try {
121  doc["origin"][0] >> origin[0];
122  doc["origin"][1] >> origin[1];
123  doc["origin"][2] >> origin[2];
124  } catch (YAML::InvalidScalar) {
125  ROS_ERROR("The map does not contain an origin tag or it is invalid.");
126  exit(-1);
127  }
128  try {
129  doc["image"] >> mapfname;
130  // TODO: make this path-handling more robust
131  if(mapfname.size() == 0)
132  {
133  ROS_ERROR("The image tag cannot be an empty string.");
134  exit(-1);
135  }
136  if(mapfname[0] != '/')
137  {
138  // dirname can modify what you pass it
139  char* fname_copy = strdup(fname.c_str());
140  mapfname = std::string(dirname(fname_copy)) + '/' + mapfname;
141  free(fname_copy);
142  }
143  } catch (YAML::InvalidScalar) {
144  ROS_ERROR("The map does not contain an image tag or it is invalid.");
145  exit(-1);
146  }
147  } else {
148  private_nh.param("negate", negate, 0);
149  private_nh.param("occupied_thresh", occ_th, 0.65);
150  private_nh.param("free_thresh", free_th, 0.196);
151  mapfname = fname;
152  origin[0] = origin[1] = origin[2] = 0.0;
153  }
154 
155  ROS_INFO("Loading map from image \"%s\"", mapfname.c_str());
156  map_server::loadMapFromFile(&map_resp_,mapfname.c_str(),res,negate,occ_th,free_th, origin);
157  map_resp_.map.info.map_load_time = ros::Time::now();
158  map_resp_.map.header.frame_id = frame_id;
159  map_resp_.map.header.stamp = ros::Time::now();
160  ROS_INFO("Read a %d X %d map @ %.3lf m/cell",
161  map_resp_.map.info.width,
162  map_resp_.map.info.height,
163  map_resp_.map.info.resolution);
164  meta_data_message_ = map_resp_.map.info;
165 
166  // Latched publisher for metadata
167  metadata_pub= n.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
169 
170  }
171 
172  void SwitchPublisher(bool up) {
173  if( up ) {
174  // Latched publisher for data
175  map_pub = n.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
176  map_pub.publish( map_resp_.map );
177  } else {
178  map_pub.shutdown();
179  }
180  }
181 
183  bool mapCallback(nav_msgs::GetMap::Request &req,
184  nav_msgs::GetMap::Response &res )
185  {
186  // request is empty; we ignore it
187 
188  // = operator is overloaded to make deep copy (tricky!)
189  res = map_resp_;
190  ROS_INFO("Sending map");
191 
192  return true;
193  }
194 
195  std::string map_id;
196 
197  private:
201  bool deprecated;
202 
205  nav_msgs::MapMetaData meta_data_message_;
206  nav_msgs::GetMap::Response map_resp_;
207 
208  /*
209  void metadataSubscriptionCallback(const ros::SingleSubscriberPublisher& pub)
210  {
211  pub.publish( meta_data_message_ );
212  }
213  */
214 
215 };
216 
217 std::map< std::string, MapServer > msv;
218 std::string current_map;
219 
220 bool mapCallback(nav_msgs::GetMap::Request &req,
221  nav_msgs::GetMap::Response &res ) {
222  if(msv.find(current_map) != msv.end()) {
223  msv.find(current_map)->second.mapCallback(req,res);
224  }
225  return true;
226 }
227 
228 void MapSelect(const std_msgs::StringConstPtr& msg) {
229  if(msv.find(msg->data) != msv.end()) {
230  current_map = msg->data;
231  msv.find(current_map)->second.SwitchPublisher(true);
232  ROS_INFO("map[%s] is available.", msg->data.c_str());
233  }
234 }
235 
236 int main(int argc, char **argv)
237 {
238  ros::init(argc, argv, "map_server", ros::init_options::AnonymousName);
239 
243  service = n.advertiseService("static_map", &mapCallback);
244  sub = n.subscribe("/map_reload", 1, MapSelect);
245 
246  try
247  {
248  for(int i=1; i < argc; i++) {
249  MapServer ms = MapServer(argv[i],0.0);
250  std::string id = ms.map_id;
251  msv.insert(make_pair(id, ms));
252  if(i==1) {
253  current_map = id;
254  msv.find(id)->second.SwitchPublisher(true);
255  }
256  }
257 
258  ros::spin();
259  }
260  catch(std::runtime_error& e)
261  {
262  ROS_ERROR("map_server exception: %s", e.what());
263  return -1;
264  }
265 
266  return 0;
267 }
268 
ros::Publisher metadata_pub
Definition: main.cpp:199
bool deprecated
Definition: main.cpp:201
std::string current_map
Definition: main.cpp:218
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
Definition: main.cpp:236
std::map< std::string, MapServer > msv
Definition: main.cpp:217
nav_msgs::MapMetaData meta_data_message_
Definition: main.cpp:205
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
ros::ServiceServer service
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
MapServer(const std::string &fname, double res)
frame_id
nav_msgs::GetMap::Response map_resp_
Definition: main.cpp:206
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void loadMapFromFile(nav_msgs::GetMap::Response *resp, const char *fname, double res, bool negate, double occ_th, double free_th, double *origin, MapMode mode=TRINARY)
sub
static Time now()
ros::Publisher map_pub
Definition: main.cpp:200
ros::NodeHandle n
Definition: main.cpp:198
void MapSelect(const std_msgs::StringConstPtr &msg)
Definition: main.cpp:228
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
#define ROS_ERROR(...)


multi_map_server
Author(s): Manabu Saito
autogenerated on Tue Feb 6 2018 03:45:43