Skip to content
Snippets Groups Projects
Verified Commit 055def9b authored by Justin Carpentier's avatar Justin Carpentier
Browse files

serialization/octree: fix pointer case handling

parent 115b812a
No related branches found
No related tags found
No related merge requests found
...@@ -26,6 +26,13 @@ struct OcTreeAccessor : hpp::fcl::OcTree { ...@@ -26,6 +26,13 @@ struct OcTreeAccessor : hpp::fcl::OcTree {
}; };
} // namespace internal } // namespace internal
template <class Archive>
void save_construct_data(Archive &ar, const hpp::fcl::OcTree *octree_ptr,
const unsigned int /*version*/) {
const double resolution = octree_ptr->getResolution();
ar << make_nvp("resolution", resolution);
}
template <class Archive> template <class Archive>
void save(Archive &ar, const hpp::fcl::OcTree &octree, void save(Archive &ar, const hpp::fcl::OcTree &octree,
const unsigned int /*version*/) { const unsigned int /*version*/) {
...@@ -37,9 +44,6 @@ void save(Archive &ar, const hpp::fcl::OcTree &octree, ...@@ -37,9 +44,6 @@ void save(Archive &ar, const hpp::fcl::OcTree &octree,
const std::string stream_str = stream.str(); const std::string stream_str = stream.str();
ar << make_nvp("tree_data", stream_str); ar << make_nvp("tree_data", stream_str);
// const double resolution = octree.getResolution();
// ar << make_nvp("resolution", resolution);
ar << make_nvp("base", base_object<hpp::fcl::CollisionGeometry>(octree)); ar << make_nvp("base", base_object<hpp::fcl::CollisionGeometry>(octree));
ar << make_nvp("default_occupancy", access.default_occupancy); ar << make_nvp("default_occupancy", access.default_occupancy);
ar << make_nvp("occupancy_threshold", access.occupancy_threshold); ar << make_nvp("occupancy_threshold", access.occupancy_threshold);
...@@ -49,26 +53,9 @@ void save(Archive &ar, const hpp::fcl::OcTree &octree, ...@@ -49,26 +53,9 @@ void save(Archive &ar, const hpp::fcl::OcTree &octree,
template <class Archive> template <class Archive>
void load_construct_data(Archive &ar, hpp::fcl::OcTree *octree_ptr, void load_construct_data(Archive &ar, hpp::fcl::OcTree *octree_ptr,
const unsigned int /*version*/) { const unsigned int /*version*/) {
std::string stream_str; double resolution;
ar >> make_nvp("tree_data", stream_str); ar >> make_nvp("resolution", resolution);
std::istringstream stream(stream_str); new (octree_ptr) hpp::fcl::OcTree(resolution);
octomap::AbstractOcTree *tree_raw_ptr = octomap::AbstractOcTree::read(stream);
std::shared_ptr<const octomap::OcTree> tree_ptr(
dynamic_cast<octomap::OcTree *>(tree_raw_ptr));
new (octree_ptr) hpp::fcl::OcTree(tree_ptr);
hpp::fcl::OcTree &octree = *octree_ptr;
typedef internal::OcTreeAccessor Accessor;
Accessor &access = reinterpret_cast<Accessor &>(octree);
// double resolution;
// ar >> make_nvp("resolution", resolution);
ar >> make_nvp("base", base_object<hpp::fcl::CollisionGeometry>(octree));
ar >> make_nvp("default_occupancy", access.default_occupancy);
ar >> make_nvp("occupancy_threshold", access.occupancy_threshold);
ar >> make_nvp("free_threshold", access.free_threshold);
} }
template <class Archive> template <class Archive>
...@@ -85,9 +72,6 @@ void load(Archive &ar, hpp::fcl::OcTree &octree, ...@@ -85,9 +72,6 @@ void load(Archive &ar, hpp::fcl::OcTree &octree,
access.tree = std::shared_ptr<const octomap::OcTree>( access.tree = std::shared_ptr<const octomap::OcTree>(
dynamic_cast<octomap::OcTree *>(new_tree)); dynamic_cast<octomap::OcTree *>(new_tree));
// double resolution;
// ar >> make_nvp("resolution", resolution);
ar >> make_nvp("base", base_object<hpp::fcl::CollisionGeometry>(octree)); ar >> make_nvp("base", base_object<hpp::fcl::CollisionGeometry>(octree));
ar >> make_nvp("default_occupancy", access.default_occupancy); ar >> make_nvp("default_occupancy", access.default_occupancy);
ar >> make_nvp("occupancy_threshold", access.occupancy_threshold); ar >> make_nvp("occupancy_threshold", access.occupancy_threshold);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment