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" AND *
00018  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED   *
00019  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE          *
00020  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY                    *
00021  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES      *
00022  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;    *
00023  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND     *
00024  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT      *
00025  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS   *
00026  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.                    *
00027  ***********************************************************************************/
00028 
00029 #include <map_server_node.h>
00030 #include <mrpt/base.h>
00031 #include <mrpt/slam.h>
00032 #include <mrpt_bridge/map.h>
00033 
00034 MapServer::MapServer(ros::NodeHandle &n)
00035     : n_(n)
00036     , n_param_("~")
00037     , loop_count_(0)
00038     , frequency_(0)
00039     , debug_(true) {
00040 }
00041 
00042 MapServer::~MapServer() {
00043 }
00044 
00045 void MapServer::init() {
00046     std::string ini_file;
00047     std::string map_file;
00048     n_param_.param<bool>("debug", debug_, true);
00049     ROS_INFO("debug: %s", (debug_?"true":"false"));
00050     n_param_.param<std::string>("ini_file", ini_file, "map.ini");
00051     ROS_INFO("ini_file: %s", ini_file.c_str());
00052     n_param_.param<std::string>("map_file", map_file, "map.simplemap");
00053     ROS_INFO("map_file: %s", map_file.c_str());
00054     n_param_.param<std::string>("frame_id", resp_ros_.map.header.frame_id, "map");
00055     ROS_INFO("frame_id: %s", resp_ros_.map.header.frame_id.c_str());
00056     n_param_.param<double>("frequency", frequency_, 0.1);
00057     ROS_INFO("frequency: %f", frequency_);
00058 
00059     pub_map_ros_ = n_.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00060     pub_metadata_= n_.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00061     service_map_ = n_.advertiseService("static_map", &MapServer::mapCallback, this);
00062 
00063     if(!mrpt::utils::fileExists(ini_file)){
00064       ROS_ERROR("ini_file: %s does not exit", ini_file.c_str());
00065     }
00066     if(!mrpt::utils::fileExists(map_file)){
00067       ROS_ERROR("map_file: %s does not exit", map_file.c_str());
00068     }
00069     ASSERT_FILE_EXISTS_(ini_file);
00070     mrpt::utils::CConfigFile config_file;
00071     config_file.setFileName(ini_file);
00072     metric_map_ = boost::shared_ptr<mrpt::slam::CMultiMetricMap>(new  mrpt::slam::CMultiMetricMap);
00073     mrpt_bridge::MapHdl::loadMap(*metric_map_, config_file, map_file, "metricMap", debug_);
00074     const mrpt::slam::COccupancyGridMap2D &grid = *metric_map_->m_gridMaps[0];
00075     if(debug_) printf("gridMap[0]:  %i x %i @ %4.3fm/p, %4.3f, %4.3f, %4.3f, %4.3f\n",
00076                       grid.getSizeX(), grid.getSizeY(), grid.getResolution(),
00077                       grid.getXMin(), grid.getYMin(),
00078                       grid.getXMax(), grid.getYMax());
00079 
00080     mrpt_bridge::convert(*metric_map_->m_gridMaps[0], resp_ros_.map);
00081     if(debug_) printf("msg:         %i x %i @ %4.3fm/p, %4.3f, %4.3f, %4.3f, %4.3f\n",
00082                       resp_ros_.map.info.width, resp_ros_.map.info.height, resp_ros_.map.info.resolution,
00083                       resp_ros_.map.info.origin.position.x, resp_ros_.map.info.origin.position.y,
00084                       resp_ros_.map.info.width*resp_ros_.map.info.resolution+resp_ros_.map.info.origin.position.x,
00085                       resp_ros_.map.info.height*resp_ros_.map.info.resolution+resp_ros_.map.info.origin.position.y);
00086 }
00087 
00088 bool MapServer::mapCallback(nav_msgs::GetMap::Request  &req, nav_msgs::GetMap::Response &res )
00089 {
00090   ROS_INFO("mapCallback: service requested!\n");
00091   res = resp_ros_;
00092   return true;
00093 }
00094 
00095 void MapServer::publishMap () {
00096     resp_ros_.map.header.stamp = ros::Time::now();
00097     resp_ros_.map.header.seq = loop_count_;
00098     if(pub_map_ros_.getNumSubscribers() > 0){
00099         pub_map_ros_.publish(resp_ros_.map );
00100     }
00101     if(pub_metadata_.getNumSubscribers() > 0){
00102         pub_metadata_.publish( resp_ros_.map.info );
00103     }
00104 }
00105 
00106 void MapServer::loop() {
00107     if(frequency_ > 0){
00108         ros::Rate rate(frequency_);
00109         for(loop_count_ = 0; ros::ok(); loop_count_++) {
00110           publishMap ();
00111           ros::spinOnce();
00112           rate.sleep();
00113         }
00114     } else {
00115         publishMap ();
00116         ros::spin();
00117     }
00118 }
00119 
00120 int main(int argc, char **argv)
00121 {
00122     // Initialize ROS
00123     ros::init(argc, argv, "mrpt_map_server");
00124     ros::NodeHandle node;
00125     MapServer my_node(node);
00126     my_node.init();
00127     my_node.loop();
00128     return 0;
00129 }


mrpt_map
Author(s):
autogenerated on Tue Aug 5 2014 10:58:11