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 <fstream>
41 #include <boost/filesystem.hpp>
42 
43 #include "ros/ros.h"
44 #include "ros/console.h"
46 #include "nav_msgs/MapMetaData.h"
47 #include "nav_msgs/LoadMap.h"
48 #include "yaml-cpp/yaml.h"
49 
50 #ifdef HAVE_YAMLCPP_GT_0_5_0
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  MapMode mode = TRINARY;
71  ros::NodeHandle private_nh("~");
72  private_nh.param("frame_id", frame_id_, std::string("map"));
73 
74  //When called this service returns a copy of the current map
76 
77  //Change the currently published map
79 
80  // Latched publisher for metadata
81  metadata_pub_ = nh_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
82 
83  // Latched publisher for data
84  map_pub_ = nh_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
85 
86  deprecated_ = (res != 0);
87  if (!deprecated_) {
88  if (!loadMapFromYaml(fname))
89  {
90  exit(-1);
91  }
92  } else {
93  if (!loadMapFromParams(fname, res))
94  {
95  exit(-1);
96  }
97  }
98  }
99 
100  private:
107  std::string frame_id_;
108 
110  bool mapCallback(nav_msgs::GetMap::Request &req,
111  nav_msgs::GetMap::Response &res )
112  {
113  // request is empty; we ignore it
114 
115  // = operator is overloaded to make deep copy (tricky!)
116  res = map_resp_;
117  ROS_INFO("Sending map");
118 
119  return true;
120  }
121 
123  bool changeMapCallback(nav_msgs::LoadMap::Request &request,
124  nav_msgs::LoadMap::Response &response )
125  {
126  if (loadMapFromYaml(request.map_url))
127  {
128  response.result = response.RESULT_SUCCESS;
129  ROS_INFO("Changed map to %s", request.map_url.c_str());
130  }
131  else
132  {
133  response.result = response.RESULT_UNDEFINED_FAILURE;
134  }
135  return true;
136  }
137 
140  bool loadMapFromValues(std::string map_file_name, double resolution,
141  int negate, double occ_th, double free_th,
142  double origin[3], MapMode mode)
143  {
144  ROS_INFO("Loading map from image \"%s\"", map_file_name.c_str());
145  try {
146  map_server::loadMapFromFile(&map_resp_, map_file_name.c_str(),
147  resolution, negate, occ_th, free_th,
148  origin, mode);
149  } catch (std::runtime_error& e) {
150  ROS_ERROR("%s", e.what());
151  return false;
152  }
153 
154  // To make sure get a consistent time in simulation
156  map_resp_.map.info.map_load_time = ros::Time::now();
157  map_resp_.map.header.frame_id = frame_id_;
158  map_resp_.map.header.stamp = ros::Time::now();
159  ROS_INFO("Read a %d X %d map @ %.3lf m/cell",
160  map_resp_.map.info.width,
161  map_resp_.map.info.height,
162  map_resp_.map.info.resolution);
163  meta_data_message_ = map_resp_.map.info;
164 
165  //Publish latched topics
167  map_pub_.publish( map_resp_.map );
168  return true;
169  }
170 
173  bool loadMapFromParams(std::string map_file_name, double resolution)
174  {
175  ros::NodeHandle private_nh("~");
176  int negate;
177  double occ_th;
178  double free_th;
179  double origin[3];
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;
184  return loadMapFromValues(map_file_name, resolution, negate, occ_th, free_th, origin, TRINARY);
185  }
186 
189  bool loadMapFromYaml(std::string path_to_yaml)
190  {
191  std::string mapfname;
192  MapMode mode;
193  double res;
194  int negate;
195  double occ_th;
196  double free_th;
197  double origin[3];
198  std::ifstream fin(path_to_yaml.c_str());
199  if (fin.fail()) {
200  ROS_ERROR("Map_server could not open %s.", path_to_yaml.c_str());
201  return false;
202  }
203 #ifdef HAVE_YAMLCPP_GT_0_5_0
204  // The document loading process changed in yaml-cpp 0.5.
205  YAML::Node doc = YAML::Load(fin);
206 #else
207  YAML::Parser parser(fin);
208  YAML::Node doc;
209  parser.GetNextDocument(doc);
210 #endif
211  try {
212  doc["resolution"] >> res;
213  } catch (YAML::InvalidScalar &) {
214  ROS_ERROR("The map does not contain a resolution tag or it is invalid.");
215  return false;
216  }
217  try {
218  doc["negate"] >> negate;
219  } catch (YAML::InvalidScalar &) {
220  ROS_ERROR("The map does not contain a negate tag or it is invalid.");
221  return false;
222  }
223  try {
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.");
227  return false;
228  }
229  try {
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.");
233  return false;
234  }
235  try {
236  std::string modeS = "";
237  doc["mode"] >> modeS;
238 
239  if(modeS=="trinary")
240  mode = TRINARY;
241  else if(modeS=="scale")
242  mode = SCALE;
243  else if(modeS=="raw")
244  mode = RAW;
245  else{
246  ROS_ERROR("Invalid mode tag \"%s\".", modeS.c_str());
247  return false;
248  }
249  } catch (YAML::Exception &) {
250  ROS_DEBUG("The map does not contain a mode tag or it is invalid... assuming Trinary");
251  mode = TRINARY;
252  }
253  try {
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.");
259  return false;
260  }
261  try {
262  doc["image"] >> mapfname;
263  // TODO: make this path-handling more robust
264  if(mapfname.size() == 0)
265  {
266  ROS_ERROR("The image tag cannot be an empty string.");
267  return false;
268  }
269 
270  boost::filesystem::path mapfpath(mapfname);
271  if (!mapfpath.is_absolute())
272  {
273  boost::filesystem::path dir(path_to_yaml);
274  dir = dir.parent_path();
275  mapfpath = dir / mapfpath;
276  mapfname = mapfpath.string();
277  }
278  } catch (YAML::InvalidScalar &) {
279  ROS_ERROR("The map does not contain an image tag or it is invalid.");
280  return false;
281  }
282  return loadMapFromValues(mapfname, res, negate, occ_th, free_th, origin, mode);
283  }
284 
287  nav_msgs::MapMetaData meta_data_message_;
288  nav_msgs::GetMap::Response map_resp_;
289 
290  /*
291  void metadataSubscriptionCallback(const ros::SingleSubscriberPublisher& pub)
292  {
293  pub.publish( meta_data_message_ );
294  }
295  */
296 
297 };
298 
299 int main(int argc, char **argv)
300 {
301  ros::init(argc, argv, "map_server", ros::init_options::AnonymousName);
302  ros::NodeHandle nh("~");
303  if(argc != 3 && argc != 2)
304  {
305  ROS_ERROR("%s", USAGE);
306  exit(-1);
307  }
308  if (argc != 2) {
309  ROS_WARN("Using deprecated map server interface. Please switch to new interface.");
310  }
311  std::string fname(argv[1]);
312  double res = (argc == 2) ? 0.0 : atof(argv[2]);
313 
314  try
315  {
316  MapServer ms(fname, res);
317  ros::spin();
318  }
319  catch(std::runtime_error& e)
320  {
321  ROS_ERROR("map_server exception: %s", e.what());
322  return -1;
323  }
324 
325  return 0;
326 }
ros::init_options::AnonymousName
AnonymousName
MapServer::loadMapFromParams
bool loadMapFromParams(std::string map_file_name, double resolution)
Definition: main.cpp:173
response
const std::string response
MapServer::map_resp_
nav_msgs::GetMap::Response map_resp_
Definition: main.cpp:288
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
MapMode
MapMode
Definition: image_loader.h:52
ros.h
MapServer::loadMapFromYaml
bool loadMapFromYaml(std::string path_to_yaml)
Definition: main.cpp:189
main
int main(int argc, char **argv)
Definition: main.cpp:299
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
MapServer::map_pub_
ros::Publisher map_pub_
Definition: main.cpp:102
USAGE
#define USAGE
Definition: main.cpp:32
map_server::loadMapFromFile
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)
Definition: image_loader.cpp:57
MapServer::get_map_service_
ros::ServiceServer get_map_service_
Definition: main.cpp:104
TRINARY
@ TRINARY
Definition: image_loader.h:52
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
MapServer::frame_id_
std::string frame_id_
Definition: main.cpp:107
ros::ServiceServer
console.h
MapServer
Definition: main.cpp:60
MapServer::metadata_pub_
ros::Publisher metadata_pub_
Definition: main.cpp:103
MapServer::MapServer
MapServer(const std::string &fname, double res)
Definition: main.cpp:64
MapServer::nh_
ros::NodeHandle nh_
Definition: main.cpp:101
ROS_DEBUG
#define ROS_DEBUG(...)
ROS_WARN
#define ROS_WARN(...)
MapServer::loadMapFromValues
bool loadMapFromValues(std::string map_file_name, double resolution, int negate, double occ_th, double free_th, double origin[3], MapMode mode)
Definition: main.cpp:140
MapServer::deprecated_
bool deprecated_
Definition: main.cpp:106
MapServer::meta_data_message_
nav_msgs::MapMetaData meta_data_message_
Definition: main.cpp:287
SCALE
@ SCALE
Definition: image_loader.h:52
RAW
@ RAW
Definition: image_loader.h:52
ROS_ERROR
#define ROS_ERROR(...)
MapServer::mapCallback
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: main.cpp:110
ros::Time::waitForValid
static bool waitForValid()
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
ROS_INFO
#define ROS_INFO(...)
MapServer::change_map_srv_
ros::ServiceServer change_map_srv_
Definition: main.cpp:105
image_loader.h
MapServer::changeMapCallback
bool changeMapCallback(nav_msgs::LoadMap::Request &request, nav_msgs::LoadMap::Response &response)
Definition: main.cpp:123
ros::NodeHandle
ros::Time::now
static Time now()


map_server
Author(s): Brian Gerkey, Tony Pratkanis, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:11