src
examples
pubsub
pubsub.cpp
Go to the documentation of this file.
1
/*
2
* rosserial PubSub Example
3
* Prints "hello world!" and toggles led
4
*/
5
#include "mbed.h"
6
#include <ros.h>
7
#include <std_msgs/String.h>
8
#include <std_msgs/Empty.h>
9
10
ros::NodeHandle
nh
;
11
DigitalOut
myled
(LED1);
12
13
void
messageCb
(
const
std_msgs::Empty& toggle_msg) {
14
myled
= !
myled
;
// blink the led
15
}
16
17
ros::Subscriber<std_msgs::Empty>
sub
(
"toggle_led"
,
messageCb
);
18
19
std_msgs::String
str_msg
;
20
ros::Publisher
chatter
(
"chatter"
, &
str_msg
);
21
22
char
hello
[13] =
"hello world!"
;
23
24
int
main
() {
25
nh
.initNode();
26
nh
.
advertise
(
chatter
);
27
nh
.
subscribe
(
sub
);
28
29
while
(1) {
30
str_msg
.data =
hello
;
31
chatter
.
publish
( &
str_msg
);
32
nh
.spinOnce();
33
wait_ms(500);
34
}
35
}
36
ros::Publisher
sub
ros::Subscriber< std_msgs::Empty > sub("toggle_led", messageCb)
hello
char hello[13]
Definition:
pubsub.cpp:22
chatter
ros::Publisher chatter("chatter", &str_msg)
myled
DigitalOut myled(LED1)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
main
int main()
Definition:
pubsub.cpp:24
messageCb
void messageCb(const std_msgs::Empty &toggle_msg)
Definition:
pubsub.cpp:13
str_msg
std_msgs::String str_msg
Definition:
pubsub.cpp:19
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())
nh
ros::NodeHandle nh
Definition:
pubsub.cpp:10
ros::Subscriber
ros::NodeHandle
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08