Go to the documentation of this file.
19 #ifndef SLAM_TOOLBOX_SERIALIZATION_H_
20 #define SLAM_TOOLBOX_SERIALIZATION_H_
35 return (stat (name.c_str(), &buffer) == 0);
47 catch (boost::archive::archive_exception e)
49 ROS_ERROR(
"Failed to write file: Exception %s", e.what());
59 ROS_ERROR(
"serialization::Read: Failed to open "
60 "requested file: %s.",
filename.c_str());
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 SaveToFile(const std::string &filename)
bool read(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)
void LoadFromFile(const std::string &filename)
void LoadFromFile(const std::string &filename)
bool fileExists(const std::string &name)
void write(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)
slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:55