serialization.hpp
Go to the documentation of this file.
1 /*
2  * Author
3  * Copyright (c) 2018, Simbe Robotics, Inc.
4  *
5  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
6  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
7  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
8  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
9  *
10  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
11  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
12  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
13  * CONDITIONS.
14  *
15  */
16 
17 /* Author: Steven Macenski */
18 
19 #ifndef SLAM_TOOLBOX_SERIALIZATION_H_
20 #define SLAM_TOOLBOX_SERIALIZATION_H_
21 
22 #include <vector>
23 #include <string>
24 #include <ros/ros.h>
25 #include <karto_sdk/Karto.h>
26 #include <karto_sdk/Mapper.h>
27 #include <sys/stat.h>
28 
29 namespace serialization
30 {
31 
32 inline bool fileExists(const std::string& name)
33 {
34  struct stat buffer;
35  return (stat (name.c_str(), &buffer) == 0);
36 }
37 
38 inline void write(const std::string& filename,
39  karto::Mapper& mapper,
40  karto::Dataset& dataset)
41 {
42  try
43  {
44  mapper.SaveToFile(filename + std::string(".posegraph"));
45  dataset.SaveToFile(filename + std::string(".data"));
46  }
47  catch (boost::archive::archive_exception e)
48  {
49  ROS_ERROR("Failed to write file: Exception %s", e.what());
50  }
51 }
52 
53 inline bool read(const std::string& filename,
54  karto::Mapper& mapper,
55  karto::Dataset& dataset)
56 {
57  if (!fileExists(filename + std::string(".posegraph")))
58  {
59  ROS_ERROR("serialization::Read: Failed to open "
60  "requested file: %s.", filename.c_str());
61  return false;
62  }
63 
64  try
65  {
66  mapper.LoadFromFile(filename + std::string(".posegraph"));
67  dataset.LoadFromFile(filename + std::string(".data"));
68  return true;
69  }
70  catch (boost::archive::archive_exception e)
71  {
72  ROS_ERROR("serialization::Read: Failed to read file: "
73  "Exception: %s", e.what());
74  }
75 
76  return false;
77 }
78 
79 } // end namespace
80 
81 #endif //SLAM_TOOLBOX_SERIALIZATION_H_
karto::Mapper
Definition: Mapper.h:1928
karto::Mapper::SaveToFile
void SaveToFile(const std::string &filename)
Definition: Mapper.cpp:2671
karto::Dataset::SaveToFile
void SaveToFile(const std::string &filename)
Definition: Karto.h:6572
ros.h
serialization::read
bool read(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)
Definition: serialization.hpp:53
karto::Mapper::LoadFromFile
void LoadFromFile(const std::string &filename)
Definition: Mapper.cpp:2679
Karto.h
karto::Dataset
Definition: Karto.h:6549
karto::Dataset::LoadFromFile
void LoadFromFile(const std::string &filename)
Definition: Karto.h:6584
ROS_ERROR
#define ROS_ERROR(...)
serialization
Definition: serialization.hpp:29
process_constraints.filename
filename
Definition: process_constraints.py:114
Mapper.h
serialization::fileExists
bool fileExists(const std::string &name)
Definition: serialization.hpp:32
serialization::write
void write(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)
Definition: serialization.hpp:38


slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:55