Skip to content

Commit

Permalink
Remove ACM entries when removing collision objects (#3183)
Browse files Browse the repository at this point in the history
* Fix ACM for CollisionObjects when they are completely removed

* Update test to check for collision

* Address review
  • Loading branch information
JafarAbdi authored Dec 31, 2024
1 parent e2d9dc5 commit c3a2edc
Show file tree
Hide file tree
Showing 2 changed files with 58 additions and 0 deletions.
3 changes: 3 additions & 0 deletions moveit_core/planning_scene/src/planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -374,6 +374,7 @@ void PlanningScene::pushDiffs(const PlanningScenePtr& scene)
scene->world_->removeObject(it.first);
scene->removeObjectColor(it.first);
scene->removeObjectType(it.first);
scene->getAllowedCollisionMatrixNonConst().removeEntry(it.first);
}
else
{
Expand Down Expand Up @@ -1465,6 +1466,7 @@ void PlanningScene::removeAllCollisionObjects()
world_->removeObject(object_id);
removeObjectColor(object_id);
removeObjectType(object_id);
getAllowedCollisionMatrixNonConst().removeEntry(object_id);
}
}
}
Expand Down Expand Up @@ -1939,6 +1941,7 @@ bool PlanningScene::processCollisionObjectRemove(const moveit_msgs::msg::Collisi

removeObjectColor(object.id);
removeObjectType(object.id);
getAllowedCollisionMatrixNonConst().removeEntry(object.id);
}
return true;
}
Expand Down
55 changes: 55 additions & 0 deletions moveit_core/planning_scene/test/test_planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -590,6 +590,61 @@ TEST(PlanningScene, RobotStateDiffBug)
}
}

TEST(PlanningScene, UpdateACMAfterObjectRemoval)
{
auto robot_model = moveit::core::loadTestingRobotModel("panda");
auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model);

const auto object_name = "object";
collision_detection::CollisionRequest collision_request;
collision_request.group_name = "hand";
collision_request.verbose = true;

// Helper function to add an object to the planning scene
auto add_object = [&] {
const auto ps1 = createPlanningSceneDiff(*ps, object_name, moveit_msgs::msg::CollisionObject::ADD);
ps->usePlanningSceneMsg(ps1);
EXPECT_EQ(getCollisionObjectsNames(*ps), (std::set<std::string>{ object_name }));
};

// Modify the allowed collision matrix and make sure it is updated
auto modify_acm = [&] {
collision_detection::AllowedCollisionMatrix& acm = ps->getAllowedCollisionMatrixNonConst();
acm.setEntry(object_name, ps->getRobotModel()->getJointModelGroup("hand")->getLinkModelNamesWithCollisionGeometry(),
true);
EXPECT_TRUE(ps->getAllowedCollisionMatrix().hasEntry(object_name));
};

// Check collision
auto check_collision = [&] {
collision_detection::CollisionResult res;
ps->checkCollision(collision_request, res);
return res.collision;
};

// Test removing a collision object using a diff
add_object();
EXPECT_TRUE(check_collision());
modify_acm();
EXPECT_FALSE(check_collision());
{
const auto ps1 = createPlanningSceneDiff(*ps, object_name, moveit_msgs::msg::CollisionObject::REMOVE);
ps->usePlanningSceneMsg(ps1);
EXPECT_EQ(getCollisionObjectsNames(*ps), (std::set<std::string>{}));
EXPECT_FALSE(ps->getAllowedCollisionMatrix().hasEntry(object_name));
}

// Test removing all objects
add_object();
// This should report a collision since it's a completely new object
EXPECT_TRUE(check_collision());
modify_acm();
EXPECT_FALSE(check_collision());
ps->removeAllCollisionObjects();
EXPECT_EQ(getCollisionObjectsNames(*ps), (std::set<std::string>{}));
EXPECT_FALSE(ps->getAllowedCollisionMatrix().hasEntry(object_name));
}

#ifndef INSTANTIATE_TEST_SUITE_P // prior to gtest 1.10
#define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
#endif
Expand Down

0 comments on commit c3a2edc

Please sign in to comment.