From 7fadfabaa7e2ca1d10821203f6cc66e14d846de8 Mon Sep 17 00:00:00 2001
From: roangel <roangel@student.ethz.ch>
Date: Tue, 22 Aug 2017 11:59:17 +0200
Subject: [PATCH] Now we publish in name of PPSClient from GUI :)

---
 .../src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp   | 8 ++++++--
 pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py            | 1 -
 2 files changed, 6 insertions(+), 3 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
index f045fb52..63c3f271 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
@@ -1,5 +1,6 @@
 #include "MainWindow.h"
 #include "ui_MainWindow.h"
+#include <string>
 
 #include <ros/ros.h>
 #include <ros/network.h>
@@ -15,9 +16,12 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     qRegisterMetaType<ptrToMessage>("ptrToMessage");
     QObject::connect(m_rosNodeThread, SIGNAL(newViconData(const ptrToMessage&)), this, SLOT(updateNewViconData(const ptrToMessage&)));
 
-    ros::NodeHandle nh("~");
+    std::string ros_namespace = ros::this_node::getNamespace();
+    ROS_INFO("namespace: %s", ros_namespace.c_str());
 
-    crazyRadioCommandPublisher = nh.advertise<std_msgs::Int32>("crazyRadioCommand", 1);
+    ros::NodeHandle nh_PPSClient(ros_namespace + "/PPSClient");
+
+    crazyRadioCommandPublisher = nh_PPSClient.advertise<std_msgs::Int32>("crazyRadioCommand", 1);
 }
 
 MainWindow::~MainWindow()
diff --git a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
index 75b5191e..54986be4 100755
--- a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
+++ b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
@@ -211,7 +211,6 @@ if __name__ == '__main__':
     global cf_client
 
     cf_client = PPSRadioClient(radio_address)
-    rospy.Subscriber("student_GUI/crazyRadioCommand", Int32, cf_client.crazyRadioCommandCallback) # allows commands from student_GUI
     rospy.Subscriber("PPSClient/crazyRadioCommand", Int32, cf_client.crazyRadioCommandCallback) # allows commands from scripts
 
     time.sleep(1.0)
-- 
GitLab