hello.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <std_msgs/String.h>
4 
5 namespace mf = fkie_message_filters;
6 
10 
11 int main(int argc, char** argv)
12 {
13  ros::init(argc, argv, "hello");
14  ros::NodeHandle nh;
15  StringSubscriber sub(nh, "name", 1);
16  StringPublisher pub(nh, "greeting", 1);
17  GreetingFilter flt;
18  flt.set_processing_function(
19  [](const std_msgs::String& input, const GreetingFilter::CallbackFunction& output)
20  {
21  std_msgs::String greeting;
22  greeting.data = "Hello, " + input.data + "!";
23  output(greeting);
24  }
25  );
26  mf::chain(sub, flt, pub);
27  ros::spin();
28  return 0;
29 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publish consumed data on a ROS topic.
Definition: publisher.h:51
Subscribe to a ROS topic as data provider.
Definition: subscriber.h:54
int main(int argc, char **argv)
Definition: hello.cpp:11
Primary namespace.
Definition: buffer.h:33
void chain(Filter1 &flt1, Filter2 &flt2, MoreFilters &... filters) noexcept
Convenience function to chain multiple filters.
Definition: filter_impl.h:53
ROSCPP_DECL void spin()


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Mon Feb 28 2022 22:21:43