chat_client.cpp
Go to the documentation of this file.
1 #include <grpcpp/grpcpp.h>
2 #include <ros/ros.h>
3 #include <std_msgs/String.h>
4 #include <test_grpc/grpcs/Chat.grpc.pb.h>
5 
6 namespace test_grpc
7 {
9 {
10  ros::Publisher response_pub = nh.advertise<std_msgs::String>("response", 1, true);
11 
12  const std::string client_address =
13  nh.param<std::string>("client_address", "127.0.0.1:50000");
14 
15  std::shared_ptr<grpc::Channel> channel =
17  ROS_INFO_STREAM("Connecting to " << client_address);
18  std::chrono::system_clock::time_point deadline =
19  std::chrono::system_clock::now() + std::chrono::seconds(10);
20  if (!channel->WaitForConnected(deadline))
21  {
22  ROS_ERROR_STREAM("Waiting for server timedout");
23  return;
24  }
25  ROS_INFO_STREAM("Connected to " << client_address);
26 
27  std::unique_ptr<grpcs::Chat::Stub> stub(
28  grpcs::Chat::NewStub(channel));
29 
31  grpcs::Message request;
32  grpcs::Message response;
33 
34  auto stamp = request.mutable_header()->mutable_stamp();
35  auto now = ros::Time::now();
36  stamp->set_seconds(now.sec);
37  stamp->set_nanos(now.nsec);
38  request.set_sender(1);
39  request.set_body("foo");
40 
42  if (status.ok())
43  {
44  ROS_INFO_STREAM("response received " << response.body() << " from " << response.sender());
45  if (request.body() == response.body())
46  {
47  std_msgs::String msg;
48  msg.data = response.body();
49  // wait for test subscriber
50  ros::Duration(1).sleep();
51  response_pub.publish(msg);
52  // wait for publish
53  ros::Duration(10).sleep();
54  }
55  else
56  {
57  ROS_ERROR_STREAM("received response mismatch: " << request.body()
58  << " != " << response.body());
59  }
60  }
61  else
62  {
63  ROS_ERROR_STREAM("Echo service returned error " << static_cast<int>(status.error_code()) << ": "
64  << status.error_message());
65  }
66 }
67 }
68 
69 int main(int argc, char** argv)
70 {
71  ros::init(argc, argv, "chat_client");
72  ros::NodeHandle pnh("~");
74  return 0;
75 }
test_grpc
Definition: chat_client.cpp:6
status
auto status
ctx
ros::Publisher
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
request
request
ros.h
stub
stub
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
grpcpp.h
channel
channel
main
int main(int argc, char **argv)
Definition: chat_client.cpp:69
grpc::CreateChannel
std::shared_ptr< Channel > CreateChannel(const grpc::string &target, const std::shared_ptr< ChannelCredentials > &creds)
msg
std::string msg
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
grpc::ClientContext
test_grpc::chatClient
void chatClient(ros::NodeHandle &nh)
Definition: chat_client.cpp:8
response
response
grpc::Status
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Duration::sleep
bool sleep() const
grpc::InsecureChannelCredentials
std::shared_ptr< ChannelCredentials > InsecureChannelCredentials()
ros::Duration
ros::NodeHandle
ros::Time::now
static Time now()


test_grpc
Author(s): Yuki Furuta
autogenerated on Thu Mar 13 2025 03:40:40