Skip to content

Commit

Permalink
Only check end effector collisions for target pose in ComputeIK
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser committed Jan 5, 2020
1 parent 233d63a commit 35a7aa3
Showing 1 changed file with 13 additions and 1 deletion.
14 changes: 13 additions & 1 deletion core/src/stages/compute_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ bool isTargetPoseColliding(const planning_scene::PlanningScenePtr& scene, Eigen:

// consider all rigidly connected parent links as well
const robot_model::LinkModel* parent = robot_model::RobotModel::getRigidlyConnectedParentLinkModel(link);
const auto& considered_target_links = parent->getParentJointModel()->getDescendantLinkModels();
if (parent != link) // transform pose into pose suitable to place parent
pose = pose * robot_state.getGlobalLinkTransform(link).inverse() * robot_state.getGlobalLinkTransform(parent);

Expand Down Expand Up @@ -125,7 +126,18 @@ bool isTargetPoseColliding(const planning_scene::PlanningScenePtr& scene, Eigen:
req.contacts = (collision_result != nullptr);
collision_detection::CollisionResult& res = collision_result ? *collision_result : result;
scene->checkCollision(req, res, robot_state, acm);
return res.collision;

// Only check collisions with target links
if (res.collision) {
for (const auto& contact : res.contacts) {
const auto& colliding_links = contact.first;
for (const auto& link : considered_target_links) {
if (colliding_links.first == link->getName() || colliding_links.second == link->getName())
return true;
}
}
}
return false;
}

std::string listCollisionPairs(const collision_detection::CollisionResult::ContactMap& contacts,
Expand Down

0 comments on commit 35a7aa3

Please sign in to comment.