DART 6.13.2
Loading...
Searching...
No Matches
BackwardCompatibility.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2022, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
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 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33#ifndef DART_COLLISION_FCL_BACKWARDCOMPATIBILITY_HPP_
34#define DART_COLLISION_FCL_BACKWARDCOMPATIBILITY_HPP_
35
36#include <Eigen/Dense>
37
39#include "dart/config.hpp"
40
41// clang-format off
42#define FCL_VERSION_AT_LEAST(x,y,z) \
43 (FCL_MAJOR_VERSION > x || (FCL_MAJOR_VERSION >= x && \
44 (FCL_MINOR_VERSION > y || (FCL_MINOR_VERSION >= y && \
45 FCL_PATCH_VERSION >= z))))
46
47#define FCL_MAJOR_MINOR_VERSION_AT_MOST(x,y) \
48 (FCL_MAJOR_VERSION < x || (FCL_MAJOR_VERSION <= x && \
49 (FCL_MINOR_VERSION < y || (FCL_MINOR_VERSION <= y))))
50// clang-format on
51
52#include <fcl/config.h>
53
54#if FCL_VERSION_AT_LEAST(0, 6, 0)
55
56 #include <fcl/geometry/bvh/BVH_model.h>
57 #include <fcl/geometry/geometric_shape_to_BVH_model.h>
58 #include <fcl/math/bv/OBBRSS.h>
59 #include <fcl/math/bv/utility.h>
60 #include <fcl/math/geometry.h>
61 #include <fcl/narrowphase/collision.h>
62 #include <fcl/narrowphase/collision_object.h>
63 #include <fcl/narrowphase/distance.h>
64
65#else
66
67 #include <fcl/BV/OBBRSS.h>
68 #include <fcl/BVH/BVH_model.h>
69 #include <fcl/collision.h>
70 #include <fcl/collision_data.h>
71 #include <fcl/collision_object.h>
72 #include <fcl/distance.h>
73 #include <fcl/math/matrix_3f.h>
74 #include <fcl/math/transform.h>
75 #include <fcl/math/vec_3f.h>
76 #include <fcl/shape/geometric_shape_to_BVH_model.h>
77
78#endif // FCL_VERSION_AT_LEAST(0,6,0)
79
80#include <fcl/broadphase/broadphase_dynamic_AABB_tree.h>
81
82#if HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
83 #if FCL_VERSION_AT_LEAST(0, 6, 0)
84 #include <fcl/geometry/octree/octree.h>
85 #else
86 #include <fcl/octree.h>
87 #endif // FCL_VERSION_AT_LEAST(0,6,0)
88#endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
89
90#include <memory>
91
93template <class T>
94using fcl_shared_ptr = std::shared_ptr<T>;
95
97template <class T>
98using fcl_weak_ptr = std::weak_ptr<T>;
99
101template <class T, class... Args>
102DART_DEPRECATED(6.13)
103std::shared_ptr<T> fcl_make_shared(Args&&... args)
104{
105 return std::make_shared<T>(std::forward<Args>(args)...);
106}
107
108namespace dart {
109namespace collision {
110namespace fcl {
111
112#if FCL_VERSION_AT_LEAST(0, 6, 0)
113// Geometric fundamentals
114using Vector3 = ::fcl::Vector3<double>;
115using Matrix3 = ::fcl::Matrix3<double>;
116using Transform3 = ::fcl::Transform3<double>;
117// Geometric primitives
118using Box = ::fcl::Box<double>;
119using Cylinder = ::fcl::Cylinder<double>;
120using Cone = ::fcl::Cone<double>;
121using Ellipsoid = ::fcl::Ellipsoid<double>;
122using Halfspace = ::fcl::Halfspace<double>;
123using Sphere = ::fcl::Sphere<double>;
124 #if HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
125using OcTree = ::fcl::OcTree<double>;
126 #endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
127// Collision objects
128using CollisionObject = ::fcl::CollisionObject<double>;
129using CollisionGeometry = ::fcl::CollisionGeometry<double>;
131 = ::fcl::DynamicAABBTreeCollisionManager<double>;
132using OBBRSS = ::fcl::OBBRSS<double>;
133using CollisionRequest = ::fcl::CollisionRequest<double>;
134using CollisionResult = ::fcl::CollisionResult<double>;
135using DistanceRequest = ::fcl::DistanceRequest<double>;
136using DistanceResult = ::fcl::DistanceResult<double>;
137using Contact = ::fcl::Contact<double>;
138#else
139// Geometric fundamentals
140using Vector3 = ::fcl::Vec3f;
141using Matrix3 = ::fcl::Matrix3f;
142using Transform3 = ::fcl::Transform3f;
143// Geometric primitives
149 #if HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
150using OcTree = ::fcl::OcTree;
151 #endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
152// Collision objects
162#endif
163
164#if !FCL_VERSION_AT_LEAST(0, 6, 0)
166#endif
167
170
173
175{
176#if FCL_VERSION_AT_LEAST(0, 6, 0)
177 return dart::collision::fcl::Transform3::Identity();
178#else
180#endif
181}
182
186
188void setTranslation(
191
195
197void setRotation(
200
202void setEulerZYX(
204 double eulerX,
205 double eulerY,
206 double eulerZ);
207
212
213} // namespace fcl
214} // namespace collision
215} // namespace dart
216
217#endif // DART_COLLISION_FCL_BACKWARDCOMPATIBILITY_HPP_
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
std::shared_ptr< T > fcl_make_shared(Args &&... args)
Definition BackwardCompatibility.hpp:103
std::shared_ptr< T > fcl_shared_ptr
Definition BackwardCompatibility.hpp:94
std::weak_ptr< T > fcl_weak_ptr
Definition BackwardCompatibility.hpp:98
::fcl::CollisionGeometry CollisionGeometry
Definition BackwardCompatibility.hpp:154
void setTranslation(dart::collision::fcl::Transform3 &T, const dart::collision::fcl::Vector3 &t)
Sets translation component of a transform.
Definition BackwardCompatibility.cpp:71
::fcl::CollisionObject CollisionObject
Definition BackwardCompatibility.hpp:153
::fcl::Sphere Sphere
Definition BackwardCompatibility.hpp:148
void setEulerZYX(dart::collision::fcl::Matrix3 &rot, double eulerX, double eulerY, double eulerZ)
Sets a rotation matrix given Euler-XYZ angles.
Definition BackwardCompatibility.cpp:104
double length(const dart::collision::fcl::Vector3 &t)
Returns norm of a 3-dim vector.
Definition BackwardCompatibility.cpp:40
double length2(const dart::collision::fcl::Vector3 &t)
Returns squared norm of a 3-dim vector.
Definition BackwardCompatibility.cpp:50
::fcl::OBBRSS OBBRSS
Definition BackwardCompatibility.hpp:156
void setRotation(dart::collision::fcl::Transform3 &T, const dart::collision::fcl::Matrix3 &R)
Sets rotation component of a transform.
Definition BackwardCompatibility.cpp:93
::fcl::Cone Cone
Definition BackwardCompatibility.hpp:146
::fcl::CollisionResult CollisionResult
Definition BackwardCompatibility.hpp:158
::fcl::Halfspace Halfspace
Definition BackwardCompatibility.hpp:147
::fcl::DynamicAABBTreeCollisionManager DynamicAABBTreeCollisionManager
Definition BackwardCompatibility.hpp:155
::fcl::Vec3f Vector3
Definition BackwardCompatibility.hpp:140
dart::collision::fcl::Vector3 transform(const dart::collision::fcl::Transform3 &t, const dart::collision::fcl::Vector3 &v)
Transforms a 3-dim vector by a transform and returns the result.
Definition BackwardCompatibility.cpp:133
::fcl::Cylinder Cylinder
Definition BackwardCompatibility.hpp:145
::fcl::Transform3f Transform3
Definition BackwardCompatibility.hpp:142
dart::collision::fcl::Transform3 getTransform3Identity()
Definition BackwardCompatibility.hpp:174
::fcl::Ellipsoid Ellipsoid
Definition BackwardCompatibility.hpp:165
::fcl::CollisionRequest CollisionRequest
Definition BackwardCompatibility.hpp:157
::fcl::DistanceResult DistanceResult
Definition BackwardCompatibility.hpp:160
::fcl::Matrix3f Matrix3
Definition BackwardCompatibility.hpp:141
dart::collision::fcl::Vector3 getTranslation(const dart::collision::fcl::Transform3 &T)
Returns translation component of a transform.
Definition BackwardCompatibility.cpp:60
dart::collision::fcl::Matrix3 getRotation(const dart::collision::fcl::Transform3 &T)
Returns rotation component of a transform.
Definition BackwardCompatibility.cpp:82
::fcl::Box Box
Definition BackwardCompatibility.hpp:144
::fcl::Contact Contact
Definition BackwardCompatibility.hpp:161
::fcl::DistanceRequest DistanceRequest
Definition BackwardCompatibility.hpp:159
Definition BulletCollisionDetector.cpp:60