Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Guilhem Saurel
hpp-fcl
Commits
3852a0f8
Unverified
Commit
3852a0f8
authored
Dec 09, 2019
by
Justin Carpentier
Committed by
GitHub
Dec 09, 2019
Browse files
Merge pull request #116 from jcarpent/topic/python
Improve bindings + remove borring warnings + fix
parents
f46b141f
0fef5b66
Changes
37
Show whitespace changes
Inline
Side-by-side
CMakeLists.txt
View file @
3852a0f8
...
...
@@ -41,6 +41,9 @@ set(PROJECT_DESCRIPTION
)
SET
(
PROJECT_USE_CMAKE_EXPORT TRUE
)
SET
(
CMAKE_C_STANDARD 99
)
SET
(
CMAKE_CXX_STANDARD 98
)
# Do not support CMake older than 2.8.12
CMAKE_POLICY
(
SET CMP0022 NEW
)
SET
(
PROJECT_USE_KEYWORD_LINK_LIBRARIES TRUE
)
...
...
@@ -55,6 +58,7 @@ include(cmake/boost.cmake)
include
(
cmake/python.cmake
)
include
(
cmake/hpp.cmake
)
include
(
cmake/apple.cmake
)
include
(
cmake/ide.cmake
)
# If needed, fix CMake policy for APPLE systems
APPLY_DEFAULT_APPLE_CONFIGURATION
()
...
...
cmake
@
a99dc925
Compare
308d3c94
...
a99dc925
Subproject commit
308d3c947a3e276b06c5fa79894119346635de4d
Subproject commit
a99dc925bde7b976ae1ed286d0ab38906c73dff5
include/hpp/fcl/BV/AABB.h
View file @
3852a0f8
...
...
@@ -38,14 +38,15 @@
#ifndef HPP_FCL_AABB_H
#define HPP_FCL_AABB_H
#include
<stdexcept>
#include
<hpp/fcl/data_types.h>
namespace
hpp
{
namespace
fcl
{
class
CollisionRequest
;
struct
CollisionRequest
;
/// @defgroup Bounding_Volume
/// regroup class of differents types of bounding volume.
/// @{
...
...
include/hpp/fcl/BV/BV.h
View file @
3852a0f8
...
...
@@ -62,7 +62,7 @@ template<typename BV1, typename BV2>
class
Converter
{
private:
static
void
convert
(
const
BV1
&
bv1
,
const
Transform3f
&
tf1
,
BV2
&
bv2
)
static
void
convert
(
const
BV1
&
/*
bv1
*/
,
const
Transform3f
&
/*
tf1
*/
,
BV2
&
/*
bv2
*/
)
{
// should only use the specialized version, so it is private.
}
...
...
include/hpp/fcl/BV/BV_node.h
View file @
3852a0f8
...
...
@@ -107,11 +107,15 @@ struct BVNode : public BVNodeBase
return
bv
.
distance
(
other
.
bv
,
P1
,
P2
);
}
/// @brief Access the center of the BV
/// @brief Access
to
the center of the BV
Vec3f
getCenter
()
const
{
return
bv
.
center
();
}
/// @brief Access the orientation of the BV
const
Matrix3f
&
getOrientation
()
const
{
return
Matrix3f
::
Identity
();
}
/// @brief Access to the orientation of the BV
const
Matrix3f
&
getOrientation
()
const
{
static
const
Matrix3f
id3
=
Matrix3f
::
Identity
();
return
id3
;
}
};
template
<
>
...
...
include/hpp/fcl/BV/OBB.h
View file @
3852a0f8
...
...
@@ -44,7 +44,8 @@ namespace hpp
{
namespace
fcl
{
class
CollisionRequest
;
struct
CollisionRequest
;
/// @addtogroup Bounding_Volume
/// @{
...
...
include/hpp/fcl/BV/OBBRSS.h
View file @
3852a0f8
...
...
@@ -46,7 +46,8 @@ namespace hpp
{
namespace
fcl
{
class
CollisionRequest
;
struct
CollisionRequest
;
/// @addtogroup Bounding_Volume
/// @{
...
...
include/hpp/fcl/BV/RSS.h
View file @
3852a0f8
...
...
@@ -38,7 +38,6 @@
#ifndef HPP_FCL_RSS_H
#define HPP_FCL_RSS_H
#include
<stdexcept>
#include
<hpp/fcl/data_types.h>
#include
<boost/math/constants/constants.hpp>
...
...
@@ -47,7 +46,8 @@ namespace hpp
namespace
fcl
{
class
CollisionRequest
;
struct
CollisionRequest
;
/// @addtogroup Bounding_Volume
/// @{
...
...
include/hpp/fcl/BV/kDOP.h
View file @
3852a0f8
...
...
@@ -46,7 +46,7 @@ namespace hpp
namespace
fcl
{
class
CollisionRequest
;
struct
CollisionRequest
;
/// @addtogroup Bounding_Volume
/// @{
...
...
include/hpp/fcl/BV/kIOS.h
View file @
3852a0f8
...
...
@@ -45,7 +45,8 @@ namespace hpp
{
namespace
fcl
{
class
CollisionRequest
;
struct
CollisionRequest
;
/// @addtogroup Bounding_Volume
/// @{
...
...
include/hpp/fcl/collision_data.h
View file @
3852a0f8
...
...
@@ -129,6 +129,11 @@ struct Contact
&&
pos
==
other
.
pos
&&
penetration_depth
==
other
.
penetration_depth
;
}
bool
operator
!=
(
const
Contact
&
other
)
const
{
return
!
(
*
this
==
other
);
}
};
struct
CollisionResult
;
...
...
include/hpp/fcl/internal/tools.h
View file @
3852a0f8
...
...
@@ -207,3 +207,4 @@ bool isEqual(const Eigen::MatrixBase<Derived>& lhs, const Eigen::MatrixBase<Othe
}
// namespace hpp
#endif
include/hpp/fcl/internal/traversal_node_base.h
View file @
3852a0f8
...
...
@@ -182,3 +182,4 @@ public:
/// @endcond
#endif
include/hpp/fcl/math/transform.h
View file @
3852a0f8
...
...
@@ -55,17 +55,6 @@ static inline std::ostream& operator << (std::ostream& o, const Quaternion3f& q)
return
o
;
}
inline
bool
isQuatIdentity
(
const
Quaternion3f
&
q
)
{
return
(
q
.
w
()
==
1
||
q
.
w
()
==
-
1
)
&&
q
.
x
()
==
0
&&
q
.
y
()
==
0
&&
q
.
z
()
==
0
;
}
inline
bool
areQuatEquals
(
const
Quaternion3f
&
q1
,
const
Quaternion3f
&
q2
)
{
return
(
q1
.
w
()
==
q2
.
w
()
&&
q1
.
x
()
==
q2
.
x
()
&&
q1
.
y
()
==
q2
.
y
()
&&
q1
.
z
()
==
q2
.
z
())
||
(
q1
.
w
()
==
-
q2
.
w
()
&&
q1
.
x
()
==
-
q2
.
x
()
&&
q1
.
y
()
==
-
q2
.
y
()
&&
q1
.
z
()
==
-
q2
.
z
());
}
/// @brief Simple transform class used locally by InterpMotion
class
Transform3f
{
...
...
@@ -140,8 +129,9 @@ public:
}
/// @brief set transform from rotation and translation
template
<
typename
Matrixx3Like
,
typename
Vector3Like
>
inline
void
setTransform
(
const
Eigen
::
MatrixBase
<
Matrixx3Like
>&
R_
,
const
Eigen
::
MatrixBase
<
Vector3Like
>&
T_
)
template
<
typename
Matrix3Like
,
typename
Vector3Like
>
inline
void
setTransform
(
const
Eigen
::
MatrixBase
<
Matrix3Like
>&
R_
,
const
Eigen
::
MatrixBase
<
Vector3Like
>&
T_
)
{
R
.
noalias
()
=
R_
;
T
.
noalias
()
=
T_
;
...
...
@@ -242,7 +232,7 @@ public:
template
<
typename
Derived
>
inline
Quaternion3f
fromAxisAngle
(
const
Eigen
::
MatrixBase
<
Derived
>&
axis
,
FCL_REAL
angle
)
{
return
Quaternion3f
(
Eigen
::
AngleAxis
<
double
>
(
angle
,
axis
));
return
Quaternion3f
(
Eigen
::
AngleAxis
<
FCL_REAL
>
(
angle
,
axis
));
}
}
...
...
python/CMakeLists.txt
View file @
3852a0f8
...
...
@@ -39,13 +39,22 @@ SET(LIBRARY_NAME hppfcl)
INCLUDE_DIRECTORIES
(
"
${
Boost_INCLUDE_DIRS
}
"
${
PYTHON_INCLUDE_DIRS
}
)
ADD_LIBRARY
(
${
LIBRARY_NAME
}
SHARED
SET
(
${
LIBRARY_NAME
}
_HEADERS
fcl.hh
)
SET
(
${
LIBRARY_NAME
}
_SOURCES
version.cc
math.cc
collision-geometries.cc
collision.cc
distance.cc
fcl.cc
)
fcl.cc
)
ADD_LIBRARY
(
${
LIBRARY_NAME
}
SHARED
${${
LIBRARY_NAME
}
_SOURCES
}
${${
LIBRARY_NAME
}
_HEADERS
}
)
ADD_HEADER_GROUP
(
${
LIBRARY_NAME
}
_HEADER
)
ADD_SOURCE_GROUP
(
${
LIBRARY_NAME
}
_SOURCES
)
TARGET_LINK_BOOST_PYTHON
(
${
LIBRARY_NAME
}
PUBLIC
)
TARGET_LINK_LIBRARIES
(
${
LIBRARY_NAME
}
PUBLIC
${
PROJECT_NAME
}
${
BOOST_system_LIBRARY
}
)
...
...
python/collision-geometries.cc
View file @
3852a0f8
//
// Software License Agreement (BSD License)
//
// Copyright (c) 2019 CNRS-LAAS
// Copyright (c) 2019 CNRS-LAAS
INRIA
// Author: Joseph Mirabel
// All rights reserved.
//
...
...
@@ -34,6 +34,8 @@
#include
<boost/python.hpp>
#include
<eigenpy/registration.hpp>
#include
"fcl.hh"
#include
<hpp/fcl/fwd.hh>
...
...
@@ -183,12 +185,19 @@ void exposeShapes ()
void
exposeCollisionGeometries
()
{
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
OBJECT_TYPE
>
())
{
enum_
<
OBJECT_TYPE
>
(
"OBJECT_TYPE"
)
.
value
(
"OT_UNKNOWN"
,
OT_UNKNOWN
)
.
value
(
"OT_BVH"
,
OT_BVH
)
.
value
(
"OT_GEOM"
,
OT_GEOM
)
.
value
(
"OT_OCTREE"
,
OT_OCTREE
)
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
NODE_TYPE
>
())
{
enum_
<
NODE_TYPE
>
(
"NODE_TYPE"
)
.
value
(
"BV_UNKNOWN"
,
BV_UNKNOWN
)
.
value
(
"BV_AABB"
,
BV_AABB
)
...
...
@@ -210,7 +219,10 @@ void exposeCollisionGeometries ()
.
value
(
"GEOM_TRIANGLE"
,
GEOM_TRIANGLE
)
.
value
(
"GEOM_OCTREE"
,
GEOM_OCTREE
)
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
CollisionGeometry
>
())
{
class_
<
CollisionGeometry
,
CollisionGeometryPtr_t
,
noncopyable
>
(
"CollisionGeometry"
,
no_init
)
.
def
(
"getObjectType"
,
&
CollisionGeometry
::
getObjectType
)
...
...
@@ -225,6 +237,7 @@ void exposeCollisionGeometries ()
.
def_readwrite
(
"aabb_radius"
,
&
CollisionGeometry
::
aabb_radius
,
"AABB radius"
)
;
}
exposeShapes
();
...
...
python/collision.cc
View file @
3852a0f8
//
// Software License Agreement (BSD License)
//
// Copyright (c) 2019 CNRS-LAAS
// Copyright (c) 2019 CNRS-LAAS
INRIA
// Author: Joseph Mirabel
// All rights reserved.
//
...
...
@@ -35,6 +35,8 @@
#include
<boost/python.hpp>
#include
<boost/python/suite/indexing/vector_indexing_suite.hpp>
#include
<eigenpy/registration.hpp>
#include
"fcl.hh"
#include
<hpp/fcl/fwd.hh>
...
...
@@ -43,17 +45,20 @@
using
namespace
boost
::
python
;
using
namespace
hpp
::
fcl
;
using
boost
::
shared_ptr
;
using
boost
::
noncopyable
;
void
exposeCollisionAPI
()
{
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
CollisionRequestFlag
>
())
{
enum_
<
CollisionRequestFlag
>
(
"CollisionRequestFlag"
)
.
value
(
"CONTACT"
,
CONTACT
)
.
value
(
"DISTANCE_LOWER_BOUND"
,
DISTANCE_LOWER_BOUND
)
.
value
(
"NO_REQUEST"
,
NO_REQUEST
)
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
CollisionRequest
>
())
{
class_
<
CollisionRequest
>
(
"CollisionRequest"
,
init
<>
())
.
def
(
init
<
CollisionRequestFlag
,
size_t
>
())
...
...
@@ -65,7 +70,10 @@ void exposeCollisionAPI ()
.
def_readwrite
(
"security_margin"
,
&
CollisionRequest
::
security_margin
)
.
def_readwrite
(
"break_distance"
,
&
CollisionRequest
::
break_distance
)
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
Contact
>
())
{
class_
<
Contact
>
(
"Contact"
,
init
<>
())
//.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int>())
//.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int, Vec3f, Vec3f, FCL_REAL>())
...
...
@@ -77,12 +85,19 @@ void exposeCollisionAPI ()
.
def_readwrite
(
"pos"
,
&
Contact
::
pos
)
.
def_readwrite
(
"penetration_depth"
,
&
Contact
::
penetration_depth
)
.
def
(
self
==
self
)
.
def
(
self
!=
self
)
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
std
::
vector
<
Contact
>
>
())
{
class_
<
std
::
vector
<
Contact
>
>
(
"StdVec_Contact"
)
.
def
(
vector_indexing_suite
<
std
::
vector
<
Contact
>
>
())
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
std
::
vector
<
CollisionResult
>
>
())
{
class_
<
CollisionResult
>
(
"CollisionResult"
,
init
<>
())
.
def
(
"isCollision"
,
&
CollisionResult
::
isCollision
)
.
def
(
"numContacts"
,
&
CollisionResult
::
numContacts
)
...
...
@@ -91,10 +106,14 @@ void exposeCollisionAPI ()
.
def
(
"addContact"
,
&
CollisionResult
::
addContact
)
.
def
(
"clear"
,
&
CollisionResult
::
clear
)
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
std
::
vector
<
CollisionResult
>
>
())
{
class_
<
std
::
vector
<
CollisionResult
>
>
(
"CollisionResult"
)
.
def
(
vector_indexing_suite
<
std
::
vector
<
CollisionResult
>
>
())
;
}
def
(
"collide"
,
static_cast
<
std
::
size_t
(
*
)(
const
CollisionObject
*
,
const
CollisionObject
*
,
const
CollisionRequest
&
,
CollisionResult
&
)
>
(
&
collide
));
...
...
python/distance.cc
View file @
3852a0f8
//
// Software License Agreement (BSD License)
//
// Copyright (c) 2019 CNRS-LAAS
// Copyright (c) 2019 CNRS-LAAS
INRIA
// Author: Joseph Mirabel
// All rights reserved.
//
...
...
@@ -35,6 +35,8 @@
#include
<boost/python.hpp>
#include
<boost/python/suite/indexing/vector_indexing_suite.hpp>
#include
<eigenpy/registration.hpp>
#include
"fcl.hh"
#include
<hpp/fcl/fwd.hh>
...
...
@@ -43,8 +45,6 @@
using
namespace
boost
::
python
;
using
namespace
hpp
::
fcl
;
using
boost
::
shared_ptr
;
using
boost
::
noncopyable
;
struct
DistanceRequestWrapper
{
...
...
@@ -54,12 +54,17 @@ struct DistanceRequestWrapper
void
exposeDistanceAPI
()
{
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
DistanceRequest
>
())
{
class_
<
DistanceRequest
>
(
"DistanceRequest"
,
init
<
optional
<
bool
,
FCL_REAL
,
FCL_REAL
>
>
())
.
def_readwrite
(
"enable_nearest_points"
,
&
DistanceRequest
::
enable_nearest_points
)
.
def_readwrite
(
"rel_err"
,
&
DistanceRequest
::
rel_err
)
.
def_readwrite
(
"abs_err"
,
&
DistanceRequest
::
abs_err
)
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
DistanceResult
>
())
{
class_
<
DistanceResult
>
(
"DistanceResult"
,
init
<>
())
.
def_readwrite
(
"min_distance"
,
&
DistanceResult
::
min_distance
)
.
def_readwrite
(
"normal"
,
&
DistanceResult
::
normal
)
...
...
@@ -73,10 +78,14 @@ void exposeDistanceAPI ()
.
def
(
"clear"
,
&
DistanceResult
::
clear
)
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
std
::
vector
<
DistanceResult
>
>
())
{
class_
<
std
::
vector
<
DistanceResult
>
>
(
"StdVec_DistanceResult"
)
.
def
(
vector_indexing_suite
<
std
::
vector
<
DistanceResult
>
>
())
;
}
def
(
"distance"
,
static_cast
<
FCL_REAL
(
*
)(
const
CollisionObject
*
,
const
CollisionObject
*
,
const
DistanceRequest
&
,
DistanceResult
&
)
>
(
&
distance
));
...
...
python/fcl.cc
View file @
3852a0f8
//
// Software License Agreement (BSD License)
//
// Copyright (c) 2019 CNRS-LAAS
// Copyright (c) 2019 CNRS-LAAS
INRIA
// Author: Joseph Mirabel
// All rights reserved.
//
...
...
@@ -34,6 +34,8 @@
#include
<boost/python.hpp>
#include
<eigenpy/registration.hpp>
#include
"fcl.hh"
#include
<hpp/fcl/fwd.hh>
...
...
@@ -47,17 +49,21 @@
using
namespace
boost
::
python
;
using
namespace
hpp
::
fcl
;
using
boost
::
shared_ptr
;
using
boost
::
noncopyable
;
void
exposeMeshLoader
()
{
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
MeshLoader
>
())
{
class_
<
MeshLoader
>
(
"MeshLoader"
,
init
<
optional
<
NODE_TYPE
>
>
())
.
def
(
"load"
,
static_cast
<
BVHModelPtr_t
(
MeshLoader
::*
)
(
const
std
::
string
&
,
const
Vec3f
&
)
>
(
&
MeshLoader
::
load
))
;
}
if
(
!
eigenpy
::
register_symbolic_link_to_registered_type
<
CachedMeshLoader
>
())
{
class_
<
CachedMeshLoader
,
bases
<
MeshLoader
>
>
(
"CachedMeshLoader"
,
init
<
optional
<
NODE_TYPE
>
>
())
;
}
}
BOOST_PYTHON_MODULE
(
hppfcl
)
...
...
src/CMakeLists.txt
View file @
3852a0f8
...
...
@@ -82,11 +82,21 @@ set(${LIBRARY_NAME}_SOURCES
mesh_loader/loader.cpp
)
SET
(
PROJECT_HEADERS_FULL_PATH
)
FOREACH
(
header
${${
PROJECT_NAME
}
_HEADERS
}
)
LIST
(
APPEND PROJECT_HEADERS_FULL_PATH
${
PROJECT_SOURCE_DIR
}
/
${
header
}
)
ENDFOREACH
()
LIST
(
APPEND PROJECT_HEADERS_FULL_PATH
${
PROJECT_BINARY_DIR
}
/include/hpp/fcl/config.hh
)
add_library
(
${
LIBRARY_NAME
}
SHARED
${
PROJECT_HEADERS_FULL_PATH
}
${${
LIBRARY_NAME
}
_SOURCES
}
)
# IDE sources and headers sorting
ADD_SOURCE_GROUP
(
${
LIBRARY_NAME
}
_SOURCES
)
ADD_HEADER_GROUP
(
PROJECT_HEADERS_FULL_PATH
)
TARGET_LINK_LIBRARIES
(
${
LIBRARY_NAME
}
PUBLIC
Boost::thread
...
...
@@ -102,7 +112,7 @@ target_include_directories(${LIBRARY_NAME}
target_include_directories
(
${
LIBRARY_NAME
}
PUBLIC
$<INSTALL_INTERFACE:
${
CMAKE_INSTALL_INCLUDEDIR
}
>
)
)
PKG_CONFIG_USE_DEPENDENCY
(
${
LIBRARY_NAME
}
assimp
)
if
(
NOT
${
ASSIMP_VERSION
}
VERSION_LESS
"2.0.1150"
)
...
...
Prev
1
2
Next
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment