5 #ifndef COAL_SERIALIZATION_OCTREE_H
6 #define COAL_SERIALIZATION_OCTREE_H
11 #include <boost/serialization/string.hpp>
17 namespace serialization {
29 template <
class Archive>
31 const unsigned int ) {
33 ar << make_nvp(
"resolution", resolution);
36 template <
class Archive>
38 const unsigned int ) {
40 const Accessor &access =
reinterpret_cast<const Accessor &
>(
octree);
42 std::ostringstream stream;
43 access.
tree->write(stream);
44 const std::string stream_str = stream.str();
45 auto size = stream_str.size();
48 ar << make_nvp(
"tree_data_size", size);
49 ar << make_nvp(
"tree_data",
50 make_array(stream_str.c_str(), stream_str.size()));
52 ar << make_nvp(
"base", base_object<coal::CollisionGeometry>(
octree));
53 ar << make_nvp(
"default_occupancy", access.default_occupancy);
54 ar << make_nvp(
"occupancy_threshold", access.occupancy_threshold);
55 ar << make_nvp(
"free_threshold", access.free_threshold);
58 template <
class Archive>
60 const unsigned int ) {
62 ar >> make_nvp(
"resolution", resolution);
66 template <
class Archive>
69 Accessor &access =
reinterpret_cast<Accessor &
>(
octree);
71 std::size_t tree_data_size;
72 ar >> make_nvp(
"tree_data_size", tree_data_size);
74 std::string stream_str;
75 stream_str.resize(tree_data_size);
77 assert(tree_data_size > 0 &&
"tree_data_size should be greater than 0");
78 ar >> make_nvp(
"tree_data", make_array(&stream_str[0], tree_data_size));
79 std::istringstream stream(stream_str);
81 octomap::AbstractOcTree *new_tree = octomap::AbstractOcTree::read(stream);
82 access.tree = std::shared_ptr<const octomap::OcTree>(
83 dynamic_cast<octomap::OcTree *
>(new_tree));
85 ar >> make_nvp(
"base", base_object<coal::CollisionGeometry>(
octree));
86 ar >> make_nvp(
"default_occupancy", access.default_occupancy);
87 ar >> make_nvp(
"occupancy_threshold", access.occupancy_threshold);
88 ar >> make_nvp(
"free_threshold", access.free_threshold);
91 template <
class Archive>
101 #endif // ifndef COAL_SERIALIZATION_OCTREE_H