qadd_client/qadd.cpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10 ** Includes
11 *****************************************************************************/
12 
13 #include <ros/ros.h>
14 #include <string>
15 #include <sstream>
16 #include "qadd.hpp"
17 #include <std_msgs/String.h>
18 
19 /*****************************************************************************
20 ** Implementation
21 *****************************************************************************/
22 
23 QAdd::QAdd(int argc, char** argv ) :
24  QNode(argc,argv,"qadd_client")
25  {}
26 
29  add_client = n.serviceClient<qt_tutorials::TwoInts>("add_two_ints");
30 }
31 
32 void QAdd::run() {
33  ros::Rate loop_rate(1);
34  int last_sum = 0;
35  int count = 1;
36  while( ros::ok() ) {
37  qt_tutorials::TwoInts srv;
38  srv.request.a = count;
39  srv.request.b = last_sum;
40  std::stringstream logging_msg;
41  if ( add_client.call(srv) ) {
42  ROS_INFO_STREAM("Sum: " << srv.response.sum);
43  last_sum = srv.response.sum;
44  logging_msg << "[ INFO] [" << ros::Time::now() << "]: " << srv.request.a << " + " << srv.request.b << " = " << srv.response.sum;
45  ++count;
46  } else {
47  ROS_INFO_STREAM("failed to contact the server");
48  logging_msg << "[ INFO] [" << ros::Time::now() << "]: failed to contact the server";
49  }
50  logging.insertRows(0,1);
51  QVariant new_row(QString(logging_msg.str().c_str()));
52  logging.setData(logging.index(0),new_row);
53  ros::spinOnce();
54  loop_rate.sleep();
55  }
56  std::cout << "Ros shutdown, proceeding to close the gui." << std::endl;
57  Q_EMIT rosShutdown(); // used to signal the gui for a shutdown (useful to roslaunch)
58 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void ros_comms_init()
QStringListModel logging
Definition: qnode.hpp:54
bool call(MReq &req, MRes &res)
void rosShutdown()
ROSCPP_DECL bool ok()
bool sleep()
Definition: qnode.hpp:31
#define ROS_INFO_STREAM(args)
QAdd(int argc, char **argv)
ros::ServiceClient add_client
static Time now()
ROSCPP_DECL void spinOnce()
void run()


qt_tutorials
Author(s): Daniel Stonier
autogenerated on Wed Mar 11 2020 03:12:20