Go to the documentation of this file.00001
00004
00005
00006
00007
00008 #include <boost/filesystem.hpp>
00009 #include <cost_map_msgs/CostMap.h>
00010 #include <cv_bridge/cv_bridge.h>
00011 #include <ecl/console.hpp>
00012 #include <fstream>
00013 #include <iostream>
00014 #include <opencv2/core/core.hpp>
00015 #include <opencv2/imgproc/imgproc.hpp>
00016 #include <opencv2/highgui/highgui.hpp>
00017 #include <stdexcept>
00018 #include <yaml-cpp/yaml.h>
00019
00020 #include "../../include/cost_map_ros/converter.hpp"
00021 #include "../../include/cost_map_ros/image_bundles.hpp"
00022 #include "../../include/cost_map_ros/utilities.hpp"
00023
00024
00025
00026
00027
00028 namespace cost_map {
00029
00030
00031
00032
00033
00034 void fromImageBundle(const std::string& filename, cost_map::CostMap& cost_map)
00035 {
00036
00037
00038
00039 std::string frame_id;
00040 cost_map::Position centre;
00041 float resolution;
00042 unsigned int number_of_cells_x, number_of_cells_y;
00043 std::map<std::string, std::string> layers;
00044 try {
00045 YAML::Node config = YAML::LoadFile(filename);
00046 for (const std::string& property : {
00047 "frame_id", "centre_x", "centre_y",
00048 "resolution", "number_of_cells_x", "number_of_cells_y"} ) {
00049 if (!config[property]) {
00050 throw std::logic_error("missing required value '" + property + "'");
00051 }
00052 }
00053 frame_id = config["frame_id"].as<std::string>();
00054 resolution = config["resolution"].as<float>();
00055 number_of_cells_x = config["number_of_cells_x"].as<unsigned int>();
00056 number_of_cells_y = config["number_of_cells_y"].as<unsigned int>();
00057 centre << config["centre_x"].as<double>(), config["centre_y"].as<double>();
00058 if (config["layers"]) {
00059 for ( unsigned int index = 0; index < config["layers"].size(); ++index ) {
00060 const YAML::Node& layer = config["layers"][index];
00061 if (!layer["layer_name"]) {
00062 throw std::logic_error("missing required value 'layer_name'");
00063 }
00064 if (!layer["layer_data"]) {
00065 throw std::logic_error("missing required value 'layer_data'");
00066 }
00067 layers.insert(std::pair<std::string, std::string>(
00068 layer["layer_name"].as<std::string>(),
00069 layer["layer_data"].as<std::string>()
00070 ));
00071 }
00072 }
00073 } catch(const YAML::ParserException& e ) {
00074 throw std::logic_error("failed to parse (bad) yaml '" + filename + "'");
00075 }
00076
00077
00078
00079 Length length(resolution*number_of_cells_x, resolution*number_of_cells_y);
00080 cost_map.setGeometry(length, resolution, centre);
00081 cost_map.setFrameId(frame_id);
00082 cost_map.resetTimestamp();
00083
00084
00085
00086 for ( const auto& p : layers ) {
00087
00088 boost::filesystem::path parent_path = boost::filesystem::path(filename).parent_path();
00089 const std::string& layer_name = p.first;
00090 const std::string& image_relative_filename = p.second;
00091 boost::filesystem::path image_absolute_filename = parent_path / image_relative_filename;
00092
00093
00094
00095 cv::Mat image = cv::imread(image_absolute_filename.string(), cv::IMREAD_UNCHANGED);
00096
00097 std::string encoding;
00098 switch( image.channels() ) {
00099 case 3 : encoding = "bgr8"; break;
00100 case 4 : encoding = "bgra8"; break;
00101 default : encoding = "mono8"; break;
00102 }
00103
00104
00105
00106
00107
00108 sensor_msgs::ImagePtr ros_image_msg = cv_bridge::CvImage(std_msgs::Header(), encoding, image).toImageMsg();
00109
00110 ros_image_msg->header.frame_id = frame_id;
00111
00112
00113
00114
00115
00116
00117 addLayerFromROSImage(*ros_image_msg, layer_name, cost_map);
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132 }
00133 }
00134
00135 void toImageBundle(const std::string& filename, const cost_map::CostMap& cost_map) {
00136
00137
00138
00139 YAML::Node node;
00140 node["frame_id"] = cost_map.getFrameId();
00141 node["centre_x"] = cost_map.getPosition().x();
00142 node["centre_y"] = cost_map.getPosition().x();
00143 node["resolution"] = cost_map.getResolution();
00144 node["number_of_cells_x"] = cost_map.getSize()(0);
00145 node["number_of_cells_y"] = cost_map.getSize()(1);
00146 YAML::Node layers;
00147 for (const std::string& layer_name : cost_map.getLayers()) {
00148 YAML::Node layer;
00149 layer["layer_name"] = layer_name;
00150 layer["layer_data"] = layer_name + ".png";
00151 layers.push_back(layer);
00152 }
00153 node["layers"] = layers;
00154 std::ofstream ofs(filename, std::ofstream::out);
00155 ofs << node;
00156 ofs.close();
00157
00158
00159
00160 for (const std::string& layer : cost_map.getLayers()) {
00161
00162
00163 const cost_map::Matrix& cost_map_storage = cost_map.get(layer);
00164
00165 cv::Mat image(cost_map.getSize().x(), cost_map.getSize().y(), CV_8UC4);
00166 for (int i = 0; i < cost_map_storage.rows(); ++i) {
00167 for (int j = 0; j < cost_map_storage.cols(); ++j) {
00168 cv::Vec4b& rgba = image.at<cv::Vec4b>(i, j);
00169 cost_map::DataType value = cost_map_storage(i,j);
00170
00171
00172 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)));
00173 rgba[0] = flipped_value;
00174 rgba[1] = flipped_value;
00175 rgba[2] = flipped_value;
00176 rgba[3] = (value == cost_map::NO_INFORMATION) ? 0.0 : std::numeric_limits<cost_map::DataType>::max();
00177 }
00178 }
00179 boost::filesystem::path parent_path = boost::filesystem::path(filename).parent_path();
00180 boost::filesystem::path image_absolute_filename = parent_path / (layer + std::string(".png"));
00181 cv::imwrite(image_absolute_filename.string(), image);
00182 }
00183 }
00184
00185
00186
00187
00188
00189 LoadImageBundle::LoadImageBundle(
00190 const std::string& image_bundle_location,
00191 const std::string& topic_name)
00192 {
00193 ros::NodeHandle nodehandle("~");
00194 publisher = nodehandle.advertise<cost_map_msgs::CostMap>(topic_name, 1, true);
00195
00196 std::string yaml_filename;
00197 if ( boost::filesystem::exists(image_bundle_location)) {
00198 yaml_filename = image_bundle_location;
00199 } else {
00200
00201 yaml_filename = cost_map::resolveResourceName(image_bundle_location);
00202 }
00203 cost_map = std::make_shared<CostMap>();
00204 cost_map::fromImageBundle(yaml_filename, *cost_map);
00205 publish();
00206
00207
00208 }
00209
00210 void LoadImageBundle::publish() {
00211 cost_map_msgs::CostMap map_message;
00212 cost_map::toMessage(*cost_map, map_message);
00213 publisher.publish(map_message);
00214 }
00215
00216 SaveImageBundle::SaveImageBundle(
00217 const std::string& topic_name,
00218 const std::string& yaml_filename)
00219 : finished(false)
00220 , yaml_filename(yaml_filename)
00221 {
00222 ros::NodeHandle nodehandle("~");
00223
00224 subscriber_ = nodehandle.subscribe(topic_name, 1, &SaveImageBundle::_costmapCallback, this);
00225 }
00226
00227 void SaveImageBundle::_costmapCallback(const cost_map_msgs::CostMap& msg) {
00228 std::lock_guard<std::mutex> guard(mutex_);
00229 if ( !finished ) {
00230 cost_map::CostMap cost_map;
00231 if ( !fromMessage(msg, cost_map) ) {
00232 ROS_ERROR_STREAM("SaveImageBundle : failed to convert cost map msg -> cost map class");
00233 return;
00234 }
00235 toImageBundle(yaml_filename, cost_map);
00236 ROS_INFO_STREAM("SaveImageBundle : successfully saved to '" << yaml_filename << "'");
00237 finished = true;
00238 }
00239 }
00240
00241
00242
00243
00244
00245
00246
00247 }