qadd_server/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_server")
25  {}
26 
27 void QAdd::ros_comms_init() {
29  add_server = n.advertiseService("add_two_ints", &QAdd::add, this);
30 }
31 
32 bool QAdd::add(qt_tutorials::TwoInts::Request &req, qt_tutorials::TwoInts::Response &res) {
33  res.sum = req.a + req.b;
34  ROS_INFO_STREAM(req.a << " + " << req.b << " = " << res.sum);
35 
36  logging.insertRows(0,1);
37  std::stringstream logging_msg;
38  logging_msg << "[ INFO] [" << ros::Time::now() << "]: " << req.a << " + " << req.b << " = " << res.sum;
39  QVariant new_row(QString(logging_msg.str().c_str()));
40  logging.setData(logging.index(0),new_row);
41 
42  return true;
43 }
44 
45 void QAdd::run() {
46  ros::spin();
47  std::cout << "Ros shutdown, proceeding to close the gui." << std::endl;
48  Q_EMIT rosShutdown(); // used to signal the gui for a shutdown (useful to roslaunch)
49 }
bool add(qt_tutorials::TwoInts::Request &req, qt_tutorials::TwoInts::Response &res)
void ros_comms_init()
QStringListModel logging
Definition: qnode.hpp:54
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void rosShutdown()
ros::ServiceServer add_server
ROSCPP_DECL void spin()
Definition: qnode.hpp:31
#define ROS_INFO_STREAM(args)
QAdd(int argc, char **argv)
static Time now()
Ros communication central!
void run()


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