Main Page
Namespaces
Namespace List
Namespace Members
All
Functions
Variables
Typedefs
Classes
Class List
Class Members
All
Functions
Variables
Files
File List
File Members
All
b
c
d
e
g
h
i
m
n
r
s
u
Functions
Variables
c
g
h
i
m
n
r
s
Macros
src
examples
ExampleSubscriber
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
13
ros::NodeHandle
nh
;
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
}
19
ros::Subscriber<std_msgs::String>
sub
(
"chatter"
,
messageCb
);
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
}
nh
ros::NodeHandle nh
Definition:
ExampleSubscriber.cpp:13
main
int main()
Definition:
ExampleSubscriber.cpp:21
sub
ros::Subscriber< std_msgs::String > sub("chatter", messageCb)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
rosSrvrIp
char * rosSrvrIp
Definition:
ExampleSubscriber.cpp:14
ros::Subscriber
messageCb
void messageCb(const std_msgs::String &received_msg)
Definition:
ExampleSubscriber.cpp:16
ros::NodeHandle
rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Wed Mar 2 2022 00:58:06