Skip to content

Commit d174ecf

Browse files
committed
comment broken bits
1 parent 3ec6302 commit d174ecf

File tree

3 files changed

+27
-16
lines changed

3 files changed

+27
-16
lines changed

cob_obstacle_distance/include/cob_obstacle_distance/marker_shapes/marker_shapes_impl.hpp

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -127,14 +127,18 @@ inline visualization_msgs::Marker MarkerShape<T>::getMarker()
127127
template <typename T>
128128
FCL_CollisionObject MarkerShape<T>::getCollisionObject() const
129129
{
130-
fcl::Transform3f x(fcl::Quaternion3f(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::Vec3f(this->marker_.pose.position.x,
135-
this->marker_.pose.position.y,
136-
this->marker_.pose.position.z));
137-
fcl::CollisionObject cobj(this->ptr_fcl_bvh_, x);
130+
// FIXME
131+
// fcl::Transform3f x(fcl::Quaternionf(this->marker_.pose.orientation.w,
132+
// this->marker_.pose.orientation.x,
133+
// this->marker_.pose.orientation.y,
134+
// this->marker_.pose.orientation.z),
135+
// fcl::Vector3f(this->marker_.pose.position.x,
136+
// this->marker_.pose.position.y,
137+
// this->marker_.pose.position.z));
138+
fcl::Transform3f x(fcl::Quaternionf(this->marker_.pose.orientation.w,
139+
this->marker_.pose.orientation.x,
140+
this->marker_.pose.orientation.y,
141+
this->marker_.pose.orientation.z));
138142

139143
FCL_CollisionObject cobj(this->ptr_fcl_bvh_, x);
140144
return cobj;

cob_obstacle_distance/src/distance_manager.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -276,7 +276,9 @@ void DistanceManager::calculate()
276276
FCL_CollisionObject collision_obj = obstacle->getCollisionObject();
277277
FCL_DistanceResult dist_result;
278278
FCL_DistanceRequest dist_request(true, 5.0, 0.01);
279-
fcl::FCL_REAL dist = fcl::distance(&ooi_co, &collision_obj, dist_request, dist_result);
279+
//FIXME
280+
// double dist = fcl::distance(&ooi_co, &collision_obj, dist_request, dist_result);
281+
double dist = 0;
280282

281283

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

cob_obstacle_distance/src/marker_shapes/marker_shapes_impl.cpp

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

166166
FCL_CollisionObject MarkerShape<BVH_RSS_t>::getCollisionObject() const
167167
{
168-
fcl::Transform3f x(fcl::Quaternion3f(this->marker_.pose.orientation.w,
169-
this->marker_.pose.orientation.x,
170-
this->marker_.pose.orientation.y,
171-
this->marker_.pose.orientation.z),
172-
fcl::Vec3f(this->marker_.pose.position.x,
173-
this->marker_.pose.position.y,
174-
this->marker_.pose.position.z));
168+
// FIXME
169+
// fcl::Transform3f x(fcl::Quaternionf(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::Vector3f(this->marker_.pose.position.x,
174+
// this->marker_.pose.position.y,
175+
// this->marker_.pose.position.z));
176+
fcl::Transform3f x(fcl::Quaternionf(this->marker_.pose.orientation.w,
177+
this->marker_.pose.orientation.x,
178+
this->marker_.pose.orientation.y,
179+
this->marker_.pose.orientation.z));
175180
FCL_CollisionObject cobj(this->ptr_fcl_bvh_, x);
176181
return cobj;
177182
}

0 commit comments

Comments
 (0)