coal/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  * Copyright (c) 2023, Inria
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Open Source Robotics Foundation nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  */
36 
39 #ifndef COAL_DATA_TYPES_H
40 #define COAL_DATA_TYPES_H
41 
42 #include <Eigen/Core>
43 #include <Eigen/Geometry>
44 
45 #include "coal/config.hh"
46 
47 #ifdef COAL_HAS_OCTOMAP
48 #define OCTOMAP_VERSION_AT_LEAST(x, y, z) \
49  (OCTOMAP_MAJOR_VERSION > x || \
50  (OCTOMAP_MAJOR_VERSION >= x && \
51  (OCTOMAP_MINOR_VERSION > y || \
52  (OCTOMAP_MINOR_VERSION >= y && OCTOMAP_PATCH_VERSION >= z))))
53 
54 #define OCTOMAP_VERSION_AT_MOST(x, y, z) \
55  (OCTOMAP_MAJOR_VERSION < x || \
56  (OCTOMAP_MAJOR_VERSION <= x && \
57  (OCTOMAP_MINOR_VERSION < y || \
58  (OCTOMAP_MINOR_VERSION <= y && OCTOMAP_PATCH_VERSION <= z))))
59 #endif // COAL_HAS_OCTOMAP
60 
61 namespace coal {
62 #ifdef COAL_BACKWARD_COMPATIBILITY_WITH_HPP_FCL
63 // We keep the FCL_REAL typedef and the Vec[..]f typedefs for backward
64 // compatibility.
65 typedef double FCL_REAL;
66 typedef Eigen::Matrix<FCL_REAL, 3, 1> Vec3f;
67 typedef Eigen::Matrix<FCL_REAL, 2, 1> Vec2f;
68 typedef Eigen::Matrix<FCL_REAL, 6, 1> Vec6f;
69 typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 1> VecXf;
70 typedef Eigen::Matrix<FCL_REAL, 3, 3> Matrix3f;
71 typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 3, Eigen::RowMajor> Matrixx3f;
72 typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 2, Eigen::RowMajor> Matrixx2f;
73 typedef Eigen::Matrix<FCL_REAL, Eigen::Dynamic, Eigen::Dynamic> MatrixXf;
74 #endif
75 
76 typedef double CoalScalar;
77 typedef Eigen::Matrix<CoalScalar, 3, 1> Vec3s;
78 typedef Eigen::Matrix<CoalScalar, 2, 1> Vec2s;
79 typedef Eigen::Matrix<CoalScalar, 6, 1> Vec6s;
80 typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, 1> VecXs;
81 typedef Eigen::Matrix<CoalScalar, 3, 3> Matrix3s;
82 typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, 3, Eigen::RowMajor> MatrixX3s;
83 typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, 2, Eigen::RowMajor> MatrixX2s;
84 typedef Eigen::Matrix<Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor>
86 typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, Eigen::Dynamic> MatrixXs;
87 typedef Eigen::Vector2i support_func_guess_t;
88 
96 
99 
105 
109 
111 class COAL_DLLAPI Triangle {
112  public:
113  typedef std::size_t index_type;
114  typedef int size_type;
115 
117  Triangle() {}
118 
120  Triangle(index_type p1, index_type p2, index_type p3) { set(p1, p2, p3); }
121 
123  inline void set(index_type p1, index_type p2, index_type p3) {
124  vids[0] = p1;
125  vids[1] = p2;
126  vids[2] = p3;
127  }
128 
130  inline index_type operator[](index_type i) const { return vids[i]; }
131 
132  inline index_type& operator[](index_type i) { return vids[i]; }
133 
134  static inline size_type size() { return 3; }
135 
136  bool operator==(const Triangle& other) const {
137  return vids[0] == other.vids[0] && vids[1] == other.vids[1] &&
138  vids[2] == other.vids[2];
139  }
140 
141  bool operator!=(const Triangle& other) const { return !(*this == other); }
142 
143  bool isValid() const {
144  return vids[0] != (std::numeric_limits<index_type>::max)() &&
145  vids[1] != (std::numeric_limits<index_type>::max)() &&
146  vids[2] != (std::numeric_limits<index_type>::max)();
147  }
148 
149  private:
151  index_type vids[3] = {(std::numeric_limits<index_type>::max)(),
152  (std::numeric_limits<index_type>::max)(),
153  (std::numeric_limits<index_type>::max)()};
154 };
155 
157 struct COAL_DLLAPI Quadrilateral {
158  typedef std::size_t index_type;
159  typedef int size_type;
160 
162 
164  set(p0, p1, p2, p3);
165  }
166 
168  inline void set(index_type p0, index_type p1, index_type p2, index_type p3) {
169  vids[0] = p0;
170  vids[1] = p1;
171  vids[2] = p2;
172  vids[3] = p3;
173  }
174 
176  inline index_type operator[](index_type i) const { return vids[i]; }
177 
178  inline index_type& operator[](index_type i) { return vids[i]; }
179 
180  static inline size_type size() { return 4; }
181 
182  bool operator==(const Quadrilateral& other) const {
183  return vids[0] == other.vids[0] && vids[1] == other.vids[1] &&
184  vids[2] == other.vids[2] && vids[3] == other.vids[3];
185  }
186 
187  bool operator!=(const Quadrilateral& other) const {
188  return !(*this == other);
189  }
190 
191  private:
192  index_type vids[4];
193 };
194 
195 } // namespace coal
196 
197 #endif
coal::Triangle::isValid
bool isValid() const
Definition: coal/data_types.h:143
coal::GJKConvergenceCriterion
GJKConvergenceCriterion
Which convergence criterion is used to stop the algorithm (when the shapes are not in collision)....
Definition: coal/data_types.h:104
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::Triangle::Triangle
Triangle(index_type p1, index_type p2, index_type p3)
Create a triangle with given vertex indices.
Definition: coal/data_types.h:120
coal::Hybrid
@ Hybrid
Definition: coal/data_types.h:104
coal::MatrixX2s
Eigen::Matrix< CoalScalar, Eigen::Dynamic, 2, Eigen::RowMajor > MatrixX2s
Definition: coal/data_types.h:83
coal::Triangle::Triangle
Triangle()
Default constructor.
Definition: coal/data_types.h:117
coal::Triangle::size_type
int size_type
Definition: coal/data_types.h:114
coal::Triangle::set
void set(index_type p1, index_type p2, index_type p3)
Set the vertex indices of the triangle.
Definition: coal/data_types.h:123
coal::GJKConvergenceCriterionType
GJKConvergenceCriterionType
Wether the convergence criterion is scaled on the norm of the solution or not.
Definition: coal/data_types.h:108
coal::DefaultGuess
@ DefaultGuess
Definition: coal/data_types.h:95
coal::Triangle::operator!=
bool operator!=(const Triangle &other) const
Definition: coal/data_types.h:141
coal::Quadrilateral
Quadrilateral with 4 indices for points.
Definition: coal/data_types.h:157
coal::Relative
@ Relative
Definition: coal/data_types.h:108
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::Triangle::index_type
std::size_t index_type
Definition: coal/data_types.h:113
coal::Triangle::operator==
bool operator==(const Triangle &other) const
Definition: coal/data_types.h:136
coal::CachedGuess
@ CachedGuess
Definition: coal/data_types.h:95
coal::Default
@ Default
Definition: coal/data_types.h:104
coal::DefaultGJK
@ DefaultGJK
Definition: coal/data_types.h:98
coal::GJKVariant
GJKVariant
Variant to use for the GJK algorithm.
Definition: coal/data_types.h:98
coal::Quadrilateral::Quadrilateral
Quadrilateral()
Definition: coal/data_types.h:161
coal::Quadrilateral::index_type
std::size_t index_type
Definition: coal/data_types.h:158
coal::Triangle::operator[]
index_type operator[](index_type i) const
Access the triangle index.
Definition: coal/data_types.h:130
coal::Quadrilateral::Quadrilateral
Quadrilateral(index_type p0, index_type p1, index_type p2, index_type p3)
Definition: coal/data_types.h:163
coal::NesterovAcceleration
@ NesterovAcceleration
Definition: coal/data_types.h:98
coal::Quadrilateral::size
static size_type size()
Definition: coal/data_types.h:180
coal::support_func_guess_t
Eigen::Vector2i support_func_guess_t
Definition: coal/data_types.h:87
coal::VecXs
Eigen::Matrix< CoalScalar, Eigen::Dynamic, 1 > VecXs
Definition: coal/data_types.h:80
coal::Triangle::vids
index_type vids[3]
indices for each vertex of triangle
Definition: coal/data_types.h:151
coal::Quadrilateral::operator==
bool operator==(const Quadrilateral &other) const
Definition: coal/data_types.h:182
coal::Vec6s
Eigen::Matrix< CoalScalar, 6, 1 > Vec6s
Definition: coal/data_types.h:79
coal::Quadrilateral::operator!=
bool operator!=(const Quadrilateral &other) const
Definition: coal/data_types.h:187
coal::MatrixX3s
Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3, Eigen::RowMajor > MatrixX3s
Definition: coal/data_types.h:82
coal::PolyakAcceleration
@ PolyakAcceleration
Definition: coal/data_types.h:98
coal::BoundingVolumeGuess
@ BoundingVolumeGuess
Definition: coal/data_types.h:95
coal::Triangle::operator[]
index_type & operator[](index_type i)
Definition: coal/data_types.h:132
octree.p1
tuple p1
Definition: octree.py:54
coal::Quadrilateral::operator[]
index_type operator[](index_type i) const
@access the quadrilateral index
Definition: coal/data_types.h:176
coal::MatrixXs
Eigen::Matrix< CoalScalar, Eigen::Dynamic, Eigen::Dynamic > MatrixXs
Definition: coal/data_types.h:86
coal::Quadrilateral::set
void set(index_type p0, index_type p1, index_type p2, index_type p3)
Set the vertex indices of the quadrilateral.
Definition: coal/data_types.h:168
coal::Quadrilateral::size_type
int size_type
Definition: coal/data_types.h:159
coal::GJKInitialGuess
GJKInitialGuess
Initial guess to use for the GJK algorithm DefaultGuess: Vec3s(1, 0, 0) CachedGuess: previous vector ...
Definition: coal/data_types.h:95
coal::Matrix3s
Eigen::Matrix< CoalScalar, 3, 3 > Matrix3s
Definition: coal/data_types.h:81
coal::Triangle::size
static size_type size()
Definition: coal/data_types.h:134
coal::Quadrilateral::operator[]
index_type & operator[](index_type i)
Definition: coal/data_types.h:178
coal::DualityGap
@ DualityGap
Definition: coal/data_types.h:104
coal::Triangle
Triangle with 3 indices for points.
Definition: coal/data_types.h:111
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::Quadrilateral::vids
index_type vids[4]
Definition: coal/data_types.h:192
coal::Matrixx3i
Eigen::Matrix< Eigen::DenseIndex, Eigen::Dynamic, 3, Eigen::RowMajor > Matrixx3i
Definition: coal/data_types.h:85
coal::Vec2s
Eigen::Matrix< CoalScalar, 2, 1 > Vec2s
Definition: coal/data_types.h:78
coal::Absolute
@ Absolute
Definition: coal/data_types.h:108


hpp-fcl
Author(s):
autogenerated on Fri Feb 14 2025 03:45:50