DART 6.7.3
Loading...
Searching...
No Matches
BackwardCompatibility.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2019, 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 "dart/config.hpp"
37
38#include <Eigen/Dense>
39
40#define FCL_VERSION_AT_LEAST(x,y,z) \
41 (FCL_MAJOR_VERSION > x || (FCL_MAJOR_VERSION >= x && \
42 (FCL_MINOR_VERSION > y || (FCL_MINOR_VERSION >= y && \
43 FCL_PATCH_VERSION >= z))))
44
45#define FCL_MAJOR_MINOR_VERSION_AT_MOST(x,y) \
46 (FCL_MAJOR_VERSION < x || (FCL_MAJOR_VERSION <= x && \
47 (FCL_MINOR_VERSION < y || (FCL_MINOR_VERSION <= y))))
48
49#include <fcl/config.h>
50
51#if FCL_VERSION_AT_LEAST(0,6,0)
52
53#include <fcl/math/geometry.h>
54
55#include <fcl/geometry/bvh/BVH_model.h>
56#include <fcl/geometry/geometric_shape_to_BVH_model.h>
57#include <fcl/math/bv/OBBRSS.h>
58#include <fcl/math/bv/utility.h>
59#include <fcl/narrowphase/collision.h>
60#include <fcl/narrowphase/collision_object.h>
61#include <fcl/narrowphase/distance.h>
62
63#else
64
65#include <fcl/math/vec_3f.h>
66#include <fcl/math/matrix_3f.h>
67#include <fcl/math/transform.h>
68
69#include <fcl/BV/OBBRSS.h>
70#include <fcl/BVH/BVH_model.h>
71#include <fcl/collision.h>
72#include <fcl/collision_data.h>
73#include <fcl/collision_object.h>
74#include <fcl/distance.h>
75
76#endif // FCL_VERSION_AT_LEAST(0,6,0)
77
78#include <fcl/broadphase/broadphase_dynamic_AABB_tree.h>
79
80#if HAVE_OCTOMAP && defined(FCL_HAVE_OCTOMAP)
81#if FCL_VERSION_AT_LEAST(0,6,0)
82#include <fcl/geometry/octree/octree.h>
83#else
84#include <fcl/octree.h>
85#endif // FCL_VERSION_AT_LEAST(0,6,0)
86#endif // HAVE_OCTOMAP && defined(FCL_HAVE_OCTOMAP)
87
88#if FCL_VERSION_AT_LEAST(0,5,0)
89#include <memory>
90template <class T> using fcl_shared_ptr = std::shared_ptr<T>;
91template <class T> using fcl_weak_ptr = std::weak_ptr<T>;
92template <class T, class... Args>
94{
95 return std::make_shared<T>(std::forward<Args>(args)...);
96}
97#else
98#include <boost/weak_ptr.hpp>
99#include <boost/make_shared.hpp>
100template <class T> using fcl_shared_ptr = boost::shared_ptr<T>;
101template <class T> using fcl_weak_ptr = boost::weak_ptr<T>;
102template <class T, class... Args>
104{
105 return boost::make_shared<T>(std::forward<Args>(args)...);
106}
107#endif // FCL_VERSION_AT_LEAST(0,5,0)
108
109namespace dart {
110namespace collision {
111namespace fcl {
112
113#if FCL_VERSION_AT_LEAST(0,6,0)
114// Geometric fundamentals
118// Geometric primitives
119using Box = ::fcl::Box<double>;
124#if HAVE_OCTOMAP && defined(FCL_HAVE_OCTOMAP)
126#endif // HAVE_OCTOMAP && defined(FCL_HAVE_OCTOMAP)
127// Collision objects
138#else
139// Geometric fundamentals
143// Geometric primitives
148#if HAVE_OCTOMAP && defined(FCL_HAVE_OCTOMAP)
149using OcTree = ::fcl::OcTree;
150#endif // HAVE_OCTOMAP && defined(FCL_HAVE_OCTOMAP)
151// Collision objects
161#endif
162
163#if FCL_VERSION_AT_LEAST(0,4,0) && !FCL_VERSION_AT_LEAST(0,6,0)
165#endif
166
169
172
176
178void setTranslation(
181
185
187void setRotation(
190
192void setEulerZYX(
194 double eulerX,
195 double eulerY,
196 double eulerZ);
197
202
203} // namespace fcl
204} // namespace collision
205} // namespace dart
206
207#endif // DART_COLLISION_FCL_BACKWARDCOMPATIBILITY_HPP_
boost::weak_ptr< T > fcl_weak_ptr
Definition BackwardCompatibility.hpp:101
fcl_shared_ptr< T > fcl_make_shared(Args &&... args)
Definition BackwardCompatibility.hpp:103
boost::shared_ptr< T > fcl_shared_ptr
Definition BackwardCompatibility.hpp:100
::fcl::CollisionGeometry CollisionGeometry
Definition BackwardCompatibility.hpp:153
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:152
::fcl::Sphere Sphere
Definition BackwardCompatibility.hpp:147
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:155
void setRotation(dart::collision::fcl::Transform3 &T, const dart::collision::fcl::Matrix3 &R)
Sets rotation component of a transform.
Definition BackwardCompatibility.cpp:93
::fcl::CollisionResult CollisionResult
Definition BackwardCompatibility.hpp:157
::fcl::Halfspace Halfspace
Definition BackwardCompatibility.hpp:146
::fcl::DynamicAABBTreeCollisionManager DynamicAABBTreeCollisionManager
Definition BackwardCompatibility.hpp:154
::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:131
::fcl::Cylinder Cylinder
Definition BackwardCompatibility.hpp:145
::fcl::Transform3f Transform3
Definition BackwardCompatibility.hpp:142
::fcl::CollisionRequest CollisionRequest
Definition BackwardCompatibility.hpp:156
::fcl::DistanceResult DistanceResult
Definition BackwardCompatibility.hpp:159
::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:160
::fcl::DistanceRequest DistanceRequest
Definition BackwardCompatibility.hpp:158
Definition BulletCollisionDetector.cpp:63