simple_node.cpp
Go to the documentation of this file.
1 #include <atomic>
2 #include <ros/ros.h>
3 #include <ros/service.h>
4 #include <simple_node/GetMessage.h>
5 
6 std::atomic<unsigned> i;
7 
8 bool getMessageCallback(simple_node::GetMessage::Request &req,
9  simple_node::GetMessage::Response &res)
10 {
11  ROS_INFO_STREAM("getMessageCallback: " << req.value);
12 
13  if (i == 0)
14  {
15  res.return_status = true;
16  res.return_message = "Hello!\nThis service will fail next time you call it.";
17  }
18  else
19  {
20  res.return_status = false;
21  res.return_message = "Uh oh, failure!\nThis service will succeed next time you call it.";
22  }
23 
24  ++i;
25  if (i > 1)
26  i = 0;
27  return true;
28 }
29 
30 int main(int argc,
31  char **argv)
32 {
33  ros::init(argc, argv, "simple_node");
34  ros::NodeHandle nh;
35  i = 0;
36  ros::AsyncSpinner spinner(1);
37  spinner.start();
38  ros::ServiceServer service = nh.advertiseService("get_message", getMessageCallback);
40  spinner.stop();
41  return 0;
42 }
bool getMessageCallback(simple_node::GetMessage::Request &req, simple_node::GetMessage::Response &res)
Definition: simple_node.cpp:8
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int main(int argc, char **argv)
Definition: simple_node.cpp:30
#define ROS_INFO_STREAM(args)
ROSCPP_DECL void waitForShutdown()
std::atomic< unsigned > i
Definition: simple_node.cpp:6


simple_node
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Feb 28 2022 23:45:56