occupancy_grid.hpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Ifdefs
6 *****************************************************************************/
7 
8 #ifndef cost_map_visualisations_OCCUPANCY_GRID_HPP_
9 #define cost_map_visualisations_OCCUPANCY_GRID_HPP_
10 
11 /*****************************************************************************
12 ** Includes
13 *****************************************************************************/
14 
15 #include <cost_map_msgs/CostMap.h>
16 #include <ros/ros.h>
17 #include <map>
18 #include <string>
19 
20 /*****************************************************************************
21 ** Namespaces
22 *****************************************************************************/
23 
24 namespace cost_map {
25 
26 /*****************************************************************************
27 ** Interfaces
28 *****************************************************************************/
29 
34 public:
35  OccupancyGrid();
36 
37 
38 private:
39  void _costMapCallback(const cost_map_msgs::CostMap::ConstPtr& msg);
40 
42  std::map<std::string, ros::Publisher> publishers_;
43 };
44 
45 /*****************************************************************************
46 ** Trailers
47 *****************************************************************************/
48 
49 } // namespace cost_map
50 
51 #endif /* cost_map_visualisations_OCCUPANCY_GRID_HPP_ */
void _costMapCallback(const cost_map_msgs::CostMap::ConstPtr &msg)
Tunes into a cost map publisher and relays it as an Occupancy Grid.
std::map< std::string, ros::Publisher > publishers_
ros::Subscriber subscriber_


cost_map_visualisations
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:03:53