19 #ifndef SLAM_TOOLBOX_SERIALIZATION_H_ 20 #define SLAM_TOOLBOX_SERIALIZATION_H_ 35 return (stat (name.c_str(), &buffer) == 0);
38 inline void write(
const std::string& filename,
44 mapper.
SaveToFile(filename + std::string(
".posegraph"));
45 dataset.
SaveToFile(filename + std::string(
".data"));
47 catch (boost::archive::archive_exception e)
49 ROS_ERROR(
"Failed to write file: Exception %s", e.what());
53 inline bool read(
const std::string& filename,
57 if (!
fileExists(filename + std::string(
".posegraph")))
59 ROS_ERROR(
"serialization::Read: Failed to open " 60 "requested file: %s.", filename.c_str());
66 mapper.
LoadFromFile(filename + std::string(
".posegraph"));
70 catch (boost::archive::archive_exception e)
72 ROS_ERROR(
"serialization::Read: Failed to read file: " 73 "Exception: %s", e.what());
81 #endif //SLAM_TOOLBOX_SERIALIZATION_H_
void SaveToFile(const std::string &filename)
void LoadFromFile(const std::string &filename)
void LoadFromFile(const std::string &filename)
bool read(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)
void SaveToFile(const std::string &filename)
bool fileExists(const std::string &name)
void write(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)