map_server.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002    STDR Simulator - Simple Two DImensional Robot Simulator
00003    Copyright (C) 2013 STDR Simulator
00004    This program is free software; you can redistribute it and/or modify
00005    it under the terms of the GNU General Public License as published by
00006    the Free Software Foundation; either version 3 of the License, or
00007    (at your option) any later version.
00008    This program is distributed in the hope that it will be useful,
00009    but WITHOUT ANY WARRANTY; without even the implied warranty of
00010    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011    GNU General Public License for more details.
00012    You should have received a copy of the GNU General Public License
00013    along with this program; if not, write to the Free Software Foundation,
00014    Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301  USA
00015 
00016    Authors :
00017    * Manos Tsardoulias, etsardou@gmail.com
00018    * Aris Thallas, aris.thallas@gmail.com
00019    * Chris Zalidis, zalidis@gmail.com
00020 ******************************************************************************/
00021 
00022 #include <stdr_server/map_server.h>
00023 
00024 namespace stdr_server {
00025 
00031   MapServer::MapServer(const std::string& fname)
00032   {
00033 
00034     map_ = map_loader::loadMap(fname);
00035 
00036     meta_data_message_ = map_.info;
00037 
00038     publishData();
00039   }
00040 
00046   MapServer::MapServer(const nav_msgs::OccupancyGrid& map)
00047   {
00048 
00049     map_ = map;
00050 
00051     meta_data_message_ = map_.info;
00052 
00053     publishData();
00054   }
00055 
00060   void MapServer::publishData(void)
00061   {
00062 
00063     tfTimer = n.createTimer(ros::Duration(0.1),
00064       &MapServer::publishTransform, this);
00065 
00067     metadata_pub= n.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
00068     metadata_pub.publish( meta_data_message_ );
00069 
00071     map_pub = n.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00072     map_pub.publish( map_ );
00073   }
00074 
00080   void MapServer::publishTransform(const ros::TimerEvent&) {
00081 
00082     tf::Vector3 translation(
00083       map_.info.origin.position.x,
00084       map_.info.origin.position.y,
00085       0);
00086 
00087     tf::Quaternion rotation;
00088 
00089     rotation.setRPY(0, 0, tf::getYaw(map_.info.origin.orientation));
00090 
00091     tf::Transform worldTomap(rotation, translation);
00092 
00093     tfBroadcaster.sendTransform(
00094       tf::StampedTransform(worldTomap, ros::Time::now(), "map", "map_static"));
00095 
00096   }
00097 
00098 } // end of namespace stdr_server
00099 


stdr_server
Author(s): Chris Zalidis
autogenerated on Thu Jun 6 2019 18:57:23