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 Jun 16, 2020
1 parent b3b215a commit 366b7fa
Showing 1 changed file with 10 additions and 1 deletion.
11 changes: 10 additions & 1 deletion core/src/stages/compute_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ bool isTargetPoseColliding(const planning_scene::PlanningScenePtr& scene, Eigen:
robot_state.updateCollisionBodyTransforms();

// disable collision checking for parent links (except links fixed to root)
auto& acm = scene->getAllowedCollisionMatrixNonConst();
collision_detection::AllowedCollisionMatrix acm(scene->getAllowedCollisionMatrix());
std::vector<const std::string*> pending_links; // parent link names that might be rigidly connected to root
while (parent) {
pending_links.push_back(&parent->getName());
Expand All @@ -119,6 +119,15 @@ bool isTargetPoseColliding(const planning_scene::PlanningScenePtr& scene, Eigen:
}
}

// Remaining pending_links are fixed to root, disable padded scene collisions for this check
if (!pending_links.empty()) {
for (const std::string& object_id : scene->getWorld()->getObjectIds()) {
for (const std::string* name : pending_links) {
acm.setEntry(object_id, *name, true);
}
}
}

// check collision with the world using the padded version
collision_detection::CollisionRequest req;
collision_detection::CollisionResult result;
Expand Down

0 comments on commit 366b7fa

Please sign in to comment.