src
tests
array_test
array_test.cpp
Go to the documentation of this file.
1
//#define COMPILE_ARRAY_CODE_RSOSSERIAL
2
#ifdef COMPILE_ARRAY_CODE_RSOSSERIAL
3
4
/*
5
* rosserial::geometry_msgs::PoseArray Test
6
* Sums an array, publishes sum
7
*/
8
#include "mbed.h"
9
#include <ros.h>
10
#include <geometry_msgs/Pose.h>
11
#include <geometry_msgs/PoseArray.h>
12
13
14
ros::NodeHandle
nh
;
15
16
bool
set_;
17
DigitalOut
myled
(LED1);
18
19
geometry_msgs::Pose sum_msg;
20
ros::Publisher
p
(
"sum"
, &sum_msg);
21
22
void
messageCb
(
const
geometry_msgs::PoseArray& msg) {
23
sum_msg.position.x = 0;
24
sum_msg.position.y = 0;
25
sum_msg.position.z = 0;
26
for
(
int
i
= 0;
i
< msg.poses_length;
i
++) {
27
sum_msg.position.x += msg.poses[
i
].position.x;
28
sum_msg.position.y += msg.poses[
i
].position.y;
29
sum_msg.position.z += msg.poses[
i
].position.z;
30
}
31
myled
= !
myled
;
// blink the led
32
}
33
34
ros::Subscriber<geometry_msgs::PoseArray>
s
(
"poses"
,
messageCb
);
35
36
int
main
() {
37
nh
.initNode();
38
nh
.
subscribe
(s);
39
nh
.
advertise
(
p
);
40
41
while
(1) {
42
p
.
publish
(&sum_msg);
43
nh
.spinOnce();
44
wait_ms(10);
45
}
46
}
47
#endif
main
int main()
Definition:
ADC.cpp:46
ros::Publisher
s
XmlRpcServer s
i
int i
Definition:
ServiceServer.cpp:12
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
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)
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08