coal/internal/BV_fitter.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef COAL_BV_FITTER_H
39 #define COAL_BV_FITTER_H
40 
41 #include "coal/BVH/BVH_internal.h"
42 #include "coal/BV/kIOS.h"
43 #include "coal/BV/OBBRSS.h"
44 #include "coal/BV/AABB.h"
45 #include <iostream>
46 
47 namespace coal {
48 
50 template <typename BV>
51 void fit(Vec3s* ps, unsigned int n, BV& bv) {
52  for (unsigned int i = 0; i < n; ++i) // TODO(jcarpent): vectorize
53  {
54  bv += ps[i];
55  }
56 }
57 
58 template <>
59 void fit<OBB>(Vec3s* ps, unsigned int n, OBB& bv);
60 
61 template <>
62 void fit<RSS>(Vec3s* ps, unsigned int n, RSS& bv);
63 
64 template <>
65 void fit<kIOS>(Vec3s* ps, unsigned int n, kIOS& bv);
66 
67 template <>
68 void fit<OBBRSS>(Vec3s* ps, unsigned int n, OBBRSS& bv);
69 
70 template <>
71 void fit<AABB>(Vec3s* ps, unsigned int n, AABB& bv);
72 
75 template <typename BV>
76 class COAL_DLLAPI BVFitterTpl {
77  public:
79  virtual ~BVFitterTpl() {}
80 
82  void set(Vec3s* vertices_, Triangle* tri_indices_, BVHModelType type_) {
83  vertices = vertices_;
84  prev_vertices = NULL;
85  tri_indices = tri_indices_;
86  type = type_;
87  }
88 
91  void set(Vec3s* vertices_, Vec3s* prev_vertices_, Triangle* tri_indices_,
92  BVHModelType type_) {
93  vertices = vertices_;
94  prev_vertices = prev_vertices_;
95  tri_indices = tri_indices_;
96  type = type_;
97  }
98 
100  virtual BV fit(unsigned int* primitive_indices,
101  unsigned int num_primitives) = 0;
102 
104  void clear() {
105  vertices = NULL;
106  prev_vertices = NULL;
107  tri_indices = NULL;
109  }
110 
111  protected:
116 };
117 
120 template <typename BV>
121 class COAL_DLLAPI BVFitter : public BVFitterTpl<BV> {
123 
124  public:
128  BV fit(unsigned int* primitive_indices, unsigned int num_primitives) {
129  BV bv;
130 
131  if (type == BVH_MODEL_TRIANGLES)
132  {
133  for (unsigned int i = 0; i < num_primitives; ++i) {
134  Triangle t = tri_indices[primitive_indices[i]];
135  bv += vertices[t[0]];
136  bv += vertices[t[1]];
137  bv += vertices[t[2]];
138 
139  if (prev_vertices)
140  {
141  bv += prev_vertices[t[0]];
142  bv += prev_vertices[t[1]];
143  bv += prev_vertices[t[2]];
144  }
145  }
146  } else if (type == BVH_MODEL_POINTCLOUD)
147  {
148  for (unsigned int i = 0; i < num_primitives; ++i) {
149  bv += vertices[primitive_indices[i]];
150 
151  if (prev_vertices)
152  {
153  bv += prev_vertices[primitive_indices[i]];
154  }
155  }
156  }
157 
158  return bv;
159  }
160 
161  protected:
162  using Base::prev_vertices;
163  using Base::tri_indices;
164  using Base::type;
165  using Base::vertices;
166 };
167 
169 template <>
170 class COAL_DLLAPI BVFitter<OBB> : public BVFitterTpl<OBB> {
171  public:
175  OBB fit(unsigned int* primitive_indices, unsigned int num_primitives);
176 };
177 
179 template <>
180 class COAL_DLLAPI BVFitter<RSS> : public BVFitterTpl<RSS> {
181  public:
185  RSS fit(unsigned int* primitive_indices, unsigned int num_primitives);
186 };
187 
189 template <>
190 class COAL_DLLAPI BVFitter<kIOS> : public BVFitterTpl<kIOS> {
191  public:
195  kIOS fit(unsigned int* primitive_indices, unsigned int num_primitives);
196 };
197 
199 template <>
200 class COAL_DLLAPI BVFitter<OBBRSS> : public BVFitterTpl<OBBRSS> {
201  public:
205  OBBRSS fit(unsigned int* primitive_indices, unsigned int num_primitives);
206 };
207 
209 template <>
210 class COAL_DLLAPI BVFitter<AABB> : public BVFitterTpl<AABB> {
211  public:
215  AABB fit(unsigned int* primitive_indices, unsigned int num_primitives);
216 };
217 
218 } // namespace coal
219 
220 #endif
coal::BVH_MODEL_UNKNOWN
@ BVH_MODEL_UNKNOWN
Definition: coal/BVH/BVH_internal.h:80
coal::BVFitterTpl::clear
void clear()
Clear the geometry primitive data.
Definition: coal/internal/BV_fitter.h:104
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::BVFitterTpl::set
void set(Vec3s *vertices_, Vec3s *prev_vertices_, Triangle *tri_indices_, BVHModelType type_)
Prepare the geometry primitive data for fitting, for deformable mesh.
Definition: coal/internal/BV_fitter.h:91
doxygen_xml_parser.type
type
Definition: doxygen_xml_parser.py:885
coal::BVFitterTpl::set
void set(Vec3s *vertices_, Triangle *tri_indices_, BVHModelType type_)
Prepare the geometry primitive data for fitting.
Definition: coal/internal/BV_fitter.h:82
coal::BVHModelType
BVHModelType
BVH model type.
Definition: coal/BVH/BVH_internal.h:79
coal::BVFitterTpl::vertices
Vec3s * vertices
Definition: coal/internal/BV_fitter.h:112
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::fit< OBBRSS >
void fit< OBBRSS >(Vec3s *ps, unsigned int n, OBBRSS &bv)
coal::fit< AABB >
void fit< AABB >(Vec3s *ps, unsigned int n, AABB &bv)
coal::fit
void fit(Vec3s *ps, unsigned int n, BV &bv)
Compute a bounding volume that fits a set of n points.
Definition: coal/internal/BV_fitter.h:51
coal::kIOS
A class describing the kIOS collision structure, which is a set of spheres.
Definition: coal/BV/kIOS.h:52
coal::BVFitterTpl
The class for the default algorithm fitting a bounding volume to a set of points.
Definition: coal/internal/BV_fitter.h:76
coal::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: coal/BV/AABB.h:55
coal::BVH_MODEL_POINTCLOUD
@ BVH_MODEL_POINTCLOUD
triangle model
Definition: coal/BVH/BVH_internal.h:82
coal::BVH_MODEL_TRIANGLES
@ BVH_MODEL_TRIANGLES
unknown model type
Definition: coal/BVH/BVH_internal.h:81
coal::OBBRSS
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: coal/BV/OBBRSS.h:53
coal::fit< RSS >
void fit< RSS >(Vec3s *ps, unsigned int n, RSS &bv)
coal::BVFitterTpl::tri_indices
Triangle * tri_indices
Definition: coal/internal/BV_fitter.h:114
kIOS.h
BVH_internal.h
coal::BVFitter::fit
BV fit(unsigned int *primitive_indices, unsigned int num_primitives)
Compute a bounding volume that fits a set of primitives (points or triangles). The primitive data was...
Definition: coal/internal/BV_fitter.h:128
coal::BVFitterTpl::~BVFitterTpl
virtual ~BVFitterTpl()
default deconstructor
Definition: coal/internal/BV_fitter.h:79
coal::BVFitter
The class for the default algorithm fitting a bounding volume to a set of points.
Definition: coal/BVH/BVH_model.h:59
coal::BVFitterTpl::prev_vertices
Vec3s * prev_vertices
Definition: coal/internal/BV_fitter.h:113
OBBRSS.h
coal::BVFitter::Base
BVFitterTpl< BV > Base
Definition: coal/internal/BV_fitter.h:122
coal::OBB
Oriented bounding box class.
Definition: include/coal/BV/OBB.h:51
coal::fit< kIOS >
void fit< kIOS >(Vec3s *ps, unsigned int n, kIOS &bv)
coal::Triangle
Triangle with 3 indices for points.
Definition: coal/data_types.h:111
coal::fit< OBB >
void fit< OBB >(Vec3s *ps, unsigned int n, OBB &bv)
t
dictionary t
coal::RSS
A class for rectangle sphere-swept bounding volume.
Definition: coal/BV/RSS.h:53
coal::BVFitterTpl::type
BVHModelType type
Definition: coal/internal/BV_fitter.h:115
AABB.h


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