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

Now tested the feedback from python nodes

parent 7af9dcb9
No related branches found
No related tags found
No related merge requests found
......@@ -13,19 +13,20 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
m_rosNodeThread = new rosNodeThread(argc, argv, "student_GUI");
ui->setupUi(this);
m_rosNodeThread->init();
std::string ros_namespace = ros::this_node::getNamespace();
ROS_INFO("namespace: %s", ros_namespace.c_str());
qRegisterMetaType<ptrToMessage>("ptrToMessage");
QObject::connect(m_rosNodeThread, SIGNAL(newViconData(const ptrToMessage&)), this, SLOT(updateNewViconData(const ptrToMessage&)));
ros::NodeHandle nodeHandle("~");
crazyRadioStatusSubscriber = nodeHandle.subscribe("/CrazyRadio/CrazyRadioStatus", 1, &MainWindow::crazyRadioStatusCallback, this);
std::string ros_namespace = ros::this_node::getNamespace();
ROS_INFO("namespace: %s", ros_namespace.c_str());
crazyRadioStatusSubscriber = nodeHandle.subscribe(ros_namespace + "/CrazyRadioStatus", 1, &MainWindow::crazyRadioStatusCallback, this);
// communication with PPS Client, just to make it possible to communicate through terminal also we use PPSClient's name
ros::NodeHandle nh_PPSClient(ros_namespace + "/PPSClient");
crazyRadioCommandPublisher = nh_PPSClient.advertise<std_msgs::Int32>("crazyRadioCommand", 1);
PPSClientCommadPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
PPSClientCommadPublisher = nh_PPSClient.advertise<std_msgs::Int32>("Command", 1);
disableGUI();
}
......@@ -54,6 +55,7 @@ void MainWindow::setCrazyRadioStatus(int radio_status)
case CONNECTED:
// change icon, the rest of the GUI is available now
ui->connected_disconnected_label->setText("Connected!");
enableGUI();
break;
case CONNECTING:
// change icon
......@@ -62,6 +64,7 @@ void MainWindow::setCrazyRadioStatus(int radio_status)
case DISCONNECTED:
// change icon, the rest of the GUI is disabled
ui->connected_disconnected_label->setText("Disconnected");
disableGUI();
break;
default:
ROS_ERROR_STREAM("unexpected radio status: " << m_radio_status);
......@@ -72,6 +75,7 @@ void MainWindow::setCrazyRadioStatus(int radio_status)
void MainWindow::crazyRadioStatusCallback(const std_msgs::Int32& msg)
{
ROS_INFO("Callback CrazyRadioStatus called");
this->setCrazyRadioStatus(msg.data);
}
......
......@@ -89,6 +89,7 @@ class PPSRadioClient:
self.connect()
def change_status_to(self, new_status):
print "status changed to: %s" % new_status
self._status = new_status
self.status_pub.publish(new_status)
......@@ -116,6 +117,7 @@ class PPSRadioClient:
#publish battery voltage for GUI
#cfbattery_pub.publish(std_msgs.Float32(batteryVolt.data))
print "batteryVolt: %s" % batteryVolt
cfbattery_pub.publish(batteryVolt)
......@@ -133,7 +135,7 @@ class PPSRadioClient:
# Config for Logging
logconf = LogConfig("LoggingTest", 100)
logconf = LogConfig("LoggingTest", 100) # second variable is freq in ms
logconf.add_variable("stabilizer.roll", "float");
logconf.add_variable("stabilizer.pitch", "float");
logconf.add_variable("stabilizer.yaw", "float");
......@@ -184,6 +186,8 @@ class PPSRadioClient:
if self.get_status() == DISCONNECTED:
print "entered disconnected"
self.connect()
if self.get_status() == CONNECTED:
self.status_pub.publish(CONNECTED)
def controlCommandCallback(data):
"""Callback for controller actions"""
......
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