saver.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 #include <ros/ros.h>
39 #include <boost/filesystem.hpp>
40 #include <opencv2/core/core.hpp>
41 #include <opencv2/highgui/highgui.hpp>
42 #include <fstream>
43 #include <string>
44 #include <vector>
45 
46 class MapSaver
47 {
48 public:
50  {
51  ros::NodeHandle nh, private_nh("~");
52 
53  // Load settings from the parameter server
54  std::string topic;
55  bool use_nav_grid;
56  private_nh.param("topic", topic, std::string("map"));
57  private_nh.param("nav_grid", use_nav_grid, false);
58  private_nh.param("once", once_, true);
59  private_nh.param("write_unstamped", write_unstamped_, true);
60  private_nh.param("write_stamped", write_stamped_, false);
62  {
63  ROS_FATAL_NAMED("MapSaver", "write_unstamped and write_stamped both set to false. Nothing will be written.");
64  exit(EXIT_FAILURE);
65  }
66 
67  bool trinary_output;
68  private_nh.param("trinary_output", trinary_output, true);
69  if (trinary_output)
70  {
72  }
73  else
74  {
76  }
77 
78  private_nh.param("map_extension", map_extension_, std::string("png"));
79  private_nh.param("map_prefix", map_prefix_, std::string("map"));
80  std::string output_directory_str;
81  private_nh.param("output_directory", output_directory_str, std::string("."));
82  output_directory_ = boost::filesystem::path(output_directory_str);
83  if (!boost::filesystem::exists(output_directory_))
84  {
85  // Create the output folder
86  try
87  {
88  boost::filesystem::create_directories(output_directory_);
89  }
90  catch (const std::exception& e)
91  {
92  ROS_FATAL_STREAM("Unable to create the requested output directory (" + output_directory_.string() + "). "
93  "Error: " + e.what());
94  exit(EXIT_FAILURE);
95  }
96  }
97 
98  ROS_INFO_NAMED("MapSaver", "Waiting for the map");
100  map_sub_.init(nh, std::bind(&MapSaver::newDataCallback, this, std::placeholders::_1), topic, use_nav_grid, !once_);
101  }
102 
103  boost::filesystem::path generatePath(const std::string& extension, const ros::Time& stamp) const
104  {
105  boost::filesystem::path output;
106  if (stamp == ros::Time())
107  {
108  output = output_directory_ / boost::filesystem::path(map_prefix_ + "." + extension);
109  }
110  else
111  {
112  std::stringstream ss;
113  ss << map_prefix_ << "-" << std::setw(10) << std::setfill('0') << stamp.sec << "." << extension;
114  output = output_directory_ / boost::filesystem::path(ss.str());
115  }
116  return output;
117  }
118 
120  {
121  const nav_grid::NavGridInfo& info = data_.getInfo();
122  ROS_INFO_NAMED("MapSaver", "Writing a new map: %s", info.toString().c_str());
123 
124  // Convert nav_grid into an opencv image
125  cv::Mat image(info.height, info.width, CV_8UC1);
126  for (unsigned int row = 0; row < info.height; ++row)
127  {
128  unsigned char* output_row = image.ptr<unsigned char>(row);
129  for (unsigned int col = 0; col < info.width; ++col)
130  {
131  unsigned char input = data_(col, info.height - row - 1); // flip vertically
133  }
134  }
135 
136  // Save output image and yaml
137  if (write_unstamped_)
138  {
139  writeData(ros::Time(), image, info);
140  }
141 
142  if (write_stamped_)
143  {
144  writeData(ros::Time::now(), image, info);
145  }
146  written_once_ = true;
147  }
148 
149  void writeData(const ros::Time& stamp, const cv::Mat& image, const nav_grid::NavGridInfo& info) const
150  {
151  // Save the Image
152  auto map_path = generatePath(map_extension_, stamp);
153  cv::imwrite(map_path.string(), image);
154 
155  // Save the yaml file
156  auto yaml_path = generatePath("yaml", stamp);
157  std::ofstream yaml_file(yaml_path.c_str(), std::ofstream::out);
158  if (yaml_file.is_open())
159  {
160  yaml_file << "image: " << map_path.filename().string() << "\n";
161  yaml_file << "resolution: " << info.resolution << "\n";
162  yaml_file << "origin: [" << info.origin_x << ", " << info.origin_y << ", 0]\n";
163  yaml_file << "occupied_thresh: 0.65\n";
164  yaml_file << "free_thresh: 0.196\n";
165  yaml_file << "negate: 0\n";
166  yaml_file.close();
167  }
168  else
169  {
170  ROS_WARN_STREAM_THROTTLE(10.0, "Could not open output file '" + yaml_path.string() + "'");
171  }
172  }
173 
174  void spin()
175  {
176  // Keep spinning unless we just want to run once and we wrote our map once
177  while (ros::ok() && !(once_ && written_once_))
178  ros::spinOnce();
179  }
180 
181 protected:
185  boost::filesystem::path output_directory_;
187  std::vector<unsigned char> output_interpretation_;
188 };
189 
190 int main(int argc, char** argv)
191 {
192  ros::init(argc, argv, "map_saver");
193  MapSaver ms;
194  ms.spin();
195  return 0;
196 }
nav_grid::NavGridInfo::height
unsigned int height
MapSaver::output_directory_
boost::filesystem::path output_directory_
Definition: saver.cpp:185
MapSaver::data_
nav_grid::VectorNavGrid< unsigned char > data_
Definition: saver.cpp:183
nav_grid_pub_sub::interpretCost
NumericType interpretCost(IntegralType original_value, const std::vector< NumericType > &cost_interpretation_table)
cost_interpretation.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
main
int main(int argc, char **argv)
Definition: saver.cpp:190
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
ros.h
MapSaver
Definition: saver.cpp:46
nav_grid::NavGrid::getInfo
NavGridInfo getInfo() const
ros::spinOnce
ROSCPP_DECL void spinOnce()
nav_grid_pub_sub::GenericNavGridSubscriber::setCostInterpretation
void setCostInterpretation(const std::vector< NumericType > &cost_interpretation_table)
nav_grid::NavGridInfo::origin_x
double origin_x
MapSaver::spin
void spin()
Definition: saver.cpp:174
MapSaver::writeData
void writeData(const ros::Time &stamp, const cv::Mat &image, const nav_grid::NavGridInfo &info) const
Definition: saver.cpp:149
MapSaver::once_
bool once_
Definition: saver.cpp:186
nav_grid_pub_sub::TRINARY_SAVE
static std::vector< unsigned char > TRINARY_SAVE
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
MapSaver::map_sub_
nav_grid_pub_sub::NavGridSubscriber map_sub_
Definition: saver.cpp:182
ros::ok
ROSCPP_DECL bool ok()
MapSaver::generatePath
boost::filesystem::path generatePath(const std::string &extension, const ros::Time &stamp) const
Definition: saver.cpp:103
vector_nav_grid.h
MapSaver::map_prefix_
std::string map_prefix_
Definition: saver.cpp:184
ROS_WARN_STREAM_THROTTLE
#define ROS_WARN_STREAM_THROTTLE(period, args)
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
MapSaver::output_interpretation_
std::vector< unsigned char > output_interpretation_
Definition: saver.cpp:187
nav_grid_pub_sub::SCALE_SAVE
static std::vector< unsigned char > SCALE_SAVE
cost_interpretation_tables.h
MapSaver::MapSaver
MapSaver()
Definition: saver.cpp:49
TimeBase< Time, Duration >::sec
uint32_t sec
nav_grid_pub_sub::getOccupancyInput
std::vector< unsigned char > getOccupancyInput(bool trinary=false, bool use_unknown_value=false)
nav_grid::NavGridInfo
MapSaver::write_stamped_
bool write_stamped_
Definition: saver.cpp:186
nav_grid_pub_sub::GenericNavGridSubscriber::init
void init(ros::NodeHandle &nh, NewDataCallback callback, const std::string &topic="map", bool nav_grid=true, bool subscribe_to_updates=true)
nav_grid::NavGridInfo::resolution
double resolution
ros::Time
nav_grid::NavGridInfo::width
unsigned int width
MapSaver::write_unstamped_
bool write_unstamped_
Definition: saver.cpp:186
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
MapSaver::written_once_
bool written_once_
Definition: saver.cpp:186
nav_grid_pub_sub::GenericNavGridSubscriber
MapSaver::newDataCallback
void newDataCallback(const nav_core2::UIntBounds &bounds)
Definition: saver.cpp:119
nav_grid::NavGridInfo::origin_y
double origin_y
nav_grid_subscriber.h
nav_core2::UIntBounds
nav_grid::VectorNavGrid< unsigned char >
ros::NodeHandle
ros::Time::now
static Time now()
MapSaver::map_extension_
std::string map_extension_
Definition: saver.cpp:184
nav_grid::NavGridInfo::toString
std::string toString() const


nav_grid_server
Author(s):
autogenerated on Sun May 18 2025 02:47:47