rc_silhouettematch_client_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020 Roboception GmbH
3  *
4  * Author: Elena Gambaro
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  *
12  * 2. Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its contributors
17  * may be used to endorse or promote products derived from this software without
18  * specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
23  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
24  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
25  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
26  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
27  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
28  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
29  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
34 
35 #include <ros/ros.h>
36 #include <signal.h>
37 #include <rcdiscover/discover.h>
38 #include <rcdiscover/utils.h>
39 
41 std::unique_ptr<SilhouetteMatchClient> client;
42 
43 void sigintHandler(int)
44 {
45  ROS_INFO("Shutting down...");
46  client.reset();
47  ros::shutdown();
48 }
49 
50 std::string getHost(const std::string& device_name, const std::string& interface)
51 {
52  // broadcast discover request
53  rcdiscover::Discover discover;
54  discover.broadcastRequest();
55 
56  std::vector<rcdiscover::DeviceInfo> infos;
57 
58  // get responses
59  while (discover.getResponse(infos, 100))
60  {
61  }
62 
63  std::vector<std::vector<std::string>> devices;
64  std::vector<std::string> filtered_info = { "", "" };
65  for (const auto& info : infos)
66  {
67  if (!interface.empty() && interface != info.getIfaceName())
68  {
69  continue;
70  }
71 
72  // if used defined name is not set, fall back to model name
73  std::string user_defined_name = info.getUserName();
74  if (user_defined_name.empty())
75  {
76  user_defined_name = info.getModelName();
77  }
78 
79  // if no device is given, return any rc_visard
80  if (device_name.empty())
81  {
82  if (info.getModelName().find("rc_visard") != std::string::npos)
83  {
84  filtered_info[0] = user_defined_name;
85  filtered_info[1] = ip2string(info.getIP());
86  devices.push_back(filtered_info);
87  }
88  }
89  else if ((device_name == info.getSerialNumber()) || (device_name == user_defined_name))
90  {
91  filtered_info[0] = user_defined_name;
92  filtered_info[1] = ip2string(info.getIP());
93  devices.push_back(filtered_info);
94  }
95  }
96  std::sort(devices.begin(), devices.end());
97  auto unique_devices_it = std::unique(devices.begin(), devices.end());
98  devices.erase(unique_devices_it, devices.end());
99 
100  if (devices.empty())
101  {
102  ROS_FATAL_STREAM("No device found with the name '" << device_name << "'");
103  return "";
104  }
105  else if (devices.size() > 1)
106  {
107  ROS_FATAL_STREAM("Found " << devices.size() << " devices with the name '" << device_name
108  << "'. Please specify a unique device name.");
109  return "";
110  }
111 
112  ROS_INFO_STREAM("Using device '" << device_name << "' with name '" << devices[0][0] << "' and IP address "
113  << devices[0][1]);
114  return devices[0][1];
115 }
116 
117 int main(int argc, char** argv)
118 {
119  ros::init(argc, argv, "rc_silhouettematch_client", ros::init_options::NoSigintHandler);
120  signal(SIGINT, sigintHandler);
121 
122  ros::NodeHandle pnh("~");
123 
124  std::string host;
125  std::string device;
126  pnh.getParam("host", host);
127  pnh.getParam("device", device);
128  if (!host.empty() && !device.empty())
129  {
130  ROS_WARN("Both parameters: 'device' and 'host' are set. Using 'device' to "
131  "start the client.");
132  }
133 
134  if (!device.empty() || host.empty())
135  {
136  std::size_t delim_pos = 0;
137  delim_pos = device.find(':');
138  std::string interface;
139  if (delim_pos != std::string::npos)
140  {
141  interface = device.substr(0, delim_pos);
142  device = device.substr(delim_pos + 1);
143  }
144 
145  host = getHost(device, interface);
146  }
147 
148  if (host.empty())
149  {
150  return 1;
151  }
152 
153  try
154  {
155  client.reset(new SilhouetteMatchClient(host, pnh));
156  }
157  catch (const std::exception& ex)
158  {
159  ROS_FATAL("Client could not be created due to an error: %s", ex.what());
160  return 1;
161  }
162 
163  ROS_INFO_STREAM("SilhouetteMatch client node started for host: " << host);
164 
165  ros::spin();
166 }
#define ROS_FATAL(...)
std::string ip2string(const uint32_t ip)
std::string getHost(const std::string &device_name, const std::string &interface)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
std::unique_ptr< SilhouetteMatchClient > client
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_FATAL_STREAM(args)
void sigintHandler(int)
#define ROS_INFO(...)
bool getResponse(std::vector< DeviceInfo > &info, int timeout_per_socket=1000)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
ROSCPP_DECL void shutdown()


rc_silhouettematch_client
Author(s): Elena Gambaro
autogenerated on Sat Feb 13 2021 03:42:03