service.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #include "ros/service.h"
29 #include "ros/connection.h"
31 #include "ros/service_manager.h"
33 #include "ros/poll_manager.h"
34 #include "ros/init.h"
35 #include "ros/names.h"
36 #include "ros/this_node.h"
37 #include "ros/header.h"
38 
39 using namespace ros;
40 
41 bool service::exists(const std::string& service_name, bool print_failure_reason)
42 {
43  std::string mapped_name = names::resolve(service_name);
44 
45  std::string host;
46  uint32_t port;
47 
48  if (ServiceManager::instance()->lookupService(mapped_name, host, port))
49  {
50  TransportTCPPtr transport(boost::make_shared<TransportTCP>(static_cast<ros::PollSet*>(NULL), TransportTCP::SYNCHRONOUS));
51 
52  if (transport->connect(host, port))
53  {
54  M_string m;
55  m["probe"] = "1";
56  m["md5sum"] = "*";
57  m["callerid"] = this_node::getName();
58  m["service"] = mapped_name;
60  uint32_t size = 0;;
61  Header::write(m, buffer, size);
62  transport->write((uint8_t*)&size, sizeof(size));
63  transport->write(buffer.get(), size);
64  transport->close();
65 
66  return true;
67  }
68  else
69  {
70  if (print_failure_reason)
71  {
72  ROS_INFO("waitForService: Service [%s] could not connect to host [%s:%d], waiting...", mapped_name.c_str(), host.c_str(), port);
73  }
74  }
75  }
76  else
77  {
78  if (print_failure_reason)
79  {
80  ROS_INFO("waitForService: Service [%s] has not been advertised, waiting...", mapped_name.c_str());
81  }
82  }
83 
84  return false;
85 }
86 
87 bool service::waitForService(const std::string& service_name, ros::Duration timeout)
88 {
89  std::string mapped_name = names::resolve(service_name);
90 
91  const WallTime start_time = WallTime::now();
92  const WallDuration wall_timeout{timeout.toSec()};
93 
94  bool printed = false;
95  bool result = false;
96  while (ros::ok())
97  {
98  if (exists(service_name, !printed))
99  {
100  result = true;
101  break;
102  }
103  else
104  {
105  printed = true;
106 
107  if (wall_timeout >= WallDuration(0))
108  {
109  const WallTime current_time = WallTime::now();
110 
111  if ((current_time - start_time) >= wall_timeout)
112  {
113  return false;
114  }
115  }
116 
117  WallDuration(0.02).sleep();
118  }
119  }
120 
121  if (printed && ros::ok())
122  {
123  ROS_INFO("waitForService: Service [%s] is now available.", mapped_name.c_str());
124  }
125 
126  return result;
127 }
128 
129 bool service::waitForService(const std::string& service_name, int32_t timeout)
130 {
131  return waitForService(service_name, ros::Duration(timeout / 1000.0));
132 }
ROSCPP_DECL const std::string & getName()
Returns the name of the current node.
Definition: this_node.cpp:81
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
Resolve a graph resource name into a fully qualified graph resource name.
Definition: names.cpp:136
static const ServiceManagerPtr & instance()
std::map< std::string, std::string > M_string
bool sleep() const
#define ROS_INFO(...)
static void write(const M_string &key_vals, boost::shared_array< uint8_t > &buffer, uint32_t &size)
ROSCPP_DECL bool ok()
Check whether it&#39;s time to exit.
Definition: init.cpp:573
static WallTime now()
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
Checks if a service is both advertised and available.
Definition: service.cpp:41
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
Wait for a service to be advertised and available. Blocks until it is.
Definition: service.cpp:129


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:26