$search
00001 00009 /***************************************************************************** 00010 ** Includes 00011 *****************************************************************************/ 00012 00013 #include <ros/ros.h> 00014 #include <string> 00015 #include <sstream> 00016 #include "listener.hpp" 00017 #include <std_msgs/String.h> 00018 00019 /***************************************************************************** 00020 ** Implementation 00021 *****************************************************************************/ 00022 00023 Listener::Listener(int argc, char** argv ) : 00024 QNode(argc,argv,"qlistener") 00025 {} 00026 00027 void Listener::ros_comms_init() { 00028 ros::NodeHandle n; 00029 chatter_subscriber = n.subscribe("chatter", 1000, &Listener::chatterCallback, this); 00030 } 00031 00032 void Listener::chatterCallback(const std_msgs::String::ConstPtr &msg) { 00033 ROS_INFO("I heard: [%s]", msg->data.c_str()); 00034 logging.insertRows(0,1); 00035 std::stringstream logging_msg; 00036 logging_msg << "[ INFO] [" << ros::Time::now() << "]: I heard: " << msg->data; 00037 QVariant new_row(QString(logging_msg.str().c_str())); 00038 logging.setData(logging.index(0),new_row); 00039 } 00040 00041 void Listener::run() { 00042 ros::spin(); 00043 std::cout << "Ros shutdown, proceeding to close the gui." << std::endl; 00044 Q_EMIT rosShutdown(); // used to signal the gui for a shutdown (useful to roslaunch) 00045 }