From f2f6e0088d76b2a006847f5525bbe61092d51d8c Mon Sep 17 00:00:00 2001
From: Johannes Mey <johannes.mey@tu-dresden.de>
Date: Thu, 19 May 2022 10:34:48 +0200
Subject: [PATCH] avoid double-sending scene

---
 src/moveit_sorting_controller.cpp | 4 ----
 1 file changed, 4 deletions(-)

diff --git a/src/moveit_sorting_controller.cpp b/src/moveit_sorting_controller.cpp
index 59965a0..6f86b32 100644
--- a/src/moveit_sorting_controller.cpp
+++ b/src/moveit_sorting_controller.cpp
@@ -60,10 +60,6 @@ int main(int argc, char **argv)
   controller.loadScene(getPrivateParameter<std::string>("scene", ros::package::getPath("ccf_immersive_sorting") +
       "/config/config_scene_ceti-table-placeworld.json"));
 
-  // TODO check if this is required (since loadScene already sends the scene)
-  ROS_INFO_STREAM("Sending initial scene after loading it.");
-  controller.sendScene();
-
   std::optional<std::string> currentlyPickedBox{};
 
   ros::Subscriber sub = n.subscribe<std_msgs::Empty>("send_scene", 1000, [&controller](
-- 
GitLab