Skip to content

Commit 64c626f

Browse files
captain-yoshirhaschke
authored andcommitted
Optimize MOVE_SHAPE operations for FCL (#3601)
Don't recreate the FCL object when moving shapes, but just update its transforms.
1 parent 2b8a067 commit 64c626f

File tree

2 files changed

+45
-0
lines changed

2 files changed

+45
-0
lines changed

moveit_core/collision_detection/include/moveit/collision_detection/test_collision_common_panda.h

+13
Original file line numberDiff line numberDiff line change
@@ -155,11 +155,24 @@ TYPED_TEST_P(CollisionDetectorPandaTest, RobotWorldCollision_1)
155155
ASSERT_TRUE(res.collision);
156156
res.clear();
157157

158+
pos1.translation().z() = 0.25;
159+
this->cenv_->getWorld()->moveObject("box", pos1);
160+
this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
161+
ASSERT_FALSE(res.collision);
162+
res.clear();
163+
164+
pos1.translation().z() = 0.05;
158165
this->cenv_->getWorld()->moveObject("box", pos1);
159166
this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
160167
ASSERT_TRUE(res.collision);
161168
res.clear();
162169

170+
pos1.translation().z() = 0.25;
171+
this->cenv_->getWorld()->moveObject("box", pos1);
172+
this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
173+
ASSERT_FALSE(res.collision);
174+
res.clear();
175+
163176
this->cenv_->getWorld()->moveObject("box", pos1);
164177
ASSERT_FALSE(res.collision);
165178
}

moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp

+32
Original file line numberDiff line numberDiff line change
@@ -450,6 +450,38 @@ void CollisionEnvFCL::notifyObjectChange(const ObjectConstPtr& obj, World::Actio
450450
}
451451
cleanCollisionGeometryCache();
452452
}
453+
else if (action == World::MOVE_SHAPE)
454+
{
455+
auto it = fcl_objs_.find(obj->id_);
456+
if (it == fcl_objs_.end())
457+
{
458+
ROS_ERROR_NAMED(LOGNAME, "Cannot move shapes of unknown FCL object: '%s'", obj->id_.c_str());
459+
return;
460+
}
461+
462+
if (obj->global_shape_poses_.size() != it->second.collision_objects_.size())
463+
{
464+
ROS_ERROR_NAMED(LOGNAME,
465+
"Cannot move shapes, shape size mismatch between FCL object and world object: '%s'. Respectively "
466+
"%zu and %zu.",
467+
obj->id_.c_str(), it->second.collision_objects_.size(), it->second.collision_objects_.size());
468+
return;
469+
}
470+
471+
for (std::size_t i = 0; i < it->second.collision_objects_.size(); ++i)
472+
{
473+
it->second.collision_objects_[i]->setTransform(transform2fcl(obj->global_shape_poses_[i]));
474+
475+
// compute AABB, order matters
476+
it->second.collision_geometry_[i]->collision_geometry_->computeLocalAABB();
477+
it->second.collision_objects_[i]->computeAABB();
478+
}
479+
480+
// update AABB in the FCL broadphase manager tree
481+
// see https://github.com/moveit/moveit/pull/3601 for benchmarks
482+
it->second.unregisterFrom(manager_.get());
483+
it->second.registerTo(manager_.get());
484+
}
453485
else
454486
{
455487
updateFCLObject(obj->id_);

0 commit comments

Comments
 (0)