Skip to content

Commit 89ce322

Browse files
authored
Merge pull request #255 from fmessmer/fcl_migration
fcl noetic compatibility
2 parents 3f26461 + b852fc2 commit 89ce322

18 files changed

+184
-112
lines changed

.travis.rosinstall.noetic

Lines changed: 0 additions & 8 deletions
This file was deleted.

.travis.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ env:
1717
- ROS_REPO=main
1818
matrix:
1919
- ROS_DISTRO=melodic
20-
- ROS_DISTRO=noetic UPSTREAM_WORKSPACE='.travis.rosinstall.noetic -cob_command_tools/cob_command_gui -cob_command_tools/cob_command_tools' CATKIN_LINT_ARGS='--ignore description_boilerplate --ignore target_name_collision --ignore unknown_package'
20+
- ROS_DISTRO=noetic
2121
install:
2222
- git clone --quiet --depth 1 https://github.com/ros-industrial/industrial_ci.git .industrial_ci -b master
2323
script:

cob_obstacle_distance/include/cob_obstacle_distance/fcl_marker_converter.hpp

Lines changed: 37 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,25 @@
1919
#define FCL_MARKER_CONVERTER_HPP_
2020

2121
#include <boost/scoped_ptr.hpp>
22-
#include <fcl/shape/geometric_shapes.h>
23-
#include <fcl/BVH/BVH_model.h>
24-
#include <fcl/shape/geometric_shape_to_BVH_model.h>
22+
23+
#include <fcl/config.h>
24+
#if FCL_MINOR_VERSION == 5
25+
#include <fcl/shape/geometric_shapes.h>
26+
#include <fcl/BVH/BVH_model.h>
27+
#include <fcl/shape/geometric_shape_to_BVH_model.h>
28+
typedef fcl::Box FCL_Box;
29+
typedef fcl::Sphere FCL_Sphere;
30+
typedef fcl::Cylinder FCL_Cylinder;
31+
#else
32+
#include <fcl/geometry/shape/box.h>
33+
#include <fcl/geometry/shape/sphere.h>
34+
#include <fcl/geometry/shape/cylinder.h>
35+
#include <fcl/geometry/bvh/BVH_model.h>
36+
#include <fcl/geometry/geometric_shape_to_BVH_model.h>
37+
typedef fcl::Boxf FCL_Box;
38+
typedef fcl::Spheref FCL_Sphere;
39+
typedef fcl::Cylinderf FCL_Cylinder;
40+
#endif
2541

2642

2743
#include "cob_obstacle_distance/marker_shapes/marker_shapes_interface.hpp"
@@ -43,16 +59,16 @@ class FclMarkerConverter
4359
};
4460

4561
template<>
46-
class FclMarkerConverter<fcl::Box>
62+
class FclMarkerConverter<FCL_Box>
4763
{
48-
typedef boost::scoped_ptr<fcl::Box> sPtrBox;
64+
typedef boost::scoped_ptr<FCL_Box> sPtrBox;
4965

5066
private:
51-
fcl::Box geo_shape_;
67+
FCL_Box geo_shape_;
5268

5369
public:
54-
FclMarkerConverter() : geo_shape_(fcl::Box(1.0, 1.0, 1.0)) {}
55-
FclMarkerConverter(fcl::Box& box) : geo_shape_(box) {}
70+
FclMarkerConverter() : geo_shape_(FCL_Box(1.0, 1.0, 1.0)) {}
71+
FclMarkerConverter(FCL_Box& box) : geo_shape_(box) {}
5672

5773
void assignValues(visualization_msgs::Marker& marker)
5874
{
@@ -62,7 +78,7 @@ class FclMarkerConverter<fcl::Box>
6278
marker.type = visualization_msgs::Marker::CUBE;
6379
}
6480

65-
fcl::Box getGeoShape() const
81+
FCL_Box getGeoShape() const
6682
{
6783
return geo_shape_;
6884
}
@@ -75,16 +91,16 @@ class FclMarkerConverter<fcl::Box>
7591
};
7692

7793
template<>
78-
class FclMarkerConverter<fcl::Sphere>
94+
class FclMarkerConverter<FCL_Sphere>
7995
{
80-
typedef boost::scoped_ptr<fcl::Sphere> sPtrSphere;
96+
typedef boost::scoped_ptr<FCL_Sphere> sPtrSphere;
8197

8298
private:
83-
fcl::Sphere geo_shape_;
99+
FCL_Sphere geo_shape_;
84100

85101
public:
86-
FclMarkerConverter() : geo_shape_(fcl::Sphere(1.0)) {}
87-
FclMarkerConverter(fcl::Sphere &sphere) : geo_shape_(sphere) {}
102+
FclMarkerConverter() : geo_shape_(FCL_Sphere(1.0)) {}
103+
FclMarkerConverter(FCL_Sphere &sphere) : geo_shape_(sphere) {}
88104

89105
void assignValues(visualization_msgs::Marker &marker)
90106
{
@@ -94,7 +110,7 @@ class FclMarkerConverter<fcl::Sphere>
94110
marker.type = visualization_msgs::Marker::SPHERE;
95111
}
96112

97-
fcl::Sphere getGeoShape() const
113+
FCL_Sphere getGeoShape() const
98114
{
99115
return geo_shape_;
100116
}
@@ -113,16 +129,16 @@ class FclMarkerConverter<fcl::Sphere>
113129
};
114130

115131
template<>
116-
class FclMarkerConverter<fcl::Cylinder>
132+
class FclMarkerConverter<FCL_Cylinder>
117133
{
118-
typedef boost::scoped_ptr<fcl::Cylinder> sPtrCylinder;
134+
typedef boost::scoped_ptr<FCL_Cylinder> sPtrCylinder;
119135

120136
private:
121-
fcl::Cylinder geo_shape_;
137+
FCL_Cylinder geo_shape_;
122138

123139
public:
124-
FclMarkerConverter() : geo_shape_(fcl::Cylinder(1.0, 1.0)) {}
125-
FclMarkerConverter(fcl::Cylinder &cyl) : geo_shape_(cyl) {}
140+
FclMarkerConverter() : geo_shape_(FCL_Cylinder(1.0, 1.0)) {}
141+
FclMarkerConverter(FCL_Cylinder &cyl) : geo_shape_(cyl) {}
126142

127143
void assignValues(visualization_msgs::Marker &marker)
128144
{
@@ -132,7 +148,7 @@ class FclMarkerConverter<fcl::Cylinder>
132148
marker.type = visualization_msgs::Marker::CYLINDER;
133149
}
134150

135-
fcl::Cylinder getGeoShape() const
151+
FCL_Cylinder getGeoShape() const
136152
{
137153
return geo_shape_;
138154
}

cob_obstacle_distance/include/cob_obstacle_distance/link_to_collision.hpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -28,11 +28,6 @@
2828
#include <boost/scoped_ptr.hpp>
2929
#include <boost/pointer_cast.hpp>
3030

31-
#include <fcl/collision_object.h>
32-
#include <fcl/collision.h>
33-
#include <fcl/distance.h>
34-
#include <fcl/collision_data.h>
35-
3631
#include <std_msgs/ColorRGBA.h>
3732
#include <geometry_msgs/Vector3.h>
3833
#include <geometry_msgs/Quaternion.h>

cob_obstacle_distance/include/cob_obstacle_distance/marker_shapes/marker_shapes.hpp

Lines changed: 12 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -23,15 +23,18 @@
2323
#include <shape_msgs/Mesh.h>
2424
#include <shape_msgs/MeshTriangle.h>
2525

26-
#include "fcl/shape/geometric_shapes.h"
27-
#include "fcl/collision_object.h"
26+
#include <fcl/config.h>
27+
#if FCL_MINOR_VERSION == 5
28+
#include "fcl/collision_object.h"
29+
typedef fcl::CollisionObject FCL_CollisionObject;
30+
#else
31+
#include <fcl/narrowphase/collision_object.h>
32+
typedef fcl::CollisionObjectf FCL_CollisionObject;
33+
#endif
2834

2935
#include "cob_obstacle_distance/fcl_marker_converter.hpp"
3036
#include "cob_obstacle_distance/marker_shapes/marker_shapes_interface.hpp"
3137

32-
#include <fcl/distance.h>
33-
#include <fcl/collision_data.h>
34-
3538
static const std::string g_marker_namespace = "collision_object";
3639

3740
/* BEGIN MarkerShape ********************************************************************************************/
@@ -92,9 +95,9 @@ class MarkerShape : public IMarkerShape
9295
inline void updatePose(const geometry_msgs::Pose& pose);
9396

9497
/**
95-
* @return A fcl::CollisionObject to calculate distances to other objects or check whether collision occurred or not.
98+
* @return A FCL_CollisionObject to calculate distances to other objects or check whether collision occurred or not.
9699
*/
97-
fcl::CollisionObject getCollisionObject() const;
100+
FCL_CollisionObject getCollisionObject() const;
98101

99102
virtual ~MarkerShape(){}
100103
};
@@ -155,9 +158,9 @@ class MarkerShape<BVH_RSS_t> : public IMarkerShape
155158
inline void updatePose(const geometry_msgs::Pose& pose);
156159

157160
/**
158-
* @return A fcl::CollisionObject to calculate distances to other objects or check whether collision occurred or not.
161+
* @return A FCL_CollisionObject to calculate distances to other objects or check whether collision occurred or not.
159162
*/
160-
fcl::CollisionObject getCollisionObject() const;
163+
FCL_CollisionObject getCollisionObject() const;
161164

162165
virtual ~MarkerShape(){}
163166
};

cob_obstacle_distance/include/cob_obstacle_distance/marker_shapes/marker_shapes_impl.hpp

Lines changed: 24 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,15 @@
1818
#ifndef MARKER_SHAPES_IMPL_HPP_
1919
#define MARKER_SHAPES_IMPL_HPP_
2020

21+
#include <fcl/config.h>
22+
#if FCL_MINOR_VERSION == 5
23+
typedef fcl::Vec3f FCL_Vec3;
24+
typedef fcl::Quaternion3f FCL_Quaternion;
25+
#else
26+
typedef fcl::Vector3f FCL_Vec3;
27+
typedef fcl::Quaternionf FCL_Quaternion;
28+
#endif
29+
2130
#include "cob_obstacle_distance/marker_shapes/marker_shapes.hpp"
2231

2332
/* BEGIN MarkerShape ********************************************************************************************/
@@ -115,16 +124,22 @@ inline visualization_msgs::Marker MarkerShape<T>::getMarker()
115124

116125

117126
template <typename T>
118-
fcl::CollisionObject MarkerShape<T>::getCollisionObject() const
127+
FCL_CollisionObject MarkerShape<T>::getCollisionObject() const
119128
{
120-
fcl::Transform3f x(fcl::Quaternion3f(this->marker_.pose.orientation.w,
121-
this->marker_.pose.orientation.x,
122-
this->marker_.pose.orientation.y,
123-
this->marker_.pose.orientation.z),
124-
fcl::Vec3f(this->marker_.pose.position.x,
125-
this->marker_.pose.position.y,
126-
this->marker_.pose.position.z));
127-
fcl::CollisionObject cobj(this->ptr_fcl_bvh_, x);
129+
// FIXME
130+
// fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
131+
// this->marker_.pose.orientation.x,
132+
// this->marker_.pose.orientation.y,
133+
// this->marker_.pose.orientation.z),
134+
// FCL_Vec3(this->marker_.pose.position.x,
135+
// this->marker_.pose.position.y,
136+
// this->marker_.pose.position.z));
137+
fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
138+
this->marker_.pose.orientation.x,
139+
this->marker_.pose.orientation.y,
140+
this->marker_.pose.orientation.z));
141+
142+
FCL_CollisionObject cobj(this->ptr_fcl_bvh_, x);
128143
return cobj;
129144
}
130145

cob_obstacle_distance/include/cob_obstacle_distance/marker_shapes/marker_shapes_interface.hpp

Lines changed: 15 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,19 @@
2121
#include <boost/shared_ptr.hpp>
2222
#include <stdint.h>
2323
#include <visualization_msgs/Marker.h>
24-
#include <fcl/collision_object.h>
25-
#include <fcl/BVH/BVH_model.h>
24+
25+
#include <fcl/config.h>
26+
#if FCL_MINOR_VERSION == 5
27+
#include <fcl/collision_object.h>
28+
#include <fcl/BVH/BVH_model.h>
29+
typedef fcl::RSS FCL_RSS;
30+
typedef fcl::CollisionObject FCL_CollisionObject;
31+
#else
32+
#include <fcl/narrowphase/collision_object.h>
33+
#include <fcl/geometry/bvh/BVH_model.h>
34+
typedef fcl::RSSf FCL_RSS;
35+
typedef fcl::CollisionObjectf FCL_CollisionObject;
36+
#endif
2637

2738
/* BEGIN IMarkerShape *******************************************************************************************/
2839
/// Interface class marking methods that have to be implemented in derived classes.
@@ -41,7 +52,7 @@ class IMarkerShape
4152
virtual visualization_msgs::Marker getMarker() = 0;
4253
virtual void updatePose(const geometry_msgs::Vector3& pos, const geometry_msgs::Quaternion& quat) = 0;
4354
virtual void updatePose(const geometry_msgs::Pose& pose) = 0;
44-
virtual fcl::CollisionObject getCollisionObject() const = 0;
55+
virtual FCL_CollisionObject getCollisionObject() const = 0;
4556
virtual geometry_msgs::Pose getMarkerPose() const = 0;
4657
virtual geometry_msgs::Pose getOriginRelToFrame() const = 0;
4758

@@ -66,6 +77,6 @@ class IMarkerShape
6677
/* END IMarkerShape *********************************************************************************************/
6778

6879
typedef std::shared_ptr< IMarkerShape > PtrIMarkerShape_t;
69-
typedef fcl::BVHModel<fcl::RSS> BVH_RSS_t;
80+
typedef fcl::BVHModel<FCL_RSS> BVH_RSS_t;
7081

7182
#endif /* MARKER_SHAPES_INTERFACE_HPP_ */

cob_obstacle_distance/include/cob_obstacle_distance/obstacle_distance_data_types.hpp

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,13 @@
2424
#include <shape_msgs/SolidPrimitive.h>
2525
#include <visualization_msgs/Marker.h>
2626

27+
#include <fcl/config.h>
28+
#if FCL_MINOR_VERSION == 5
29+
typedef fcl::Vec3f FCL_Vec3;
30+
#else
31+
typedef fcl::Vector3f FCL_Vec3;
32+
#endif
33+
2734
#define FCL_BOX_X 0u
2835
#define FCL_BOX_Y 1u
2936
#define FCL_BOX_Z 2u
@@ -57,9 +64,9 @@ struct ShapeMsgTypeToVisMarkerType
5764

5865
struct TriangleSupport
5966
{
60-
fcl::Vec3f a;
61-
fcl::Vec3f b;
62-
fcl::Vec3f c;
67+
FCL_Vec3 a;
68+
FCL_Vec3 b;
69+
FCL_Vec3 c;
6370
};
6471

6572
static ShapeMsgTypeToVisMarkerType g_shapeMsgTypeToVisMarkerType;

cob_obstacle_distance/include/cob_obstacle_distance/parsers/mesh_parser.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
class MeshParser : public ParserBase
2828
{
2929
private:
30-
int8_t toVec3f(uint32_t num_current_face, aiVector3D* vertex, fcl::Vec3f& out);
30+
int8_t toVec3f(uint32_t num_current_face, aiVector3D* vertex, FCL_Vec3& out);
3131

3232
public:
3333
MeshParser(const std::string& file_path)

cob_obstacle_distance/include/cob_obstacle_distance/parsers/parser_base.hpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,13 @@
1919
#define PARSER_BASE_HPP_
2020

2121
#include <stdint.h>
22-
#include <fcl/BVH/BVH_model.h>
23-
#include <fcl/math/vec_3f.h>
22+
23+
#include <fcl/config.h>
24+
#if FCL_MINOR_VERSION == 5
25+
#include <fcl/BVH/BVH_model.h>
26+
#else
27+
#include <fcl/geometry/bvh/BVH_model.h>
28+
#endif
2429

2530
#include "cob_obstacle_distance/obstacle_distance_data_types.hpp"
2631

0 commit comments

Comments
 (0)