include/hpp/fcl/fwd.hh
Go to the documentation of this file.
1 //
2 // Software License Agreement (BSD License)
3 //
4 // Copyright (c) 2014, CNRS-LAAS
5 // Copyright (c) 2022, Inria
6 // Author: Florent Lamiraux
7 //
8 // All rights reserved.
9 //
10 // Redistribution and use in source and binary forms, with or without
11 // modification, are permitted provided that the following conditions
12 // are met:
13 //
14 // * Redistributions of source code must retain the above copyright
15 // notice, this list of conditions and the following disclaimer.
16 // * Redistributions in binary form must reproduce the above
17 // copyright notice, this list of conditions and the following
18 // disclaimer in the documentation and/or other materials provided
19 // with the distribution.
20 // * Neither the name of CNRS-LAAS nor the names of its
21 // contributors may be used to endorse or promote products derived
22 // from this software without specific prior written permission.
23 //
24 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35 // POSSIBILITY OF SUCH DAMAGE.
36 //
37 
38 #ifndef HPP_FCL_FWD_HH
39 #define HPP_FCL_FWD_HH
40 
41 #include <memory>
42 #include <sstream>
43 #include <stdexcept>
44 
45 #include <hpp/fcl/config.hh>
46 #include <hpp/fcl/deprecated.hh>
47 #include <hpp/fcl/warning.hh>
48 
49 #if _WIN32
50 #define HPP_FCL_PRETTY_FUNCTION __FUNCSIG__
51 #else
52 #define HPP_FCL_PRETTY_FUNCTION __PRETTY_FUNCTION__
53 #endif
54 
55 #define HPP_FCL_UNUSED_VARIABLE(var) (void)(var)
56 
57 #define HPP_FCL_THROW_PRETTY(message, exception) \
58  { \
59  std::stringstream ss; \
60  ss << "From file: " << __FILE__ << "\n"; \
61  ss << "in function: " << HPP_FCL_PRETTY_FUNCTION << "\n"; \
62  ss << "at line: " << __LINE__ << "\n"; \
63  ss << "message: " << message << "\n"; \
64  throw exception(ss.str()); \
65  }
66 
67 #if (__cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600))
68 #define HPP_FCL_WITH_CXX11_SUPPORT
69 #endif
70 
71 #if defined(__GNUC__) || defined(__clang__)
72 #define HPP_FCL_COMPILER_DIAGNOSTIC_PUSH _Pragma("GCC diagnostic push")
73 #define HPP_FCL_COMPILER_DIAGNOSTIC_POP _Pragma("GCC diagnostic pop")
74 #define HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS \
75  _Pragma("GCC diagnostic ignored \"-Wdeprecated-declarations\"")
76 #elif defined(WIN32)
77 #define HPP_FCL_COMPILER_DIAGNOSTIC_PUSH _Pragma("warning(push)")
78 #define HPP_FCL_COMPILER_DIAGNOSTIC_POP _Pragma("warning(pop)")
79 #define HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS \
80  _Pragma("warning(disable : 4996)")
81 #else
82 #define HPP_FCL_COMPILER_DIAGNOSTIC_PUSH
83 #define HPP_FCL_COMPILER_DIAGNOSTIC_POP
84 #define HPP_FCL_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
85 #endif // __GNUC__
86 
87 namespace hpp {
88 namespace fcl {
89 using std::dynamic_pointer_cast;
90 using std::make_shared;
91 using std::shared_ptr;
92 
94 typedef shared_ptr<CollisionObject> CollisionObjectPtr_t;
95 typedef shared_ptr<const CollisionObject> CollisionObjectConstPtr_t;
97 typedef shared_ptr<CollisionGeometry> CollisionGeometryPtr_t;
98 typedef shared_ptr<const CollisionGeometry> CollisionGeometryConstPtr_t;
99 class Transform3f;
100 
101 class AABB;
102 
104 typedef shared_ptr<BVHModelBase> BVHModelPtr_t;
105 
106 class OcTree;
107 typedef shared_ptr<OcTree> OcTreePtr_t;
108 typedef shared_ptr<const OcTree> OcTreeConstPtr_t;
109 } // namespace fcl
110 } // namespace hpp
111 
112 #endif // HPP_FCL_FWD_HH
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
shared_ptr< CollisionObject > CollisionObjectPtr_t
Main namespace.
A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewe...
Definition: BVH/BVH_model.h:63
Octree is one type of collision geometry which can encode uncertainty information in the sensor data...
Definition: octree.h:53
shared_ptr< OcTree > OcTreePtr_t
shared_ptr< const CollisionObject > CollisionObjectConstPtr_t
shared_ptr< BVHModelBase > BVHModelPtr_t
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: BV/AABB.h:54
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
shared_ptr< const CollisionGeometry > CollisionGeometryConstPtr_t
shared_ptr< const OcTree > OcTreeConstPtr_t
the object for collision or distance computation, contains the geometry and the transform information...
The geometry for the object for collision or distance computation.


hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:01