map_server_node.cpp
Go to the documentation of this file.
1 /***********************************************************************************
2  * Revised BSD License *
3  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
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  * * 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 Vienna University of Technology nor the *
14  * names of its contributors may be used to endorse or promote products *
15  * derived from this software without specific prior written permission. *
16  * *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  *AND *
19  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20  **
21  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
22  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
23  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
24  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  **
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
27  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
28  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
29  **
30  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *
31  ***********************************************************************************/
32 
33 #include <map_server_node.h>
34 
35 #include <mrpt_bridge/map.h>
36 
37 #include <mrpt/system/filesystem.h> // ASSERT_FILE_EXISTS_()
38 #include <mrpt/version.h>
39 #if MRPT_VERSION >= 0x199
40 #include <mrpt/config/CConfigFile.h>
41 using namespace mrpt::config;
42 #else
43 #include <mrpt/utils/CConfigFile.h>
44 using namespace mrpt::utils;
45 #endif
46 
47 #include <mrpt/maps/COccupancyGridMap2D.h>
48 #include <mrpt/maps/CMultiMetricMap.h>
49 using mrpt::maps::CMultiMetricMap;
50 using mrpt::maps::COccupancyGridMap2D;
51 
53 
56 {
57  std::string ini_file;
58  std::string map_file;
59  n_param_.param<bool>("debug", debug_, true);
60  ROS_INFO("debug: %s", (debug_ ? "true" : "false"));
61  n_param_.param<std::string>("ini_file", ini_file, "map.ini");
62  ROS_INFO("ini_file: %s", ini_file.c_str());
63  n_param_.param<std::string>("map_file", map_file, "map.simplemap");
64  ROS_INFO("map_file: %s", map_file.c_str());
65  n_param_.param<std::string>(
66  "frame_id", resp_ros_.map.header.frame_id, "map");
67  ROS_INFO("frame_id: %s", resp_ros_.map.header.frame_id.c_str());
68  n_param_.param<double>("frequency", frequency_, 0.1);
69  ROS_INFO("frequency: %f", frequency_);
70 
71  pub_map_ros_ = n_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
73  n_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
74  service_map_ =
75  n_.advertiseService("static_map", &MapServer::mapCallback, this);
76 
77  if (!mrpt::system::fileExists(ini_file))
78  {
79  ROS_ERROR("ini_file: %s does not exit", ini_file.c_str());
80  }
81  if (!mrpt::system::fileExists(map_file))
82  {
83  ROS_ERROR("map_file: %s does not exit", map_file.c_str());
84  }
85  ASSERT_FILE_EXISTS_(ini_file);
86  CConfigFile config_file;
87  config_file.setFileName(ini_file);
88  metric_map_ = boost::shared_ptr<CMultiMetricMap>(new CMultiMetricMap);
89  mrpt_bridge::MapHdl::loadMap(
90  *metric_map_, config_file, map_file, "metricMap", debug_);
91 
92 #if MRPT_VERSION >= 0x199
93  const COccupancyGridMap2D& grid =
94  *metric_map_->mapByClass<COccupancyGridMap2D>();
95 #else
96  const COccupancyGridMap2D& grid = *metric_map_->m_gridMaps[0];
97 #endif
98 
99  if (debug_)
100  printf(
101  "gridMap[0]: %i x %i @ %4.3fm/p, %4.3f, %4.3f, %4.3f, %4.3f\n",
102  grid.getSizeX(), grid.getSizeY(), grid.getResolution(),
103  grid.getXMin(), grid.getYMin(), grid.getXMax(), grid.getYMax());
104 
105  mrpt_bridge::convert(grid, resp_ros_.map);
106  if (debug_)
107  printf(
108  "msg: %i x %i @ %4.3fm/p, %4.3f, %4.3f, %4.3f, %4.3f\n",
109  resp_ros_.map.info.width, resp_ros_.map.info.height,
110  resp_ros_.map.info.resolution, resp_ros_.map.info.origin.position.x,
111  resp_ros_.map.info.origin.position.y,
112  resp_ros_.map.info.width * resp_ros_.map.info.resolution +
113  resp_ros_.map.info.origin.position.x,
114  resp_ros_.map.info.height * resp_ros_.map.info.resolution +
115  resp_ros_.map.info.origin.position.y);
116 }
117 
119  nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res)
120 {
121  ROS_INFO("mapCallback: service requested!\n");
122  res = resp_ros_;
123  return true;
124 }
125 
127 {
128  resp_ros_.map.header.stamp = ros::Time::now();
129  resp_ros_.map.header.seq = loop_count_;
131  {
133  }
135  {
136  pub_metadata_.publish(resp_ros_.map.info);
137  }
138 }
139 
141 {
142  if (frequency_ > 0)
143  {
144  ros::Rate rate(frequency_);
145  for (loop_count_ = 0; ros::ok(); loop_count_++)
146  {
147  publishMap();
148  ros::spinOnce();
149  rate.sleep();
150  }
151  }
152  else
153  {
154  publishMap();
155  ros::spin();
156  }
157 }
158 
159 int main(int argc, char** argv)
160 {
161  // Initialize ROS
162  ros::init(argc, argv, "mrpt_map_server");
163  ros::NodeHandle node;
164  MapServer my_node(node);
165  my_node.init();
166  my_node.loop();
167  return 0;
168 }
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle n_param_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
nav_msgs::GetMap::Response resp_ros_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ROSCPP_DECL void spin(Spinner &spinner)
ros::NodeHandle n_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double frequency_
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< CMultiMetricMap > metric_map_
bool sleep()
MapServer(ros::NodeHandle &n)
ros::ServiceServer service_map_
uint32_t getNumSubscribers() const
ros::Publisher pub_map_ros_
int main(int argc, char **argv)
static Time now()
ROSCPP_DECL void spinOnce()
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
unsigned long loop_count_
#define ROS_ERROR(...)
ros::Publisher pub_metadata_


mrpt_map
Author(s):
autogenerated on Thu Jun 6 2019 19:44:51