serialization/convex.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022 INRIA
3 //
4 
5 #ifndef HPP_FCL_SERIALIZATION_CONVEX_H
6 #define HPP_FCL_SERIALIZATION_CONVEX_H
7 
8 #include "hpp/fcl/shape/convex.h"
9 
15 
16 namespace boost {
17 namespace serialization {
18 
19 namespace internal {
22  using Base::own_storage_;
23 };
24 
25 } // namespace internal
26 
27 template <class Archive>
28 void serialize(Archive &ar, hpp::fcl::ConvexBase &convex_base,
29  const unsigned int /*version*/) {
30  using namespace hpp::fcl;
31 
32  typedef internal::ConvexBaseAccessor Accessor;
33  Accessor &accessor = reinterpret_cast<Accessor &>(convex_base);
34 
35  ar &make_nvp("base", boost::serialization::base_object<hpp::fcl::ShapeBase>(
36  convex_base));
37  const unsigned int num_points_previous = convex_base.num_points;
38  ar &make_nvp("num_points", convex_base.num_points);
39 
40  if (Archive::is_loading::value) {
41  if (num_points_previous != convex_base.num_points ||
42  !accessor.own_storage_) {
43  delete[] convex_base.points;
44  convex_base.points = new hpp::fcl::Vec3f[convex_base.num_points];
45  accessor.own_storage_ = true;
46  }
47  }
48 
49  {
50  typedef Eigen::Matrix<FCL_REAL, 3, Eigen::Dynamic> MatrixPoints;
51  Eigen::Map<MatrixPoints> points_map(
52  reinterpret_cast<double *>(convex_base.points), 3,
53  convex_base.num_points);
54  ar &make_nvp("points", points_map);
55  }
56 
57  ar &make_nvp("center", convex_base.center);
58  // We don't save neighbors as they will be computed directly by calling
59  // fillNeighbors.
60 }
61 
62 namespace internal {
63 template <typename PolygonT>
64 struct ConvexAccessor : hpp::fcl::Convex<PolygonT> {
66  using Base::fillNeighbors;
67 };
68 
69 } // namespace internal
70 
71 template <class Archive, typename PolygonT>
72 void serialize(Archive &ar, hpp::fcl::Convex<PolygonT> &convex_,
73  const unsigned int /*version*/) {
74  using namespace hpp::fcl;
75  typedef internal::ConvexAccessor<PolygonT> Accessor;
76 
77  Accessor &convex = reinterpret_cast<Accessor &>(convex_);
78  ar &make_nvp("base", boost::serialization::base_object<ConvexBase>(convex));
79 
80  const unsigned int num_polygons_previous = convex.num_polygons;
81  ar &make_nvp("num_polygons", convex.num_polygons);
82 
83  if (Archive::is_loading::value) {
84  if (num_polygons_previous != convex.num_polygons) {
85  delete[] convex.polygons;
86  convex.polygons = new PolygonT[convex.num_polygons];
87  }
88  }
89 
90  ar &make_array<PolygonT>(convex.polygons, convex.num_polygons);
91 
92  if (Archive::is_loading::value) convex.fillNeighbors();
93 }
94 
95 } // namespace serialization
96 } // namespace boost
97 
98 namespace hpp {
99 namespace fcl {
100 
101 // namespace internal {
102 // template <typename BV>
103 // struct memory_footprint_evaluator< ::hpp::fcl::BVHModel<BV> > {
104 // static size_t run(const ::hpp::fcl::BVHModel<BV> &bvh_model) {
105 // return static_cast<size_t>(bvh_model.memUsage(false));
106 // }
107 // };
108 // } // namespace internal
109 
110 } // namespace fcl
111 } // namespace hpp
112 
113 #endif // ifndef HPP_FCL_SERIALIZATION_CONVEX_H
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::ConvexBase::points
Vec3f * points
An array of the points of the polygon.
Definition: shape/geometric_shapes.h:623
boost::serialization::internal::ConvexAccessor::Base
hpp::fcl::Convex< PolygonT > Base
Definition: serialization/convex.h:65
hpp::fcl::ConvexBase::num_points
unsigned int num_points
Definition: shape/geometric_shapes.h:624
triangle.h
hpp::fcl::ConvexBase::own_storage_
bool own_storage_
Definition: shape/geometric_shapes.h:693
fwd.h
hpp::fcl::Convex::fillNeighbors
void fillNeighbors()
boost
hpp::fcl::Convex
Convex polytope.
Definition: shape/convex.h:50
boost::serialization::internal::ConvexBaseAccessor
Definition: serialization/convex.h:20
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
geometric_shapes.h
hpp::fcl
Definition: broadphase_bruteforce.h:45
quadrilateral.h
hpp::fcl::ConvexBase
Base for convex polytope.
Definition: shape/geometric_shapes.h:581
hpp::fcl::ConvexBase::center
Vec3f center
center of the convex polytope, this is used for collision: center is guaranteed in the internal of th...
Definition: shape/geometric_shapes.h:659
boost::serialization::internal::ConvexAccessor
Definition: serialization/convex.h:64
boost::serialization::serialize
void serialize(Archive &ar, hpp::fcl::AABB &aabb, const unsigned int)
Definition: serialization/AABB.h:15
convex.h
boost::serialization::internal::ConvexBaseAccessor::Base
hpp::fcl::ConvexBase Base
Definition: serialization/convex.h:21
memory.h


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:13