data_types.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 HPP_FCL_DATA_TYPES_H
39 #define HPP_FCL_DATA_TYPES_H
40 
41 #include <Eigen/Core>
42 #include <Eigen/Geometry>
43 
44 #include <hpp/fcl/config.hh>
45 
46 namespace hpp {
47 
48 #ifdef HPP_FCL_HAS_OCTOMAP
49 #define OCTOMAP_VERSION_AT_LEAST(x, y, z) \
50  (OCTOMAP_MAJOR_VERSION > x || \
51  (OCTOMAP_MAJOR_VERSION >= x && \
52  (OCTOMAP_MINOR_VERSION > y || \
53  (OCTOMAP_MINOR_VERSION >= y && OCTOMAP_PATCH_VERSION >= z))))
54 
55 #define OCTOMAP_VERSION_AT_MOST(x, y, z) \
56  (OCTOMAP_MAJOR_VERSION < x || \
57  (OCTOMAP_MAJOR_VERSION <= x && \
58  (OCTOMAP_MINOR_VERSION < y || \
59  (OCTOMAP_MINOR_VERSION <= y && OCTOMAP_PATCH_VERSION <= z))))
60 #endif // HPP_FCL_HAS_OCTOMAP
61 } // namespace hpp
62 
63 namespace hpp {
64 namespace fcl {
65 typedef double FCL_REAL;
66 typedef Eigen::Matrix<FCL_REAL, 3, 1> Vec3f;
67 typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 1> VecXf;
68 typedef Eigen::Matrix<FCL_REAL, 3, 3> Matrix3f;
69 typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 3> Matrixx3f;
70 typedef Eigen::Matrix<Eigen::DenseIndex, Eigen::Dynamic, 3> Matrixx3i;
71 typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, Eigen::Dynamic> MatrixXf;
72 typedef Eigen::Vector2i support_func_guess_t;
73 
81 
84 
90 
94 
96 class HPP_FCL_DLLAPI Triangle {
97  public:
98  typedef std::size_t index_type;
99  typedef int size_type;
100 
102  Triangle() {}
103 
105  Triangle(index_type p1, index_type p2, index_type p3) { set(p1, p2, p3); }
106 
108  inline void set(index_type p1, index_type p2, index_type p3) {
109  vids[0] = p1;
110  vids[1] = p2;
111  vids[2] = p3;
112  }
113 
115  inline index_type operator[](index_type i) const { return vids[i]; }
116 
117  inline index_type& operator[](index_type i) { return vids[i]; }
118 
119  static inline size_type size() { return 3; }
120 
121  bool operator==(const Triangle& other) const {
122  return vids[0] == other.vids[0] && vids[1] == other.vids[1] &&
123  vids[2] == other.vids[2];
124  }
125 
126  bool operator!=(const Triangle& other) const { return !(*this == other); }
127 
128  private:
130  index_type vids[3];
131 };
132 
134 struct HPP_FCL_DLLAPI Quadrilateral {
135  typedef std::size_t index_type;
136  typedef int size_type;
137 
139 
141  set(p0, p1, p2, p3);
142  }
143 
145  inline void set(index_type p0, index_type p1, index_type p2, index_type p3) {
146  vids[0] = p0;
147  vids[1] = p1;
148  vids[2] = p2;
149  vids[3] = p3;
150  }
151 
153  inline index_type operator[](index_type i) const { return vids[i]; }
154 
155  inline index_type& operator[](index_type i) { return vids[i]; }
156 
157  static inline size_type size() { return 4; }
158 
159  bool operator==(const Quadrilateral& other) const {
160  return vids[0] == other.vids[0] && vids[1] == other.vids[1] &&
161  vids[2] == other.vids[2] && vids[3] == other.vids[3];
162  }
163 
164  bool operator!=(const Quadrilateral& other) const {
165  return !(*this == other);
166  }
167 
168  private:
169  index_type vids[4];
170 };
171 
172 } // namespace fcl
173 
174 } // namespace hpp
175 
176 #endif
hpp::fcl::VecXf
Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 1 > VecXf
Definition: data_types.h:67
hpp::fcl::CachedGuess
@ CachedGuess
Definition: data_types.h:80
hpp::fcl::Triangle::set
void set(index_type p1, index_type p2, index_type p3)
Set the vertex indices of the triangle.
Definition: data_types.h:108
hpp::fcl::GJKConvergenceCriterionType
GJKConvergenceCriterionType
Wether the convergence criterion is scaled on the norm of the solution or not.
Definition: data_types.h:93
hpp::fcl::BoundingVolumeGuess
@ BoundingVolumeGuess
Definition: data_types.h:80
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::Triangle::Triangle
Triangle(index_type p1, index_type p2, index_type p3)
Create a triangle with given vertex indices.
Definition: data_types.h:105
hpp::fcl::Triangle::operator!=
bool operator!=(const Triangle &other) const
Definition: data_types.h:126
hpp::fcl::Quadrilateral::set
void set(index_type p0, index_type p1, index_type p2, index_type p3)
Set the vertex indices of the quadrilateral.
Definition: data_types.h:145
hpp::fcl::VDB
@ VDB
Definition: data_types.h:89
hpp::fcl::MatrixXf
Eigen::Matrix< FCL_REAL, Eigen::Dynamic, Eigen::Dynamic > MatrixXf
Definition: data_types.h:71
hpp::fcl::Triangle::index_type
std::size_t index_type
Definition: data_types.h:98
hpp::fcl::Matrixx3i
Eigen::Matrix< Eigen::DenseIndex, Eigen::Dynamic, 3 > Matrixx3i
Definition: data_types.h:70
hpp::fcl::Triangle::operator[]
index_type operator[](index_type i) const
Access the triangle index.
Definition: data_types.h:115
hpp::fcl::Quadrilateral::operator[]
index_type operator[](index_type i) const
@access the quadrilateral index
Definition: data_types.h:153
hpp::fcl::DefaultGJK
@ DefaultGJK
Definition: data_types.h:83
hpp::fcl::GJKConvergenceCriterion
GJKConvergenceCriterion
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision)....
Definition: data_types.h:89
hpp::fcl::Triangle::operator==
bool operator==(const Triangle &other) const
Definition: data_types.h:121
hpp::fcl::Quadrilateral::Quadrilateral
Quadrilateral()
Definition: data_types.h:138
hpp::fcl::Quadrilateral::size
static size_type size()
Definition: data_types.h:157
hpp::fcl::Triangle::operator[]
index_type & operator[](index_type i)
Definition: data_types.h:117
hpp::fcl::Hybrid
@ Hybrid
Definition: data_types.h:89
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::Quadrilateral::operator[]
index_type & operator[](index_type i)
Definition: data_types.h:155
hpp::fcl::Quadrilateral
Quadrilateral with 4 indices for points.
Definition: data_types.h:134
hpp::fcl::Quadrilateral::vids
index_type vids[4]
Definition: data_types.h:169
hpp::fcl::support_func_guess_t
Eigen::Vector2i support_func_guess_t
Definition: data_types.h:72
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
hpp::fcl::Triangle::Triangle
Triangle()
Default constructor.
Definition: data_types.h:102
hpp::fcl::Triangle::size
static size_type size()
Definition: data_types.h:119
hpp::fcl::Relative
@ Relative
Definition: data_types.h:93
octree.p1
tuple p1
Definition: octree.py:54
hpp::fcl::Quadrilateral::operator==
bool operator==(const Quadrilateral &other) const
Definition: data_types.h:159
hpp::fcl::Triangle::size_type
int size_type
Definition: data_types.h:99
hpp::fcl::Matrix3f
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
Definition: data_types.h:68
hpp::fcl::Triangle::vids
index_type vids[3]
indices for each vertex of triangle
Definition: data_types.h:130
hpp::fcl::GJKInitialGuess
GJKInitialGuess
Initial guess to use for the GJK algorithm DefaultGuess: Vec3f(1, 0, 0) CachedGuess: previous vector ...
Definition: data_types.h:80
hpp::fcl::DefaultGuess
@ DefaultGuess
Definition: data_types.h:80
hpp::fcl::Matrixx3f
Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 3 > Matrixx3f
Definition: data_types.h:69
hpp::fcl::Quadrilateral::size_type
int size_type
Definition: data_types.h:136
hpp::fcl::Quadrilateral::Quadrilateral
Quadrilateral(index_type p0, index_type p1, index_type p2, index_type p3)
Definition: data_types.h:140
hpp::fcl::Quadrilateral::operator!=
bool operator!=(const Quadrilateral &other) const
Definition: data_types.h:164
hpp::fcl::Triangle
Triangle with 3 indices for points.
Definition: data_types.h:96
hpp::fcl::DualityGap
@ DualityGap
Definition: data_types.h:89
hpp::fcl::Absolute
@ Absolute
Definition: data_types.h:93
hpp::fcl::GJKVariant
GJKVariant
Variant to use for the GJK algorithm.
Definition: data_types.h:83
hpp::fcl::Quadrilateral::index_type
std::size_t index_type
Definition: data_types.h:135
hpp::fcl::NesterovAcceleration
@ NesterovAcceleration
Definition: data_types.h:83


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