coal/serialization/BVH_model.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021-2022 INRIA
3 //
4 
5 #ifndef COAL_SERIALIZATION_BVH_MODEL_H
6 #define COAL_SERIALIZATION_BVH_MODEL_H
7 
8 #include "coal/BVH/BVH_model.h"
9 
10 #include "coal/serialization/fwd.h"
16 
17 namespace boost {
18 namespace serialization {
19 
20 namespace internal {
25 };
26 } // namespace internal
27 
28 template <class Archive>
29 void save(Archive &ar, const coal::BVHModelBase &bvh_model,
30  const unsigned int /*version*/) {
31  using namespace coal;
32  if (!(bvh_model.build_state == BVH_BUILD_STATE_PROCESSED ||
33  bvh_model.build_state == BVH_BUILD_STATE_UPDATED) &&
34  (bvh_model.getModelType() == BVH_MODEL_TRIANGLES)) {
36  "The BVH model is not in a BVH_BUILD_STATE_PROCESSED or "
37  "BVH_BUILD_STATE_UPDATED state.\n"
38  "The BVHModel could not be serialized.",
39  std::invalid_argument);
40  }
41 
42  ar &make_nvp(
43  "base",
44  boost::serialization::base_object<coal::CollisionGeometry>(bvh_model));
45 
46  ar &make_nvp("num_vertices", bvh_model.num_vertices);
47  ar &make_nvp("vertices", bvh_model.vertices);
48 
49  ar &make_nvp("num_tris", bvh_model.num_tris);
50  ar &make_nvp("tri_indices", bvh_model.tri_indices);
51  ar &make_nvp("build_state", bvh_model.build_state);
52 
53  ar &make_nvp("prev_vertices", bvh_model.prev_vertices);
54 
55  // if(bvh_model.convex)
56  // {
57  // const bool has_convex = true;
58  // ar << make_nvp("has_convex",has_convex);
59  // }
60  // else
61  // {
62  // const bool has_convex = false;
63  // ar << make_nvp("has_convex",has_convex);
64  // }
65 }
66 
67 template <class Archive>
68 void load(Archive &ar, coal::BVHModelBase &bvh_model,
69  const unsigned int /*version*/) {
70  using namespace coal;
71 
72  ar >> make_nvp("base",
73  boost::serialization::base_object<coal::CollisionGeometry>(
74  bvh_model));
75 
76  ar >> make_nvp("num_vertices", bvh_model.num_vertices);
77  ar >> make_nvp("vertices", bvh_model.vertices);
78 
79  ar >> make_nvp("num_tris", bvh_model.num_tris);
80  ar >> make_nvp("tri_indices", bvh_model.tri_indices);
81  ar >> make_nvp("build_state", bvh_model.build_state);
82 
83  ar >> make_nvp("prev_vertices", bvh_model.prev_vertices);
84 
85  // bool has_convex = true;
86  // ar >> make_nvp("has_convex",has_convex);
87 }
88 
90 
91 namespace internal {
92 template <typename BV>
95  using Base::bvs;
96  using Base::num_bvs;
99 };
100 } // namespace internal
101 
102 template <class Archive, typename BV>
103 void serialize(Archive &ar, coal::BVHModel<BV> &bvh_model,
104  const unsigned int version) {
105  split_free(ar, bvh_model, version);
106 }
107 
108 template <class Archive, typename BV>
109 void save(Archive &ar, const coal::BVHModel<BV> &bvh_model_,
110  const unsigned int /*version*/) {
111  using namespace coal;
112  typedef internal::BVHModelAccessor<BV> Accessor;
113  typedef BVNode<BV> Node;
114 
115  const Accessor &bvh_model = reinterpret_cast<const Accessor &>(bvh_model_);
116  ar &make_nvp("base",
117  boost::serialization::base_object<BVHModelBase>(bvh_model));
118 
119  // if(bvh_model.primitive_indices)
120  // {
121  // const bool with_primitive_indices = true;
122  // ar & make_nvp("with_primitive_indices",with_primitive_indices);
123  //
124  // int num_primitives = 0;
125  // switch(bvh_model.getModelType())
126  // {
127  // case BVH_MODEL_TRIANGLES:
128  // num_primitives = bvh_model.num_tris;
129  // break;
130  // case BVH_MODEL_POINTCLOUD:
131  // num_primitives = bvh_model.num_vertices;
132  // break;
133  // default:
134  // ;
135  // }
136  //
137  // ar & make_nvp("num_primitives",num_primitives);
138  // if(num_primitives > 0)
139  // {
140  // typedef Eigen::Matrix<unsigned int,1,Eigen::Dynamic>
141  // AsPrimitiveIndexVector; const Eigen::Map<const
142  // AsPrimitiveIndexVector>
143  // primitive_indices_map(reinterpret_cast<const unsigned int
144  // *>(bvh_model.primitive_indices),1,num_primitives); ar &
145  // make_nvp("primitive_indices",primitive_indices_map);
148  // }
149  // }
150  // else
151  // {
152  // const bool with_primitive_indices = false;
153  // ar & make_nvp("with_primitive_indices",with_primitive_indices);
154  // }
155  //
156 
157  if (bvh_model.bvs.get()) {
158  const bool with_bvs = true;
159  ar &make_nvp("with_bvs", with_bvs);
160  ar &make_nvp("num_bvs", bvh_model.num_bvs);
161  ar &make_nvp(
162  "bvs",
163  make_array(
164  reinterpret_cast<const char *>(bvh_model.bvs->data()),
165  sizeof(Node) *
166  (std::size_t)bvh_model.num_bvs)); // Assuming BVs are POD.
167  } else {
168  const bool with_bvs = false;
169  ar &make_nvp("with_bvs", with_bvs);
170  }
171 }
172 
173 template <class Archive, typename BV>
174 void load(Archive &ar, coal::BVHModel<BV> &bvh_model_,
175  const unsigned int /*version*/) {
176  using namespace coal;
177  typedef internal::BVHModelAccessor<BV> Accessor;
178  typedef BVNode<BV> Node;
179 
180  Accessor &bvh_model = reinterpret_cast<Accessor &>(bvh_model_);
181 
182  ar >> make_nvp("base",
183  boost::serialization::base_object<BVHModelBase>(bvh_model));
184 
185  // bool with_primitive_indices;
186  // ar >> make_nvp("with_primitive_indices",with_primitive_indices);
187  // if(with_primitive_indices)
188  // {
189  // int num_primitives;
190  // ar >> make_nvp("num_primitives",num_primitives);
191  //
192  // delete[] bvh_model.primitive_indices;
193  // if(num_primitives > 0)
194  // {
195  // bvh_model.primitive_indices = new unsigned int[num_primitives];
196  // ar &
197  // make_nvp("primitive_indices",make_array(bvh_model.primitive_indices,num_primitives));
198  // }
199  // else
200  // bvh_model.primitive_indices = NULL;
201  // }
202 
203  bool with_bvs;
204  ar >> make_nvp("with_bvs", with_bvs);
205  if (with_bvs) {
206  unsigned int num_bvs;
207  ar >> make_nvp("num_bvs", num_bvs);
208 
209  if (num_bvs != bvh_model.num_bvs) {
210  bvh_model.bvs.reset();
211  bvh_model.num_bvs = num_bvs;
212  if (num_bvs > 0)
213  bvh_model.bvs.reset(new
214  typename BVHModel<BV>::bv_node_vector_t(num_bvs));
215  }
216  if (num_bvs > 0) {
217  ar >> make_nvp("bvs",
218  make_array(reinterpret_cast<char *>(bvh_model.bvs->data()),
219  sizeof(Node) * (std::size_t)num_bvs));
220  } else
221  bvh_model.bvs.reset();
222  }
223 }
224 
225 } // namespace serialization
226 } // namespace boost
227 
228 namespace coal {
229 
230 namespace internal {
231 template <typename BV>
233  static size_t run(const ::coal::BVHModel<BV> &bvh_model) {
234  return static_cast<size_t>(bvh_model.memUsage(false));
235  }
236 };
237 } // namespace internal
238 
239 } // namespace coal
240 
249 
250 #endif // ifndef COAL_SERIALIZATION_BVH_MODEL_H
fwd.h
memory.h
boost::serialization::load
void load(Archive &ar, coal::BVSplitter< BV > &splitter_, const unsigned int)
Definition: coal/serialization/BV_splitter.h:44
coal::BVHModel::num_bvs_allocated
unsigned int num_bvs_allocated
Definition: coal/BVH/BVH_model.h:379
boost::serialization::internal::BVHModelAccessor
Definition: coal/serialization/BVH_model.h:93
coal::BVHModelBase::vertices
std::shared_ptr< std::vector< Vec3s > > vertices
Geometry point data.
Definition: coal/BVH/BVH_model.h:68
boost::serialization::serialize
void serialize(Archive &ar, coal::AABB &aabb, const unsigned int)
Definition: coal/serialization/AABB.h:15
coal::BVHModelBase
A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewe...
Definition: coal/BVH/BVH_model.h:65
coal::BVHModel::num_bvs
unsigned int num_bvs
Number of BV nodes in bounding volume hierarchy.
Definition: coal/BVH/BVH_model.h:386
coal::internal::memory_footprint_evaluator
Definition: coal/serialization/memory.h:12
coal::BVHModelBase::num_vertices_allocated
unsigned int num_vertices_allocated
Definition: coal/BVH/BVH_model.h:302
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
boost
coal::BVHModelBase::num_tris_allocated
unsigned int num_tris_allocated
Definition: coal/BVH/BVH_model.h:301
COAL_SERIALIZATION_DECLARE_EXPORT
#define COAL_SERIALIZATION_DECLARE_EXPORT(T)
Definition: coal/serialization/fwd.h:30
coal::BVH_BUILD_STATE_PROCESSED
@ BVH_BUILD_STATE_PROCESSED
Definition: coal/BVH/BVH_internal.h:53
COAL_SERIALIZATION_SPLIT
#define COAL_SERIALIZATION_SPLIT(Type)
Definition: coal/serialization/fwd.h:24
coal::BVH_MODEL_TRIANGLES
@ BVH_MODEL_TRIANGLES
unknown model type
Definition: coal/BVH/BVH_internal.h:81
version
version
BVH_model.h
COAL_THROW_PRETTY
#define COAL_THROW_PRETTY(message, exception)
Definition: include/coal/fwd.hh:64
coal::BVHModelBase::getModelType
BVHModelType getModelType() const
Model type described by the instance.
Definition: coal/BVH/BVH_model.h:89
coal::BVH_BUILD_STATE_UPDATED
@ BVH_BUILD_STATE_UPDATED
Definition: coal/BVH/BVH_internal.h:56
coal::internal::memory_footprint_evaluator<::coal::BVHModel< BV > >::run
static size_t run(const ::coal::BVHModel< BV > &bvh_model)
Definition: coal/serialization/BVH_model.h:233
boost::serialization::internal::BVHModelBaseAccessor::Base
coal::BVHModelBase Base
Definition: coal/serialization/BVH_model.h:22
BV_node.h
coal::BVHModel::primitive_indices
std::shared_ptr< std::vector< unsigned int > > primitive_indices
Definition: coal/BVH/BVH_model.h:380
collision_object.h
coal::BVHModelBase::build_state
BVHBuildState build_state
The state of BVH building process.
Definition: coal/BVH/BVH_model.h:83
coal::BVHModel::bvs
std::shared_ptr< bv_node_vector_t > bvs
Bounding volume hierarchy.
Definition: coal/BVH/BVH_model.h:383
coal::BVNode
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Definition: coal/BV/BV_node.h:106
coal::KDOP
KDOP class describes the KDOP collision structures. K is set as the template parameter,...
Definition: coal/BV/kDOP.h:91
boost::serialization::internal::BVHModelBaseAccessor
Definition: coal/serialization/BVH_model.h:21
coal::BVHModelBase::tri_indices
std::shared_ptr< std::vector< Triangle > > tri_indices
Geometry triangle index data, will be NULL for point clouds.
Definition: coal/BVH/BVH_model.h:71
coal::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: coal/BVH/BVH_model.h:314
coal::BVHModelBase::num_vertices
unsigned int num_vertices
Number of points.
Definition: coal/BVH/BVH_model.h:80
boost::serialization::save
void save(Archive &ar, const coal::BVSplitter< BV > &splitter_, const unsigned int)
Definition: coal/serialization/BV_splitter.h:30
BV_splitter.h
coal::BVHModelBase::num_tris
unsigned int num_tris
Number of triangles.
Definition: coal/BVH/BVH_model.h:77
boost::serialization::internal::BVHModelAccessor::Base
coal::BVHModel< BV > Base
Definition: coal/serialization/BVH_model.h:94
coal::BVHModelBase::prev_vertices
std::shared_ptr< std::vector< Vec3s > > prev_vertices
Geometry point data in previous frame.
Definition: coal/BVH/BVH_model.h:74
coal::BVHModel::bv_node_vector_t
std::vector< BVNode< BV >, Eigen::aligned_allocator< BVNode< BV > >> bv_node_vector_t
Definition: coal/BVH/BVH_model.h:319
triangle.h


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57