Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fixup fcl noetic compatibility #256

Open
wants to merge 1 commit into
base: noetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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