Go to the documentation of this file.
39 #include <boost/filesystem.hpp>
40 #include <opencv2/core/core.hpp>
41 #include <opencv2/highgui/highgui.hpp>
56 private_nh.
param(
"topic", topic, std::string(
"map"));
57 private_nh.
param(
"nav_grid", use_nav_grid,
false);
63 ROS_FATAL_NAMED(
"MapSaver",
"write_unstamped and write_stamped both set to false. Nothing will be written.");
68 private_nh.
param(
"trinary_output", trinary_output,
true);
80 std::string output_directory_str;
81 private_nh.
param(
"output_directory", output_directory_str, std::string(
"."));
90 catch (
const std::exception& e)
93 "Error: " + e.what());
105 boost::filesystem::path output;
112 std::stringstream ss;
113 ss <<
map_prefix_ <<
"-" << std::setw(10) << std::setfill(
'0') << stamp.
sec <<
"." << extension;
126 for (
unsigned int row = 0; row < info.
height; ++row)
128 unsigned char* output_row = image.ptr<
unsigned char>(row);
129 for (
unsigned int col = 0; col < info.
width; ++col)
131 unsigned char input =
data_(col, info.
height - row - 1);
153 cv::imwrite(map_path.string(), image);
157 std::ofstream yaml_file(yaml_path.c_str(), std::ofstream::out);
158 if (yaml_file.is_open())
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";
190 int main(
int argc,
char** argv)
boost::filesystem::path output_directory_
nav_grid::VectorNavGrid< unsigned char > data_
NumericType interpretCost(IntegralType original_value, const std::vector< NumericType > &cost_interpretation_table)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
#define ROS_FATAL_STREAM(args)
NavGridInfo getInfo() const
ROSCPP_DECL void spinOnce()
void setCostInterpretation(const std::vector< NumericType > &cost_interpretation_table)
void writeData(const ros::Time &stamp, const cv::Mat &image, const nav_grid::NavGridInfo &info) const
static std::vector< unsigned char > TRINARY_SAVE
#define ROS_FATAL_NAMED(name,...)
nav_grid_pub_sub::NavGridSubscriber map_sub_
boost::filesystem::path generatePath(const std::string &extension, const ros::Time &stamp) const
#define ROS_WARN_STREAM_THROTTLE(period, args)
#define ROS_INFO_NAMED(name,...)
std::vector< unsigned char > output_interpretation_
static std::vector< unsigned char > SCALE_SAVE
std::vector< unsigned char > getOccupancyInput(bool trinary=false, bool use_unknown_value=false)
void init(ros::NodeHandle &nh, NewDataCallback callback, const std::string &topic="map", bool nav_grid=true, bool subscribe_to_updates=true)
T param(const std::string ¶m_name, const T &default_val) const
void newDataCallback(const nav_core2::UIntBounds &bounds)
std::string map_extension_
std::string toString() const