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 17, 2020
1 parent 4fa7066 commit 66b4381
Showing 1 changed file with 13 additions and 2 deletions.
15 changes: 13 additions & 2 deletions core/src/stages/compute_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,15 +96,16 @@ 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& 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);

// place link at given pose
robot_state.updateStateWithLinkAt(parent, pose);
robot_state.updateCollisionBodyTransforms();

// disable collision checking for parent links (except links fixed to root)
auto& acm = scene->getAllowedCollisionMatrixNonConst();
// disable collision checking for parent links in the kinematic chain (except links fixed to root)
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 +120,16 @@ bool isTargetPoseColliding(const planning_scene::PlanningScenePtr& scene, Eigen:
}
}

// disable collision checking between collision objects and links not part of the rigid target group
const auto& world_object_ids = scene->getWorld()->getObjectIds();
for (const auto& robot_link : scene->getRobotModel()->getLinkModelsWithCollisionGeometry()) {
if (std::find(target_links.begin(), target_links.end(), robot_link) == target_links.end()) {
for (const auto& object_id : world_object_ids) {
acm.setEntry(object_id, robot_link->getName(), true);
}
}
}

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

0 comments on commit 66b4381

Please sign in to comment.