From cc9dd5d118d25c61f1996152a9756180fd9dd87b Mon Sep 17 00:00:00 2001
From: Johannes Mey <johannes.mey@tu-dresden.de>
Date: Fri, 20 May 2022 10:31:23 +0200
Subject: [PATCH] alignment

---
 src/dummy_sorting_controller.cpp  | 10 +++-------
 src/moveit_sorting_controller.cpp |  6 +-----
 2 files changed, 4 insertions(+), 12 deletions(-)

diff --git a/src/dummy_sorting_controller.cpp b/src/dummy_sorting_controller.cpp
index 8adba80..af4f2ce 100644
--- a/src/dummy_sorting_controller.cpp
+++ b/src/dummy_sorting_controller.cpp
@@ -18,7 +18,7 @@
 #include "ccf/connection/MqttConnection.h"
 #include "ccf/util/NodeUtil.h"
 
-std::string NODE_NAME = "dummy_sorting_controller";
+std::string NODE_NAME = "ceti_cell_placeworld";
 
 using CetiRosToolbox::getParameter;
 using CetiRosToolbox::getPrivateParameter;
@@ -42,14 +42,14 @@ int main(int argc, char **argv)
   std::unique_ptr<MqttConnection>
       mqtt_connection = std::make_unique<MqttConnection>(mqttServer, ros::this_node::getName());
   mqtt_connection->listen(getParameter<std::string>(n, "topics/selection", "selection"));
-  auto commandTopic = getParameter(n, "topics/command", ros::this_node::getName() + "/command");
+  auto commandTopic = getParameter<std::string>(n, "topics/command", "/ceti_cell_placeworld/command");
   mqtt_connection->listen(commandTopic);
   auto other_cell_topic = getPrivateParameter<std::string>("other_cell", "/ceti_cell_2_placeworld/scene/update");
   mqtt_connection->listen(other_cell_topic);
   controller.addConnection(std::move(mqtt_connection));
 
   controller.addCallback(other_cell_topic, [&controller](auto msg) {
-    ROS_WARN_STREAM("Updating scene from other cell");
+    ROS_INFO_STREAM("Updating scene from other cell.");
     Scene scene;
     scene.ParseFromString(msg);
     controller.initScene(scene, false);
@@ -68,10 +68,6 @@ int main(int argc, char **argv)
       ROS_INFO_STREAM("Sending scene manually (triggered by a message to the 'send_scene' topic)");
       controller.sendScene();
   });
-  //ros::Timer timer = n.createTimer(ros::Duration(10), [&controller](
-  //    const ros::TimerEvent &event)
-  //{ controller.sendScene(); }); // send a scene every ten seconds
-
 
   auto pick_place_callback = [&controller](const Command& command)
   {
diff --git a/src/moveit_sorting_controller.cpp b/src/moveit_sorting_controller.cpp
index 6f86b32..8ba44c8 100644
--- a/src/moveit_sorting_controller.cpp
+++ b/src/moveit_sorting_controller.cpp
@@ -49,7 +49,7 @@ int main(int argc, char **argv)
   controller.addConnection(std::move(mqtt_connection));
 
   controller.addCallback(other_cell_topic, [&controller](auto msg) {
-    ROS_WARN_STREAM("Updating scene from other cell");
+    ROS_INFO_STREAM("Updating scene from other cell.");
     Scene scene;
     scene.ParseFromString(msg);
     controller.initScene(scene, false);
@@ -68,10 +68,6 @@ int main(int argc, char **argv)
       ROS_INFO_STREAM("Sending scene manually (triggered by a message to the 'send_scene' topic)");
       controller.sendScene();
   });
-  //ros::Timer timer = n.createTimer(ros::Duration(10), [&controller](
-  //    const ros::TimerEvent &event)
-  //{ controller.sendScene(); }); // send a scene every ten seconds
-
 
   auto pick_place_callback = [&controller](const Command& command)
   {
-- 
GitLab