map_server_node.cpp
Go to the documentation of this file.
00001 /***********************************************************************************
00002  * Revised BSD License *
00003  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
00004  * All rights reserved. *
00005  *                                                                                 *
00006  * Redistribution and use in source and binary forms, with or without *
00007  * modification, are permitted provided that the following conditions are met: *
00008  *     * Redistributions of source code must retain the above copyright *
00009  *       notice, this list of conditions and the following disclaimer. *
00010  *     * Redistributions in binary form must reproduce the above copyright *
00011  *       notice, this list of conditions and the following disclaimer in the *
00012  *       documentation and/or other materials provided with the distribution. *
00013  *     * Neither the name of the Vienna University of Technology nor the *
00014  *       names of its contributors may be used to endorse or promote products *
00015  *       derived from this software without specific prior written permission. *
00016  *                                                                                 *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  *AND *
00019  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020  **
00021  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
00022  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
00023  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
00024  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  **
00026  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
00027  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
00028  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00029  **
00030  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *
00031  ***********************************************************************************/
00032 
00033 #include <map_server_node.h>
00034 
00035 #include <mrpt_bridge/map.h>
00036 
00037 #include <mrpt/system/filesystem.h>  // ASSERT_FILE_EXISTS_()
00038 #include <mrpt/version.h>
00039 #if MRPT_VERSION >= 0x199
00040 #include <mrpt/config/CConfigFile.h>
00041 using namespace mrpt::config;
00042 #else
00043 #include <mrpt/utils/CConfigFile.h>
00044 using namespace mrpt::utils;
00045 #endif
00046 
00047 #include <mrpt/maps/COccupancyGridMap2D.h>
00048 #include <mrpt/maps/CMultiMetricMap.h>
00049 using mrpt::maps::CMultiMetricMap;
00050 using mrpt::maps::COccupancyGridMap2D;
00051 
00052 MapServer::MapServer(ros::NodeHandle& n) : n_(n) {}
00053 
00054 MapServer::~MapServer() {}
00055 void MapServer::init()
00056 {
00057         std::string ini_file;
00058         std::string map_file;
00059         n_param_.param<bool>("debug", debug_, true);
00060         ROS_INFO("debug: %s", (debug_ ? "true" : "false"));
00061         n_param_.param<std::string>("ini_file", ini_file, "map.ini");
00062         ROS_INFO("ini_file: %s", ini_file.c_str());
00063         n_param_.param<std::string>("map_file", map_file, "map.simplemap");
00064         ROS_INFO("map_file: %s", map_file.c_str());
00065         n_param_.param<std::string>(
00066                 "frame_id", resp_ros_.map.header.frame_id, "map");
00067         ROS_INFO("frame_id: %s", resp_ros_.map.header.frame_id.c_str());
00068         n_param_.param<double>("frequency", frequency_, 0.1);
00069         ROS_INFO("frequency: %f", frequency_);
00070 
00071         pub_map_ros_ = n_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00072         pub_metadata_ =
00073                 n_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00074         service_map_ =
00075                 n_.advertiseService("static_map", &MapServer::mapCallback, this);
00076 
00077         if (!mrpt::system::fileExists(ini_file))
00078         {
00079                 ROS_ERROR("ini_file: %s does not exit", ini_file.c_str());
00080         }
00081         if (!mrpt::system::fileExists(map_file))
00082         {
00083                 ROS_ERROR("map_file: %s does not exit", map_file.c_str());
00084         }
00085         ASSERT_FILE_EXISTS_(ini_file);
00086         CConfigFile config_file;
00087         config_file.setFileName(ini_file);
00088         metric_map_ = boost::shared_ptr<CMultiMetricMap>(new CMultiMetricMap);
00089         mrpt_bridge::MapHdl::loadMap(
00090                 *metric_map_, config_file, map_file, "metricMap", debug_);
00091 
00092 #if MRPT_VERSION >= 0x199
00093         const COccupancyGridMap2D& grid =
00094                 *metric_map_->mapByClass<COccupancyGridMap2D>();
00095 #else
00096         const COccupancyGridMap2D& grid = *metric_map_->m_gridMaps[0];
00097 #endif
00098 
00099         if (debug_)
00100                 printf(
00101                         "gridMap[0]:  %i x %i @ %4.3fm/p, %4.3f, %4.3f, %4.3f, %4.3f\n",
00102                         grid.getSizeX(), grid.getSizeY(), grid.getResolution(),
00103                         grid.getXMin(), grid.getYMin(), grid.getXMax(), grid.getYMax());
00104 
00105         mrpt_bridge::convert(grid, resp_ros_.map);
00106         if (debug_)
00107                 printf(
00108                         "msg:         %i x %i @ %4.3fm/p, %4.3f, %4.3f, %4.3f, %4.3f\n",
00109                         resp_ros_.map.info.width, resp_ros_.map.info.height,
00110                         resp_ros_.map.info.resolution, resp_ros_.map.info.origin.position.x,
00111                         resp_ros_.map.info.origin.position.y,
00112                         resp_ros_.map.info.width * resp_ros_.map.info.resolution +
00113                                 resp_ros_.map.info.origin.position.x,
00114                         resp_ros_.map.info.height * resp_ros_.map.info.resolution +
00115                                 resp_ros_.map.info.origin.position.y);
00116 }
00117 
00118 bool MapServer::mapCallback(
00119         nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res)
00120 {
00121         ROS_INFO("mapCallback: service requested!\n");
00122         res = resp_ros_;
00123         return true;
00124 }
00125 
00126 void MapServer::publishMap()
00127 {
00128         resp_ros_.map.header.stamp = ros::Time::now();
00129         resp_ros_.map.header.seq = loop_count_;
00130         if (pub_map_ros_.getNumSubscribers() > 0)
00131         {
00132                 pub_map_ros_.publish(resp_ros_.map);
00133         }
00134         if (pub_metadata_.getNumSubscribers() > 0)
00135         {
00136                 pub_metadata_.publish(resp_ros_.map.info);
00137         }
00138 }
00139 
00140 void MapServer::loop()
00141 {
00142         if (frequency_ > 0)
00143         {
00144                 ros::Rate rate(frequency_);
00145                 for (loop_count_ = 0; ros::ok(); loop_count_++)
00146                 {
00147                         publishMap();
00148                         ros::spinOnce();
00149                         rate.sleep();
00150                 }
00151         }
00152         else
00153         {
00154                 publishMap();
00155                 ros::spin();
00156         }
00157 }
00158 
00159 int main(int argc, char** argv)
00160 {
00161         // Initialize ROS
00162         ros::init(argc, argv, "mrpt_map_server");
00163         ros::NodeHandle node;
00164         MapServer my_node(node);
00165         my_node.init();
00166         my_node.loop();
00167         return 0;
00168 }


mrpt_map
Author(s):
autogenerated on Thu Jun 6 2019 21:53:21