Skip to content

Commit

Permalink
Optimize MOVE_SHAPE operations for FCL (#3601)
Browse files Browse the repository at this point in the history
Don't recreate the FCL object when moving shapes, but just update its transforms.
  • Loading branch information
captain-yoshi authored and sjahr committed Jul 31, 2024
1 parent d849244 commit 53ffed2
Show file tree
Hide file tree
Showing 3 changed files with 53 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -155,11 +155,24 @@ TYPED_TEST_P(CollisionDetectorPandaTest, RobotWorldCollision_1)
ASSERT_TRUE(res.collision);
res.clear();

pos1.translation().z() = 0.25;
this->cenv_->getWorld()->moveObject("box", pos1);
this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
ASSERT_FALSE(res.collision);
res.clear();

pos1.translation().z() = 0.05;
this->cenv_->getWorld()->moveObject("box", pos1);
this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
ASSERT_TRUE(res.collision);
res.clear();

pos1.translation().z() = 0.25;
this->cenv_->getWorld()->moveObject("box", pos1);
this->cenv_->checkRobotCollision(req, res, *this->robot_state_, *this->acm_);
ASSERT_FALSE(res.collision);
res.clear();

this->cenv_->getWorld()->moveObject("box", pos1);
ASSERT_FALSE(res.collision);
}
Expand Down
32 changes: 32 additions & 0 deletions moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -450,6 +450,38 @@ void CollisionEnvFCL::notifyObjectChange(const ObjectConstPtr& obj, World::Actio
}
cleanCollisionGeometryCache();
}
else if (action == World::MOVE_SHAPE)
{
auto it = fcl_objs_.find(obj->id_);
if (it == fcl_objs_.end())
{
RCLCPP_ERROR(getLogger(), "Cannot move shapes of unknown FCL object: '%s'", obj->id_.c_str());
return;
}

if (obj->global_shape_poses_.size() != it->second.collision_objects_.size())
{
RCLCPP_ERROR(getLogger(),
"Cannot move shapes, shape size mismatch between FCL object and world object: '%s'. Respectively "
"%zu and %zu.",
obj->id_.c_str(), it->second.collision_objects_.size(), it->second.collision_objects_.size());
return;
}

for (std::size_t i = 0; i < it->second.collision_objects_.size(); ++i)
{
it->second.collision_objects_[i]->setTransform(transform2fcl(obj->global_shape_poses_[i]));

// compute AABB, order matters
it->second.collision_geometry_[i]->collision_geometry_->computeLocalAABB();
it->second.collision_objects_[i]->computeAABB();
}

// update AABB in the FCL broadphase manager tree
// see https://github.com/moveit/moveit/pull/3601 for benchmarks
it->second.unregisterFrom(manager_.get());
it->second.registerTo(manager_.get());
}
else
{
updateFCLObject(obj->id_);
Expand Down
14 changes: 8 additions & 6 deletions moveit_core/planning_scene/src/planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1880,8 +1880,9 @@ bool PlanningScene::processCollisionObjectMove(const moveit_msgs::msg::Collision
std::size_t shape_size = object.primitive_poses.size() + object.mesh_poses.size() + object.plane_poses.size();
if (shape_size != world_object->shape_poses_.size())
{
ROS_ERROR_NAMED(LOGNAME, "Move operation for object '%s' must have same number of geometry poses. Cannot move.",
object.id.c_str());
RCLCPP_ERROR(getLogger(),
"Move operation for object '%s' must have same number of geometry poses. Cannot move.",
object.id.c_str());
return false;
}

Expand All @@ -1890,22 +1891,23 @@ bool PlanningScene::processCollisionObjectMove(const moveit_msgs::msg::Collision
for (const auto& shape_pose : object.primitive_poses)
{
shape_poses.emplace_back();
PlanningScene::poseMsgToEigen(shape_pose, shape_poses.back());
utilities::poseMsgToEigen(shape_pose, shape_poses.back());
}
for (const auto& shape_pose : object.mesh_poses)
{
shape_poses.emplace_back();
PlanningScene::poseMsgToEigen(shape_pose, shape_poses.back());
utilities::poseMsgToEigen(shape_pose, shape_poses.back());
}
for (const auto& shape_pose : object.plane_poses)
{
shape_poses.emplace_back();
PlanningScene::poseMsgToEigen(shape_pose, shape_poses.back());
utilities::poseMsgToEigen(shape_pose, shape_poses.back());
}

if (!world_->moveShapesInObject(object.id, shape_poses))
{
ROS_ERROR_NAMED(LOGNAME, "Move operation for object '%s' internal world error. Cannot move.", object.id.c_str());
RCLCPP_ERROR(getLogger(), "Move operation for object '%s' internal world error. Cannot move.",
object.id.c_str());
return false;
}
}
Expand Down

0 comments on commit 53ffed2

Please sign in to comment.