image_bundles.hpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Ifdefs
6 *****************************************************************************/
7 
8 #ifndef cost_map_ros_LOADER_HPP_
9 #define cost_map_ros_LOADER_HPP_
10 
11 /*****************************************************************************
12 ** Includes
13 *****************************************************************************/
14 
16 #include <cost_map_msgs/CostMap.h>
17 #include <mutex>
18 #include <ros/ros.h>
19 #include <std_msgs/String.h>
20 #include <string>
21 
22 /*****************************************************************************
23 ** Namespaces
24 *****************************************************************************/
25 
26 namespace cost_map {
27 
28 /*****************************************************************************
29 ** Methods
30 *****************************************************************************/
31 
43 void fromImageBundle(const std::string& filename, cost_map::CostMap& cost_map);
55 void toImageBundle(const std::string& filename, const cost_map::CostMap& cost_map);
56 
57 // this might be an interesting api to have too
58 // void addLayerFromImageFile()
59 // and this one, which is similar to api in grid_map and inputs opencv types directly
60 // void addLayerFromImage()
61 
62 /*****************************************************************************
63 ** Interfaces
64 *****************************************************************************/
65 
72 public:
79  LoadImageBundle(const std::string& image_bundle_location,
80  const std::string& topic_name="cost_map");
81  virtual ~LoadImageBundle() {}
82 
83  void publish();
84 
87 };
88 
95 public:
102  SaveImageBundle(const std::string& topic_name, const std::string& yaml_filename="foo.yaml");
103  virtual ~SaveImageBundle() {}
104 
105 
106  std::string yaml_filename;
107  bool finished;
108 
109 private:
110  void _costmapCallback(const cost_map_msgs::CostMap& msg);
111 
113  std::mutex mutex_;
114 };
115 
116 /*****************************************************************************
117 ** Trailers
118 *****************************************************************************/
119 
120 } // namespace cost_map
121 
122 #endif /* cost_map_ros_LOADER_HPP_ */
void fromImageBundle(const std::string &filename, cost_map::CostMap &cost_map)
Initialises a adds a single layer from a yaml/image resource pair.
cost_map::CostMapPtr cost_map
std::shared_ptr< cost_map::CostMap > CostMapPtr
Helper for loading and publishing image bundles.
Helper for saving an image bundle from a cost map topic.
LoadImageBundle(const std::string &image_bundle_location, const std::string &topic_name="cost_map")
Load and publish from an image bundle.
void toImageBundle(const std::string &filename, const cost_map::CostMap &cost_map)
Dump a cost map to an image bundle set of files.


cost_map_ros
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:03:48