ExampleSubscriber.cpp
Go to the documentation of this file.
1 /*
2  * rosserial_embeddedlinux subscriber example
3  *
4  * Prints a string sent on a subscribed ros topic.
5  * The string can be sent with e.g.
6  * $ rostopic pub chatter std_msgs/String -- "Hello Embedded Linux"
7  */
8 
9 #include <ros.h>
10 #include <std_msgs/String.h>
11 #include <stdio.h>
12 
14 char *rosSrvrIp = "192.168.15.149";
15 
16 void messageCb(const std_msgs::String& received_msg){
17  printf("Received subscribed chatter message: %s\n", received_msg.data);
18 }
20 
21 int main()
22 {
23  //nh.initNode();
24  nh.initNode(rosSrvrIp);
25  nh.subscribe(sub);
26 
27  while(1) {
28  sleep(1);
29  nh.spinOnce();
30  }
31 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void messageCb(const std_msgs::String &received_msg)
ros::NodeHandle nh
char * rosSrvrIp
ros::Subscriber< std_msgs::String > sub("chatter", messageCb)
int main()


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Mon Jun 10 2019 14:53:23