00001 #ifndef GAZEBO_GAZEBOMAPPUBLISHER_H 00002 #define GAZEBO_GAZEBOMAPPUBLISHER_H 00003 00004 #include <ros/ros.h> 00005 #include <gazebo/gazebo.hh> 00006 #include <gazebo/physics/Model.hh> 00007 #include <nav_msgs/GetMap.h> 00008 #include <nav_msgs/GetMapRequest.h> 00009 #include <nav_msgs/GetMapResponse.h> 00010 #include <nav_msgs/OccupancyGrid.h> 00011 00012 namespace gazebo 00013 { 00014 00051 class GazeboMapPublisher : public WorldPlugin 00052 { 00053 public: 00054 00055 GazeboMapPublisher(); 00056 void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf); 00057 00058 private: 00059 00060 bool requestMap(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res); 00061 00062 void advertEvent(const ros::TimerEvent& e); 00063 00064 void onWorldUpdate(); 00065 00066 // forward declaration 00067 class CollisionMapRequest; 00068 00069 //see http://gazebosim.org/wiki/Tutorials/1.4/custom_messages#Collision_Map_Creator_Plugin 00070 bool createMap(const CollisionMapRequest &msg, const std::string& map_frame, nav_msgs::OccupancyGrid& map); 00071 00072 CollisionMapRequest getCollisionRequest(); 00073 00074 nav_msgs::MapMetaData getMetaData(); 00075 00076 nav_msgs::OccupancyGrid getMap(); 00077 00078 //map resolution (m/cell) 00079 float map_resolution; 00080 00081 //height of obstacles to consider for generating the map 00082 float map_height; 00083 double map_offset_x; 00084 double map_offset_y; 00085 double map_len_x; 00086 double map_len_y; 00087 00088 ros::NodeHandle node; 00089 00090 std::string MAP_TOPIC; 00091 std::string MAP_FRAME; 00092 std::string METADATA_TOPIC; 00093 std::string REQUEST_MAP_SERVICE; 00094 std::string ROBOT_NAME; 00095 float MAP_PUB_FREQ; 00096 00097 physics::WorldPtr world; 00098 00099 event::ConnectionPtr update_connection; 00100 ros::Publisher map_pub; 00101 ros::Publisher meta_pub; 00102 00103 ros::ServiceServer request_map_srv; 00104 00105 ros::Timer publishTimer; 00106 00107 bool worldChangedSinceLastAdvert; 00108 }; 00109 00110 } 00111 #endif // GAZEBO_GAZEBOMAPPUBLISHER_H