image_bundles.cpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Includes
6 *****************************************************************************/
7 
8 #include <boost/filesystem.hpp>
9 #include <cost_map_msgs/CostMap.h>
10 #include <cv_bridge/cv_bridge.h>
11 #include <ecl/console.hpp>
12 #include <fstream>
13 #include <iostream>
14 #include <opencv2/core/core.hpp>
15 #include <opencv2/imgproc/imgproc.hpp>
16 #include <opencv2/highgui/highgui.hpp>
17 #include <stdexcept>
18 #include <yaml-cpp/yaml.h>
19 
20 #include "../../include/cost_map_ros/converter.hpp"
21 #include "../../include/cost_map_ros/image_bundles.hpp"
22 #include "../../include/cost_map_ros/utilities.hpp"
23 
24 /*****************************************************************************
25 ** Namespaces
26 *****************************************************************************/
27 
28 namespace cost_map {
29 
30 /*****************************************************************************
31 ** ImageBundle Converters
32 *****************************************************************************/
33 
34 void fromImageBundle(const std::string& filename, cost_map::CostMap& cost_map)
35 {
36  /****************************************
37  ** Load Meta Information from Yaml
38  ****************************************/
39  std::string frame_id;
40  cost_map::Position centre;
41  float resolution;
42  unsigned int number_of_cells_x, number_of_cells_y;
43  std::map<std::string, std::string> layers;
44  try {
45  YAML::Node config = YAML::LoadFile(filename);
46  for (const std::string& property : {
47  "frame_id", "centre_x", "centre_y",
48  "resolution", "number_of_cells_x", "number_of_cells_y"} ) {
49  if (!config[property]) {
50  throw std::logic_error("missing required value '" + property + "'");
51  }
52  }
53  frame_id = config["frame_id"].as<std::string>();
54  resolution = config["resolution"].as<float>();
55  number_of_cells_x = config["number_of_cells_x"].as<unsigned int>();
56  number_of_cells_y = config["number_of_cells_y"].as<unsigned int>();
57  centre << config["centre_x"].as<double>(), config["centre_y"].as<double>();
58  if (config["layers"]) {
59  for ( unsigned int index = 0; index < config["layers"].size(); ++index ) {
60  const YAML::Node& layer = config["layers"][index];
61  if (!layer["layer_name"]) {
62  throw std::logic_error("missing required value 'layer_name'");
63  }
64  if (!layer["layer_data"]) {
65  throw std::logic_error("missing required value 'layer_data'");
66  }
67  layers.insert(std::pair<std::string, std::string>(
68  layer["layer_name"].as<std::string>(),
69  layer["layer_data"].as<std::string>()
70  ));
71  }
72  }
73  } catch(const YAML::ParserException& e ) {
74  throw std::logic_error("failed to parse (bad) yaml '" + filename + "'");
75  }
76  /****************************************
77  ** Initialise the Cost Map
78  ****************************************/
79  Length length(resolution*number_of_cells_x, resolution*number_of_cells_y);
80  cost_map.setGeometry(length, resolution, centre);
81  cost_map.setFrameId(frame_id);
82  cost_map.resetTimestamp();
83  /****************************************
84  ** Add Layers from Image Data
85  ****************************************/
86  for ( const auto& p : layers ) {
87  // until c++11 filesystem stuff is more convenient.
88  boost::filesystem::path parent_path = boost::filesystem::path(filename).parent_path();
89  const std::string& layer_name = p.first;
90  const std::string& image_relative_filename = p.second;
91  boost::filesystem::path image_absolute_filename = parent_path / image_relative_filename;
92  /********************
93  ** Load OpenCV Image
94  ********************/
95  cv::Mat image = cv::imread(image_absolute_filename.string(), cv::IMREAD_UNCHANGED); // IMREAD_UNCHANGED, cv::IMREAD_COLOR, cv::IMREAD_GRAYSCALE, CV_LOAD_IMAGE_COLOR, CV_LOAD_IMAGE_GRAYSCALE
96  // TODO check image.depth() for number of bits
97  std::string encoding;
98  switch( image.channels() ) {
99  case 3 : encoding = "bgr8"; break;
100  case 4 : encoding = "bgra8"; break;
101  default : encoding = "mono8"; break;
102  }
103 
104  /********************
105  ** To Ros Image
106  ********************/
107  // TODO figure out how to skip this step and convert directly
108  sensor_msgs::ImagePtr ros_image_msg = cv_bridge::CvImage(std_msgs::Header(), encoding, image).toImageMsg();
109  // TODO optionally set a frame id from the yaml
110  ros_image_msg->header.frame_id = frame_id;
111  //std::cout << "Ros Image Message: " << *ros_image_msg << std::endl;
112 
113  /********************
114  ** To Cost Map
115  ********************/
116  // this converts to a grayscale value immediately
117  addLayerFromROSImage(*ros_image_msg, layer_name, cost_map);
118 
119  /********************
120  ** Debugging
121  ********************/
122  //
123  // std::cout << "Filename : " << filename << std::endl;
124  // std::cout << "Resolution : " << resolution << std::endl;
125  // std::cout << "Image (Rel): " << image_relative_filename << std::endl;
126  // std::cout << "Image (Abs): " << image_absolute_filename.string() << std::endl;
127  //
128  // cv::namedWindow(image_relative_filename, cv::WINDOW_AUTOSIZE);
129  // cv::imshow(image_relative_filename, image);
130  // cv::waitKey(0);
131 
132  }
133 }
134 
135 void toImageBundle(const std::string& filename, const cost_map::CostMap& cost_map) {
136  /********************
137  ** Yaml
138  ********************/
139  YAML::Node node;
140  node["frame_id"] = cost_map.getFrameId();
141  node["centre_x"] = cost_map.getPosition().x();
142  node["centre_y"] = cost_map.getPosition().x();
143  node["resolution"] = cost_map.getResolution();
144  node["number_of_cells_x"] = cost_map.getSize()(0);
145  node["number_of_cells_y"] = cost_map.getSize()(1);
146  YAML::Node layers;
147  for (const std::string& layer_name : cost_map.getLayers()) {
148  YAML::Node layer;
149  layer["layer_name"] = layer_name;
150  layer["layer_data"] = layer_name + ".png";
151  layers.push_back(layer);
152  }
153  node["layers"] = layers;
154  std::ofstream ofs(filename, std::ofstream::out);
155  ofs << node;
156  ofs.close();
157  /********************
158  ** Layers
159  ********************/
160  for (const std::string& layer : cost_map.getLayers()) {
161  // can't take a const Matrix& here, since opencv will complain that it doesn't have control of
162  // the memory (i.e. const void* cannot convert to void*)
163  const cost_map::Matrix& cost_map_storage = cost_map.get(layer);
164  // cv::Mat image(cost_map_storage.rows(), cost_map_storage.cols(), CV_8U, cost_map_storage.data());
165  cv::Mat image(cost_map.getSize().x(), cost_map.getSize().y(), CV_8UC4);
166  for (int i = 0; i < cost_map_storage.rows(); ++i) {
167  for (int j = 0; j < cost_map_storage.cols(); ++j) {
168  cv::Vec4b& rgba = image.at<cv::Vec4b>(i, j);
169  cost_map::DataType value = cost_map_storage(i,j);
170  // RULE 1 : scale only from 0-254 (remember 255 is reserved for NO_INFORMATION)
171  // RULE 2 : invert the value as black on an image (grayscale: 0) typically represents an obstacle (cost: 254)
172  cost_map::DataType flipped_value = static_cast<cost_map::DataType>(std::numeric_limits<cost_map::DataType>::max() * (1.0 - static_cast<double>(value) / static_cast<double>(cost_map::NO_INFORMATION)));
173  rgba[0] = flipped_value;
174  rgba[1] = flipped_value;
175  rgba[2] = flipped_value;
176  rgba[3] = (value == cost_map::NO_INFORMATION) ? 0.0 : std::numeric_limits<cost_map::DataType>::max();
177  }
178  }
179  boost::filesystem::path parent_path = boost::filesystem::path(filename).parent_path();
180  boost::filesystem::path image_absolute_filename = parent_path / (layer + std::string(".png"));
181  cv::imwrite(image_absolute_filename.string(), image);
182  }
183 }
184 
185 /*****************************************************************************
186 ** Class Implementations
187 *****************************************************************************/
188 
190  const std::string& image_bundle_location,
191  const std::string& topic_name)
192 {
193  ros::NodeHandle nodehandle("~");
194  publisher = nodehandle.advertise<cost_map_msgs::CostMap>(topic_name, 1, true);
195 
196  std::string yaml_filename;
197  if ( boost::filesystem::exists(image_bundle_location)) {
198  yaml_filename = image_bundle_location;
199  } else {
200  // fallback to check if it's a ros resource
201  yaml_filename = cost_map::resolveResourceName(image_bundle_location);
202  }
203  cost_map = std::make_shared<CostMap>();
204  cost_map::fromImageBundle(yaml_filename, *cost_map);
205  publish();
206  // for debugging, verify this function returns what we loaded.
207  // toImageBundle("debug.yaml", *cost_map);
208 }
209 
211  cost_map_msgs::CostMap map_message;
212  cost_map::toMessage(*cost_map, map_message);
213  publisher.publish(map_message);
214 }
215 
217  const std::string& topic_name,
218  const std::string& yaml_filename)
219 : finished(false)
220 , yaml_filename(yaml_filename)
221 {
222  ros::NodeHandle nodehandle("~");
223  // TODO : check that a publisher exists and warn if not available?
224  subscriber_ = nodehandle.subscribe(topic_name, 1, &SaveImageBundle::_costmapCallback, this);
225 }
226 
227 void SaveImageBundle::_costmapCallback(const cost_map_msgs::CostMap& msg) {
228  std::lock_guard<std::mutex> guard(mutex_);
229  if ( !finished ) {
231  if ( !fromMessage(msg, cost_map) ) {
232  ROS_ERROR_STREAM("SaveImageBundle : failed to convert cost map msg -> cost map class");
233  return;
234  }
235  toImageBundle(yaml_filename, cost_map);
236  ROS_INFO_STREAM("SaveImageBundle : successfully saved to '" << yaml_filename << "'");
237  finished = true;
238  }
239 }
240 
241 
242 
243 /*****************************************************************************
244  ** Trailers
245  *****************************************************************************/
246 
247 } // namespace cost_map
void fromImageBundle(const std::string &filename, cost_map::CostMap &cost_map)
Initialises a adds a single layer from a yaml/image resource pair.
Eigen::Matrix< unsigned char, Eigen::Dynamic, Eigen::Dynamic > Matrix
const unsigned char NO_INFORMATION
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
const Size & getSize() const
double getResolution() const
void setFrameId(const std::string &frameId)
void toMessage(const cost_map::CostMap &cost_map, cost_map_msgs::CostMap &message)
Definition: converter.cpp:154
const Matrix & get(const std::string &layer) const
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
const std::string & getFrameId() const
SaveImageBundle(const std::string &topic_name, const std::string &yaml_filename="foo.yaml")
Load and publish from an image bundle.
bool addLayerFromROSImage(const sensor_msgs::Image &image, const std::string &layer_name, cost_map::CostMap &cost_map)
Definition: converter.cpp:37
bool getPosition(const Index &index, Position &position) const
void _costmapCallback(const cost_map_msgs::CostMap &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_INFO_STREAM(args)
grid_map::Position Position
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
Matrix::Scalar DataType
const std::vector< std::string > & getLayers() const
#define ROS_ERROR_STREAM(args)
LoadImageBundle(const std::string &image_bundle_location, const std::string &topic_name="cost_map")
Load and publish from an image bundle.
grid_map::Length Length
std::string resolveResourceName(const std::string &resource_name)
Use rospack to resolve a costmap given a ros package resource name.
Definition: utilities.cpp:23
void toImageBundle(const std::string &filename, const cost_map::CostMap &cost_map)
Dump a cost map to an image bundle set of files.
sensor_msgs::ImagePtr toImageMsg() const
bool fromMessage(const cost_map_msgs::CostMap &message, cost_map::CostMap &cost_map)
Definition: converter.cpp:186


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