Skip to content

Commit 95c933e

Browse files
committed
Revert "comment broken bits"
This reverts commit b852fc2.
1 parent 0f8c45c commit 95c933e

File tree

3 files changed

+9
-21
lines changed

3 files changed

+9
-21
lines changed

cob_obstacle_distance/include/cob_obstacle_distance/marker_shapes/marker_shapes_impl.hpp

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -126,18 +126,13 @@ inline visualization_msgs::Marker MarkerShape<T>::getMarker()
126126
template <typename T>
127127
FCL_CollisionObject MarkerShape<T>::getCollisionObject() const
128128
{
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));
137129
fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
138130
this->marker_.pose.orientation.x,
139131
this->marker_.pose.orientation.y,
140-
this->marker_.pose.orientation.z));
132+
this->marker_.pose.orientation.z),
133+
FCL_Vec3(this->marker_.pose.position.x,
134+
this->marker_.pose.position.y,
135+
this->marker_.pose.position.z));
141136

142137
FCL_CollisionObject cobj(this->ptr_fcl_bvh_, x);
143138
return cobj;

cob_obstacle_distance/src/distance_manager.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -273,9 +273,7 @@ void DistanceManager::calculate()
273273
FCL_CollisionObject collision_obj = obstacle->getCollisionObject();
274274
FCL_DistanceResult dist_result;
275275
FCL_DistanceRequest dist_request(true, 5.0, 0.01);
276-
//FIXME
277-
// double dist = fcl::distance(&ooi_co, &collision_obj, dist_request, dist_result);
278-
double dist = 0;
276+
fcl::FCL_REAL dist = fcl::distance(&ooi_co, &collision_obj, dist_request, dist_result);
279277

280278

281279
Eigen::Vector3d abs_obst_vector(dist_result.nearest_points[1][VEC_X],

cob_obstacle_distance/src/marker_shapes/marker_shapes_impl.cpp

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -165,18 +165,13 @@ inline visualization_msgs::Marker MarkerShape<BVH_RSS_t>::getMarker()
165165

166166
FCL_CollisionObject MarkerShape<BVH_RSS_t>::getCollisionObject() const
167167
{
168-
// FIXME
169-
// fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
170-
// this->marker_.pose.orientation.x,
171-
// this->marker_.pose.orientation.y,
172-
// this->marker_.pose.orientation.z),
173-
// FCL_Vec3(this->marker_.pose.position.x,
174-
// this->marker_.pose.position.y,
175-
// this->marker_.pose.position.z));
176168
fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
177169
this->marker_.pose.orientation.x,
178170
this->marker_.pose.orientation.y,
179-
this->marker_.pose.orientation.z));
171+
this->marker_.pose.orientation.z),
172+
FCL_Vec3(this->marker_.pose.position.x,
173+
this->marker_.pose.position.y,
174+
this->marker_.pose.position.z));
180175
FCL_CollisionObject cobj(this->ptr_fcl_bvh_, x);
181176
return cobj;
182177
}

0 commit comments

Comments
 (0)