Skip to content
Snippets Groups Projects
Commit 7fadfaba authored by roangel's avatar roangel
Browse files

Now we publish in name of PPSClient from GUI :)

parent a3a1cc20
No related branches found
No related tags found
No related merge requests found
#include "MainWindow.h" #include "MainWindow.h"
#include "ui_MainWindow.h" #include "ui_MainWindow.h"
#include <string>
#include <ros/ros.h> #include <ros/ros.h>
#include <ros/network.h> #include <ros/network.h>
...@@ -15,9 +16,12 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) : ...@@ -15,9 +16,12 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
qRegisterMetaType<ptrToMessage>("ptrToMessage"); qRegisterMetaType<ptrToMessage>("ptrToMessage");
QObject::connect(m_rosNodeThread, SIGNAL(newViconData(const ptrToMessage&)), this, SLOT(updateNewViconData(const 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() MainWindow::~MainWindow()
......
...@@ -211,7 +211,6 @@ if __name__ == '__main__': ...@@ -211,7 +211,6 @@ if __name__ == '__main__':
global cf_client global cf_client
cf_client = PPSRadioClient(radio_address) 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 rospy.Subscriber("PPSClient/crazyRadioCommand", Int32, cf_client.crazyRadioCommandCallback) # allows commands from scripts
time.sleep(1.0) time.sleep(1.0)
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment