src
examples
ServiceClient
ServiceClient.cpp
Go to the documentation of this file.
1
/*
2
* rosserial Service Client
3
*/
4
5
#include <ros.h>
6
#include <std_msgs/String.h>
7
#include <rosserial_mbed/Test.h>
8
9
ros::NodeHandle
nh
;
10
using
rosserial_mbed::Test;
11
12
ros::ServiceClient<Test::Request, Test::Response>
client
(
"test_srv"
);
13
14
std_msgs::String
str_msg
;
15
ros::Publisher
chatter
(
"chatter"
, &
str_msg
);
16
17
char
hello
[13] =
"hello world!"
;
18
19
int
main
() {
20
nh
.initNode();
21
nh
.
serviceClient
(
client
);
22
nh
.
advertise
(
chatter
);
23
while
(!
nh
.connected())
nh
.spinOnce();
24
nh
.loginfo(
"Startup complete"
);
25
while
(1) {
26
Test::Request req;
27
Test::Response res;
28
req.input =
hello
;
29
client
.call(req, res);
30
str_msg
.data = res.output;
31
chatter
.
publish
( &
str_msg
);
32
nh
.spinOnce();
33
wait_ms(100);
34
}
35
}
36
ros::Publisher
chatter
ros::Publisher chatter("chatter", &str_msg)
client
Definition:
client.py:1
hello
char hello[13]
Definition:
ServiceClient.cpp:17
main
int main()
Definition:
ServiceClient.cpp:19
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
client
ros::ServiceClient< Test::Request, Test::Response > client("test_srv")
ros::ServiceClient
nh
ros::NodeHandle nh
Definition:
ServiceClient.cpp:9
str_msg
std_msgs::String str_msg
Definition:
ServiceClient.cpp:14
ros::NodeHandle
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08