Skip to content

Commit

Permalink
Revert "comment broken bits"
Browse files Browse the repository at this point in the history
This reverts commit b852fc2.
  • Loading branch information
fmessmer committed Mar 20, 2024
1 parent 8b0a4eb commit 322bed5
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -126,18 +126,13 @@ inline visualization_msgs::Marker MarkerShape<T>::getMarker()
template <typename T>
FCL_CollisionObject MarkerShape<T>::getCollisionObject() const
{
// FIXME
// fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
// this->marker_.pose.orientation.x,
// this->marker_.pose.orientation.y,
// this->marker_.pose.orientation.z),
// FCL_Vec3(this->marker_.pose.position.x,
// this->marker_.pose.position.y,
// this->marker_.pose.position.z));
fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
this->marker_.pose.orientation.x,
this->marker_.pose.orientation.y,
this->marker_.pose.orientation.z));
this->marker_.pose.orientation.z),
FCL_Vec3(this->marker_.pose.position.x,
this->marker_.pose.position.y,
this->marker_.pose.position.z));

FCL_CollisionObject cobj(this->ptr_fcl_bvh_, x);
return cobj;
Expand Down
4 changes: 1 addition & 3 deletions cob_obstacle_distance/src/distance_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,9 +273,7 @@ void DistanceManager::calculate()
FCL_CollisionObject collision_obj = obstacle->getCollisionObject();
FCL_DistanceResult dist_result;
FCL_DistanceRequest dist_request(true, 5.0, 0.01);
//FIXME
// double dist = fcl::distance(&ooi_co, &collision_obj, dist_request, dist_result);
double dist = 0;
fcl::FCL_REAL dist = fcl::distance(&ooi_co, &collision_obj, dist_request, dist_result);


Eigen::Vector3d abs_obst_vector(dist_result.nearest_points[1][VEC_X],
Expand Down
13 changes: 4 additions & 9 deletions cob_obstacle_distance/src/marker_shapes/marker_shapes_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,18 +165,13 @@ inline visualization_msgs::Marker MarkerShape<BVH_RSS_t>::getMarker()

FCL_CollisionObject MarkerShape<BVH_RSS_t>::getCollisionObject() const
{
// FIXME
// fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
// this->marker_.pose.orientation.x,
// this->marker_.pose.orientation.y,
// this->marker_.pose.orientation.z),
// FCL_Vec3(this->marker_.pose.position.x,
// this->marker_.pose.position.y,
// this->marker_.pose.position.z));
fcl::Transform3f x(FCL_Quaternion(this->marker_.pose.orientation.w,
this->marker_.pose.orientation.x,
this->marker_.pose.orientation.y,
this->marker_.pose.orientation.z));
this->marker_.pose.orientation.z),
FCL_Vec3(this->marker_.pose.position.x,
this->marker_.pose.position.y,
this->marker_.pose.position.z));
FCL_CollisionObject cobj(this->ptr_fcl_bvh_, x);
return cobj;
}
Expand Down

0 comments on commit 322bed5

Please sign in to comment.