$search
00001 00009 /***************************************************************************** 00010 ** Includes 00011 *****************************************************************************/ 00012 00013 #include <ros/ros.h> 00014 #include <string> 00015 #include <sstream> 00016 #include "qadd.hpp" 00017 #include <std_msgs/String.h> 00018 00019 /***************************************************************************** 00020 ** Implementation 00021 *****************************************************************************/ 00022 00023 QAdd::QAdd(int argc, char** argv ) : 00024 QNode(argc,argv,"qadd_client") 00025 {} 00026 00027 void QAdd::ros_comms_init() { 00028 ros::NodeHandle n; 00029 add_client = n.serviceClient<qt_tutorials::TwoInts>("add_two_ints"); 00030 } 00031 00032 void QAdd::run() { 00033 ros::Rate loop_rate(1); 00034 int last_sum = 0; 00035 int count = 1; 00036 while( ros::ok() ) { 00037 qt_tutorials::TwoInts srv; 00038 srv.request.a = count; 00039 srv.request.b = last_sum; 00040 std::stringstream logging_msg; 00041 if ( add_client.call(srv) ) { 00042 ROS_INFO_STREAM("Sum: " << srv.response.sum); 00043 last_sum = srv.response.sum; 00044 logging_msg << "[ INFO] [" << ros::Time::now() << "]: " << srv.request.a << " + " << srv.request.b << " = " << srv.response.sum; 00045 ++count; 00046 } else { 00047 ROS_INFO_STREAM("failed to contact the server"); 00048 logging_msg << "[ INFO] [" << ros::Time::now() << "]: failed to contact the server"; 00049 } 00050 logging.insertRows(0,1); 00051 QVariant new_row(QString(logging_msg.str().c_str())); 00052 logging.setData(logging.index(0),new_row); 00053 ros::spinOnce(); 00054 loop_rate.sleep(); 00055 } 00056 std::cout << "Ros shutdown, proceeding to close the gui." << std::endl; 00057 Q_EMIT rosShutdown(); // used to signal the gui for a shutdown (useful to roslaunch) 00058 }