serializer.h
Go to the documentation of this file.
1 
2 #ifndef _TUW_VORONOI_SERIALIZER
3 #define _TUW_VORONOI_SERIALIZER
4 
5 #include <nav_msgs/OccupancyGrid.h>
6 #include <memory>
7 #include <opencv/cv.h>
9 
10 #include <fstream>
11 #include <boost/archive/xml_oarchive.hpp>
12 #include <boost/archive/xml_iarchive.hpp>
13 
14 #define DEFAULT_MAP_NAME "voronoi_map"
15 #include <eigen3/Eigen/Dense>
16 #include <opencv/cv.hpp>
17 #include <boost/filesystem.hpp>
18 #include <boost/functional/hash.hpp>
19 
20 namespace tuw_graph
21 {
22 
24  {
25  public:
27  {}
28  PointSerializer(float _x, float _y)
29  {
30  x = _x;
31  y = _y;
32  }
33  PointSerializer(Eigen::Vector2d p)
34  {
35  x = p[0];
36  y = p[1];
37  }
38  float x;
39  float y;
40  private:
42  template<class archive> void serialize(archive & ar, const unsigned int version)
43  {
44  using boost::serialization::make_nvp;
45  ar & boost::serialization::make_nvp("x", x);
46  ar & boost::serialization::make_nvp("y", y);
47  }
48  };
49 
50  class GraphInfo
51  {
52  public:
53  GraphInfo() : Origin(0, 0)
54  {};
55  GraphInfo(Eigen::Vector2d _pt, float _resolution, int _nrSegments_) : Origin(_pt)
56  {
57  Resolution = _resolution;
58  SegmentLength = _nrSegments_;
59  }
61  float Resolution;
63 
64  private:
65  friend class boost::serialization::access;
66  template<class archive> void serialize(archive & ar, const unsigned int version)
67  {
68  using boost::serialization::make_nvp;
69  ar & boost::serialization::make_nvp("Origin", Origin);
70  ar & boost::serialization::make_nvp("Resolution", Resolution);
71  ar & boost::serialization::make_nvp("SegmentLength", SegmentLength);
72  }
73  };
74 
75  class TreeInfo
76  {
77  public:
78  TreeInfo(std::vector<Segment> _segs) : TreeInfo(_segs.size())
79  {
80  for(uint32_t i = 0; i < _segs.size(); i++)
81  {
82  int * pred = Predecessors.get();
83  int * succ = Successors.get();
84  int * point = Points.get();
85  pred[i] = _segs[i].getPredecessors().size();
86  succ[i] = _segs[i].getSuccessors().size();
87  point[i] = _segs[i].getPath().size();
88  }
89  }
90  TreeInfo(int _length)
91  {
92  Predecessors.reset(new int[_length]);
93  Successors.reset(new int[_length]);
94  Points.reset(new int[_length]);
95  Length = _length;
96  //predLength = _length;
97 
98  }
99  int Length;
100  std::unique_ptr<int> Predecessors;
101  std::unique_ptr<int> Successors;
102  std::unique_ptr<int> Points;
103 
104  private:
105  //int predLength;
106  //int succLength;
107  //int pointsLength;
108  friend class boost::serialization::access;
109  template<class archive> void serialize(archive & ar, const unsigned int version)
110  {
111  using boost::serialization::make_nvp;
112  ar & boost::serialization::make_nvp("Length", Length);
113  ar & boost::serialization::make_array<int>(Predecessors.get(), Length);
114  ar & boost::serialization::make_array<int>(Successors.get(), Length);
115  ar & boost::serialization::make_array<int>(Points.get(), Length);
116  }
117  };
118 
119 
120 
122  {
123  public:
125  {
126  }
127 
128  SegmentSerializer(int _predLength, int _succLength, int _pointLength)
129  {
130  predecessorLength = _predLength;
131  successorLength = _succLength;
132  pointLength = _pointLength;
133  predecessors.reset(new int[predecessorLength]);
134  successors.reset(new int[successorLength]);
135  points.reset(new PointSerializer[pointLength]);
136 
137  }
138 
140  SegmentSerializer(_s.getId(), _s.getPredecessors(), _s.getSuccessors(), _s.getMinPathSpace(), _s.getPath())
141  {
142  }
143 
144  SegmentSerializer(const uint32_t _id, std::vector<uint32_t> _predecessors, std::vector<uint32_t> _successors, float _minDistance, std::vector<Eigen::Vector2d> _points):
145  SegmentSerializer(_predecessors.size(), _successors.size(), _points.size())
146  {
147  id = _id;
148  minDistance = _minDistance;
149 
150  int *pred = predecessors.get();
151  int *succ = successors.get();
152  PointSerializer *pts = points.get();
153 
154 
155  for(int i = 0; i < predecessorLength; i++)
156  {
157  pred[i] = _predecessors[i];
158  }
159 
160  for(int i = 0; i < successorLength; i++)
161  {
162  succ[i] = _successors[i];
163  }
164 
165  for(uint32_t i = 0; i < _points.size(); i++)
166  {
167  PointSerializer p(_points[i]);
168  pts[i] = p;
169  }
170  }
171 
172  int id;
175  std::unique_ptr<int> predecessors;
176  std::unique_ptr<int> successors;
177  float minDistance;
179  std::unique_ptr<PointSerializer> points;
180 
181  private:
182  friend class boost::serialization::access;
183  template<class archive> void serialize(archive & ar, const unsigned int version)
184  {
185  using boost::serialization::make_nvp;
186  ar & boost::serialization::make_nvp("id", id);
187  ar & boost::serialization::make_nvp("predecessorLength", predecessorLength);
188  ar & boost::serialization::make_nvp("successorLength", successorLength);
189  ar & boost::serialization::make_nvp("minDistance", minDistance);
190  ar & boost::serialization::make_nvp("pointLength", pointLength);
191  ar & boost::serialization::make_array<int>(predecessors.get(), predecessorLength);
192  ar & boost::serialization::make_array<int>(successors.get(), successorLength);
193  ar & boost::serialization::make_array<PointSerializer>(points.get(), pointLength);
194  }
195  };
196 
197 
199  {
200  public:
201  GraphSerializer(std::vector<SegmentSerializer> &_segments)
202  {
203  segments_ = &_segments[0];
204  Length = _segments.size();
205  }
206  int Length;
208  private:
209  friend class boost::serialization::access;
210  template<class archive> void serialize(archive & ar, const unsigned int version)
211  {
212  using boost::serialization::make_nvp;
213  ar & boost::serialization::make_nvp("pointLength", Length);
214  ar & boost::serialization::make_array<SegmentSerializer>(segments_, Length);
215  }
216  };
217 
219  {
220  public:
221  Serializer();
229  void save(const std::string &_mapPath, const std::vector<Segment> &_segs, const Eigen::Vector2d &_origin, const float &_resolution);
237  bool load(const std::string &_mapPath, std::vector<Segment> &_segs, Eigen::Vector2d &_origin, float &_resolution);
244  size_t getHash(const std::vector<signed char> &_map, Eigen::Vector2d _origin, float _resolution);
245  };
246 
247 }
248 
249 #endif
void serialize(archive &ar, const unsigned int version)
Definition: serializer.h:109
friend class boost::serialization::access
Definition: serializer.h:41
TreeInfo(int _length)
Definition: serializer.h:90
GraphInfo(Eigen::Vector2d _pt, float _resolution, int _nrSegments_)
Definition: serializer.h:55
GraphSerializer(std::vector< SegmentSerializer > &_segments)
Definition: serializer.h:201
TreeInfo(std::vector< Segment > _segs)
Definition: serializer.h:78
PointSerializer(Eigen::Vector2d p)
Definition: serializer.h:33
std::unique_ptr< int > Predecessors
Definition: serializer.h:100
void serialize(archive &ar, const unsigned int version)
Definition: serializer.h:66
PointSerializer Origin
Definition: serializer.h:60
SegmentSerializer(const uint32_t _id, std::vector< uint32_t > _predecessors, std::vector< uint32_t > _successors, float _minDistance, std::vector< Eigen::Vector2d > _points)
Definition: serializer.h:144
std::unique_ptr< int > predecessors
Definition: serializer.h:175
void serialize(archive &ar, const unsigned int version)
Definition: serializer.h:42
SegmentSerializer(const Segment &_s)
Definition: serializer.h:139
std::unique_ptr< PointSerializer > points
Definition: serializer.h:179
SegmentSerializer(int _predLength, int _succLength, int _pointLength)
Definition: serializer.h:128
std::unique_ptr< int > successors
Definition: serializer.h:176
ROSLIB_DECL std::string getPath(const std::string &package_name)
void serialize(archive &ar, const unsigned int version)
Definition: serializer.h:183
PointSerializer(float _x, float _y)
Definition: serializer.h:28
void serialize(archive &ar, const unsigned int version)
Definition: serializer.h:210
std::unique_ptr< int > Successors
Definition: serializer.h:101
Length
std::unique_ptr< int > Points
Definition: serializer.h:102
SegmentSerializer * segments_
Definition: serializer.h:207


tuw_voronoi_graph
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:44