Skip to content

Commit 92007cc

Browse files
committed
fixup: comment broken bits
1 parent 0091982 commit 92007cc

File tree

2 files changed

+15
-6
lines changed

2 files changed

+15
-6
lines changed

cob_obstacle_distance/include/cob_obstacle_distance/marker_shapes/marker_shapes_impl.hpp

Lines changed: 12 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,15 @@
2727
typedef fcl::Vector3f FCL_Vec3;
2828
#endif
2929
*/
30+
#include <fcl/config.h>
31+
#if FCL_MINOR_VERSION == 5
32+
typedef fcl::Vec3f FCL_Vec3;
33+
typedef fcl::Quaternion3f FCL_Quaternion;
34+
#else
35+
typedef fcl::Vector3f FCL_Vec3;
36+
typedef fcl::Quaternionf FCL_Quaternion;
37+
#endif
38+
3039

3140
#include "cob_obstacle_distance/marker_shapes/marker_shapes.hpp"
3241

@@ -128,14 +137,14 @@ template <typename T>
128137
FCL_CollisionObject MarkerShape<T>::getCollisionObject() const
129138
{
130139
// FIXME
131-
// fcl::Transform3f x(fcl::Quaternionf(this->marker_.pose.orientation.w,
140+
// fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
132141
// this->marker_.pose.orientation.x,
133142
// this->marker_.pose.orientation.y,
134143
// this->marker_.pose.orientation.z),
135-
// fcl::Vector3f(this->marker_.pose.position.x,
144+
// FCL_Vec3(this->marker_.pose.position.x,
136145
// this->marker_.pose.position.y,
137146
// this->marker_.pose.position.z));
138-
fcl::Transform3f x(fcl::Quaternionf(this->marker_.pose.orientation.w,
147+
fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
139148
this->marker_.pose.orientation.x,
140149
this->marker_.pose.orientation.y,
141150
this->marker_.pose.orientation.z));

cob_obstacle_distance/src/marker_shapes/marker_shapes_impl.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -166,14 +166,14 @@ inline visualization_msgs::Marker MarkerShape<BVH_RSS_t>::getMarker()
166166
FCL_CollisionObject MarkerShape<BVH_RSS_t>::getCollisionObject() const
167167
{
168168
// FIXME
169-
// fcl::Transform3f x(fcl::Quaternionf(this->marker_.pose.orientation.w,
169+
// fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
170170
// this->marker_.pose.orientation.x,
171171
// this->marker_.pose.orientation.y,
172172
// this->marker_.pose.orientation.z),
173-
// fcl::Vector3f(this->marker_.pose.position.x,
173+
// FCL_Vec3(this->marker_.pose.position.x,
174174
// this->marker_.pose.position.y,
175175
// this->marker_.pose.position.z));
176-
fcl::Transform3f x(fcl::Quaternionf(this->marker_.pose.orientation.w,
176+
fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
177177
this->marker_.pose.orientation.x,
178178
this->marker_.pose.orientation.y,
179179
this->marker_.pose.orientation.z));

0 commit comments

Comments
 (0)