map_server.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 
22 #include <stdr_server/map_server.h>
23 
24 namespace stdr_server {
25 
31  MapServer::MapServer(const std::string& fname)
32  {
33 
34  map_ = map_loader::loadMap(fname);
35 
36  meta_data_message_ = map_.info;
37 
38  publishData();
39  }
40 
46  MapServer::MapServer(const nav_msgs::OccupancyGrid& map)
47  {
48 
49  map_ = map;
50 
51  meta_data_message_ = map_.info;
52 
53  publishData();
54  }
55 
61  {
62 
65 
67  metadata_pub= n.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
69 
71  map_pub = n.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
72  map_pub.publish( map_ );
73  }
74 
81 
82  tf::Vector3 translation(
83  map_.info.origin.position.x,
84  map_.info.origin.position.y,
85  0);
86 
87  tf::Quaternion rotation;
88 
89  rotation.setRPY(0, 0, tf::getYaw(map_.info.origin.orientation));
90 
91  tf::Transform worldTomap(rotation, translation);
92 
94  tf::StampedTransform(worldTomap, ros::Time::now(), "map", "map_static"));
95 
96  }
97 
98 } // end of namespace stdr_server
99 
ros::Timer tfTimer
ROS tf broadcaster.
Definition: map_server.h:81
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle n
< The ROS node handle
Definition: map_server.h:75
MapServer(const std::string &fname)
Constructor by filename.
Definition: map_server.cpp:31
static double getYaw(const Quaternion &bt_q)
The main namespace for STDR Server.
void publishTransform(const ros::TimerEvent &ev)
Publishes the map to map_static transform.
Definition: map_server.cpp:80
nav_msgs::OccupancyGrid loadMap(const std::string &fname)
Loads a map from an image file.
Definition: map_loader.cpp:33
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
nav_msgs::MapMetaData meta_data_message_
ROS occupancy grid message.
Definition: map_server.h:85
void sendTransform(const StampedTransform &transform)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publishData()
Publishes the map data and metadata.
Definition: map_server.cpp:60
tf::TransformBroadcaster tfBroadcaster
ROS map metadata message.
Definition: map_server.h:83
nav_msgs::OccupancyGrid map_
Definition: map_server.h:87
static Time now()
ros::Publisher map_pub
ROS publisher for posting the map metadata.
Definition: map_server.h:77
ros::Publisher metadata_pub
ROS timer for tf posting.
Definition: map_server.h:79


stdr_server
Author(s): Chris Zalidis
autogenerated on Mon Jun 10 2019 15:15:07