src
tests
float64_test
float64_test.cpp
Go to the documentation of this file.
1
//#define COMPLIE_FLOAT64_CODE_ROSSERIAL
2
#ifdef COMPILE_FLOAT64_CODE_ROSSERIAL
3
4
/*
5
* rosserial::std_msgs::Float64 Test
6
* Receives a Float64 input, subtracts 1.0, and publishes it
7
*/
8
9
#include "mbed.h"
10
#include <ros.h>
11
#include <std_msgs/Float64.h>
12
13
14
ros::NodeHandle
nh
;
15
16
float
x
;
17
DigitalOut
myled
(LED1);
18
19
void
messageCb
(
const
std_msgs::Float64& msg) {
20
x
= msg.data - 1.0;
21
myled
= !
myled
;
// blink the led
22
}
23
24
std_msgs::Float64
test
;
25
ros::Subscriber<std_msgs::Float64>
s
(
"your_topic"
, &
messageCb
);
26
ros::Publisher
p
(
"my_topic"
, &
test
);
27
28
int
main
() {
29
nh
.initNode();
30
nh
.
advertise
(
p
);
31
nh
.
subscribe
(s);
32
while
(1) {
33
test
.data =
x
;
34
p
.
publish
( &
test
);
35
nh
.spinOnce();
36
wait_ms(10);
37
}
38
}
39
#endif
main
int main()
Definition:
ADC.cpp:46
ros::Publisher
s
XmlRpcServer s
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
test
messageCb
void messageCb(const std_msgs::Empty &toggle_msg)
Definition:
Blink.cpp:12
nh
ros::NodeHandle nh
Definition:
ADC.cpp:31
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())
p
ros::Publisher p("adc", &adc_msg)
ros::Subscriber
ros::NodeHandle
myled
DigitalOut myled(LED1)
x
double x
Definition:
Odom.cpp:15
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08