5 #ifndef HPP_FCL_SERIALIZATION_BVH_MODEL_H 6 #define HPP_FCL_SERIALIZATION_BVH_MODEL_H 18 namespace serialization {
28 template <
class Archive>
30 const unsigned int ) {
35 throw std::invalid_argument(
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.");
42 boost::serialization::base_object<hpp::fcl::CollisionGeometry>(
47 typedef Eigen::Matrix<FCL_REAL, 3, Eigen::Dynamic> AsVertixMatrix;
48 const Eigen::Map<const AsVertixMatrix> vertices_map(
49 reinterpret_cast<const double *>(bvh_model.
vertices), 3,
51 ar &make_nvp(
"vertices", vertices_map);
54 ar &make_nvp(
"num_tris", bvh_model.
num_tris);
56 typedef Eigen::Matrix<Triangle::index_type, 3, Eigen::Dynamic>
58 const Eigen::Map<const AsTriangleMatrix> tri_indices_map(
59 reinterpret_cast<const Triangle::index_type *>(bvh_model.
tri_indices),
61 ar &make_nvp(
"tri_indices", tri_indices_map);
66 const bool has_prev_vertices =
true;
67 ar << make_nvp(
"has_prev_vertices", has_prev_vertices);
68 typedef Eigen::Matrix<FCL_REAL, 3, Eigen::Dynamic> AsVertixMatrix;
69 const Eigen::Map<const AsVertixMatrix> prev_vertices_map(
72 ar &make_nvp(
"prev_vertices", prev_vertices_map);
74 const bool has_prev_vertices =
false;
75 ar &make_nvp(
"has_prev_vertices", has_prev_vertices);
90 template <
class Archive>
92 const unsigned int ) {
95 ar >> make_nvp(
"base",
96 boost::serialization::base_object<hpp::fcl::CollisionGeometry>(
100 ar >> make_nvp(
"num_vertices", num_vertices);
107 if (num_vertices > 0) {
108 typedef Eigen::Matrix<FCL_REAL, 3, Eigen::Dynamic> AsVertixMatrix;
109 Eigen::Map<AsVertixMatrix> vertices_map(
110 reinterpret_cast<double *>(bvh_model.
vertices), 3,
112 ar >> make_nvp(
"vertices", vertices_map);
117 ar >> make_nvp(
"num_tris", num_tris);
119 if (num_tris != bvh_model.
num_tris) {
126 typedef Eigen::Matrix<Triangle::index_type, 3, Eigen::Dynamic>
128 Eigen::Map<AsTriangleMatrix> tri_indices_map(
129 reinterpret_cast<Triangle::index_type *>(bvh_model.
tri_indices), 3,
131 ar &make_nvp(
"tri_indices", tri_indices_map);
135 ar >> make_nvp(
"build_state", bvh_model.
build_state);
141 bool has_prev_vertices;
142 ar >> make_nvp(
"has_prev_vertices", has_prev_vertices);
143 if (has_prev_vertices) {
149 if (num_vertices > 0) {
150 typedef Eigen::Matrix<FCL_REAL, 3, Eigen::Dynamic> AsVertixMatrix;
151 Eigen::Map<AsVertixMatrix> prev_vertices_map(
154 ar &make_nvp(
"prev_vertices", prev_vertices_map);
166 template <
typename BV>
171 using Base::num_bvs_allocated;
172 using Base::primitive_indices;
176 template <
class Archive,
typename BV>
178 const unsigned int version) {
179 split_free(ar, bvh_model, version);
182 template <
class Archive,
typename BV>
184 const unsigned int ) {
189 const Accessor &bvh_model =
reinterpret_cast<const Accessor &
>(bvh_model_);
191 boost::serialization::base_object<BVHModelBase>(bvh_model));
232 const bool with_bvs =
true;
233 ar &make_nvp(
"with_bvs", with_bvs);
234 ar &make_nvp(
"num_bvs", bvh_model.num_bvs);
238 reinterpret_cast<const char *>(bvh_model.bvs),
240 (std::size_t)bvh_model.num_bvs));
242 const bool with_bvs =
false;
243 ar &make_nvp(
"with_bvs", with_bvs);
247 template <
class Archive,
typename BV>
249 const unsigned int ) {
254 Accessor &bvh_model =
reinterpret_cast<Accessor &
>(bvh_model_);
256 ar >> make_nvp(
"base",
257 boost::serialization::base_object<BVHModelBase>(bvh_model));
278 ar >> make_nvp(
"with_bvs", with_bvs);
280 unsigned int num_bvs;
281 ar >> make_nvp(
"num_bvs", num_bvs);
283 if (num_bvs != bvh_model.num_bvs) {
284 delete[] bvh_model.bvs;
285 bvh_model.bvs = NULL;
286 bvh_model.num_bvs = num_bvs;
287 if (num_bvs > 0) bvh_model.bvs =
new BVNode<BV>[num_bvs];
290 ar >> make_nvp(
"bvs", make_array(reinterpret_cast<char *>(bvh_model.bvs),
291 sizeof(Node) * (std::size_t)num_bvs));
293 bvh_model.bvs = NULL;
304 template <
typename BV>
306 static size_t run(const ::hpp::fcl::BVHModel<BV> &bvh_model) {
307 return static_cast<size_t>(bvh_model.memUsage(
false));
315 #endif // ifndef HPP_FCL_SERIALIZATION_BVH_MODEL_H
Vec3f * prev_vertices
Geometry point data in previous frame.
#define HPP_FCL_SERIALIZATION_SPLIT(Type)
void serialize(Archive &ar, hpp::fcl::AABB &aabb, const unsigned int)
A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewe...
unsigned int num_vertices
Number of points.
unsigned int num_vertices_allocated
hpp::fcl::BVHModelBase Base
Triangle * tri_indices
Geometry triangle index data, will be NULL for point clouds.
Vec3f * vertices
Geometry point data.
unsigned int num_tris
Number of triangles.
void save(Archive &ar, const hpp::fcl::BVSplitter< BV > &splitter_, const unsigned int)
BVHModelType getModelType() const
Model type described by the instance.
unsigned int num_tris_allocated
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
hpp::fcl::BVHModel< BV > Base
Triangle with 3 indices for points.
BVHBuildState build_state
The state of BVH building process.
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
void load(Archive &ar, hpp::fcl::BVSplitter< BV > &splitter_, const unsigned int)