Skip to content

Commit ce1f433

Browse files
Barry-Xu-2018fujitatomoya
authored andcommitted
Support TCP/IP and UDS(Unix Domain Socket) hybrid transport for roscpp and rospy
Signed-off-by: Barry Xu <barry.xu@sony.com>
1 parent 8250c7d commit ce1f433

40 files changed

+3713
-288
lines changed

clients/roscpp/CMakeLists.txt

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,13 @@ CHECK_CXX_SYMBOL_EXISTS(epoll_wait "sys/epoll.h" HAVE_EPOLL)
7575
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/src/libros/config.h.in ${CMAKE_CURRENT_BINARY_DIR}/config.h)
7676
include_directories(${CMAKE_CURRENT_BINARY_DIR})
7777

78-
add_library(roscpp
78+
set(UDS_FEATURE_SRC
79+
src/libros/transport/transport_uds.cpp
80+
src/libros/transport/transport_uds_stream.cpp
81+
src/libros/transport/transport_uds_datagram.cpp
82+
)
83+
84+
add_library(roscpp
7985
src/libros/master.cpp
8086
src/libros/network.cpp
8187
src/libros/subscriber.cpp
@@ -124,6 +130,7 @@ add_library(roscpp
124130
src/libros/service.cpp
125131
src/libros/this_node.cpp
126132
src/libros/steady_timer.cpp
133+
${UDS_FEATURE_SRC}
127134
)
128135

129136
if(WIN32)

clients/roscpp/include/ros/connection_manager.h

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,10 +64,17 @@ class ROSCPP_DECL ConnectionManager
6464
uint32_t getTCPPort();
6565
uint32_t getUDPPort();
6666

67+
const std::string getUDSStreamPath();
68+
const std::string getUDSDatagramPath();
69+
6770
const TransportTCPPtr& getTCPServerTransport() { return tcpserver_transport_; }
6871
const TransportUDPPtr& getUDPServerTransport() { return udpserver_transport_; }
6972

73+
const TransportUDSStreamPtr& getUDSStreamServerTransport() { return uds_stream_server_transport_; }
74+
const TransportUDSDatagramPtr& getUDSDatagramServerTransport() { return uds_datagram_server_transport_; }
75+
7076
void udprosIncomingConnection(const TransportUDPPtr& transport, Header& header);
77+
void udprosIncomingConnection(const TransportUDSDatagramPtr& transport, Header& header);
7178

7279
void start();
7380
void shutdown();
@@ -81,6 +88,7 @@ class ROSCPP_DECL ConnectionManager
8188

8289
bool onConnectionHeaderReceived(const ConnectionPtr& conn, const Header& header);
8390
void tcprosAcceptConnection(const TransportTCPPtr& transport);
91+
void tcprosAcceptConnection(const TransportUDSStreamPtr& transport);
8492

8593
PollManagerPtr poll_manager_;
8694

@@ -99,6 +107,10 @@ class ROSCPP_DECL ConnectionManager
99107
TransportTCPPtr tcpserver_transport_;
100108
TransportUDPPtr udpserver_transport_;
101109

110+
// Unix Domain Socket (stream, datagram)
111+
TransportUDSStreamPtr uds_stream_server_transport_;
112+
TransportUDSDatagramPtr uds_datagram_server_transport_;
113+
102114
const static int MAX_TCPROS_CONN_QUEUE = 100; // magic
103115
};
104116

clients/roscpp/include/ros/forwards.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include <ros/macros.h>
4444
#include "exceptions.h"
4545
#include "ros/datatypes.h"
46+
#include "ros/common.h"
4647

4748
namespace ros
4849
{
@@ -59,6 +60,10 @@ class TransportTCP;
5960
typedef boost::shared_ptr<TransportTCP> TransportTCPPtr;
6061
class TransportUDP;
6162
typedef boost::shared_ptr<TransportUDP> TransportUDPPtr;
63+
class TransportUDSStream;
64+
typedef boost::shared_ptr<TransportUDSStream> TransportUDSStreamPtr;
65+
class TransportUDSDatagram;
66+
typedef boost::shared_ptr<TransportUDSDatagram> TransportUDSDatagramPtr;
6267
class Connection;
6368
typedef boost::shared_ptr<Connection> ConnectionPtr;
6469
typedef std::set<ConnectionPtr> S_Connection;

clients/roscpp/include/ros/network.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,8 @@ namespace network
4141
{
4242

4343
ROSCPP_DECL bool splitURI(const std::string& uri, std::string& host, uint32_t& port);
44+
ROSCPP_DECL bool splitURI(const std::string& uri, std::string& uds_path);
45+
ROSCPP_DECL bool isInternal(const std::string& uds_path, const std::string& hostname);
4446
ROSCPP_DECL const std::string& getHost();
4547
ROSCPP_DECL uint16_t getTCPROSPort();
4648

clients/roscpp/include/ros/service_manager.h

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -99,6 +99,15 @@ class ROSCPP_DECL ServiceManager
9999
*/
100100
bool lookupService(const std::string& name, std::string& serv_host, uint32_t& serv_port);
101101

102+
/** @brief Lookup the host/port, uds_path of a service.
103+
*
104+
* @param name The name of the service
105+
* @param serv_host OUT -- The host of the service
106+
* @param serv_port OUT -- The port of the service
107+
* @param serv_uds_path OUT -- The UDS path of the service
108+
*/
109+
bool lookupServiceExt(const std::string& name, std::string& serv_host, uint32_t& serv_port, std::string& serv_uds_path);
110+
102111
/** @brief Unadvertise a service.
103112
*
104113
* This call unadvertises a service, which must have been previously

clients/roscpp/include/ros/subscription.h

Lines changed: 78 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -119,7 +119,7 @@ class ROSCPP_DECL Subscription : public boost::enable_shared_from_this<Subscript
119119
uint32_t getNumCallbacks() const { return callbacks_.size(); }
120120
uint32_t getNumPublishers();
121121

122-
// We'll keep a list of these objects, representing in-progress XMLRPC
122+
// We'll keep a list of these objects, representing in-progress XMLRPC
123123
// connections to other nodes.
124124
class ROSCPP_DECL PendingConnection : public ASyncXMLRPCConnection
125125
{
@@ -131,13 +131,24 @@ class ROSCPP_DECL Subscription : public boost::enable_shared_from_this<Subscript
131131
, remote_uri_(remote_uri)
132132
{}
133133

134+
PendingConnection(XmlRpc::XmlRpcClient* client, TransportUDPPtr udp_transport, TransportUDSDatagramPtr uds_datagram_transport, const SubscriptionWPtr& parent, const std::string& remote_uri)
135+
: client_(client)
136+
, udp_transport_(udp_transport)
137+
, uds_datagram_transport_(uds_datagram_transport)
138+
, parent_(parent)
139+
, remote_uri_(remote_uri)
140+
{}
141+
134142
~PendingConnection()
135143
{
136144
delete client_;
137145
}
138146

139147
XmlRpc::XmlRpcClient* getClient() const { return client_; }
140148
TransportUDPPtr getUDPTransport() const { return udp_transport_; }
149+
TransportUDSDatagramPtr getUDSDatagramTransport() const { return uds_datagram_transport_; }
150+
const std::string& getUDSPath() const { return uds_path_; }
151+
void setUDSPath(const std::string& uds_path) { uds_path_ = uds_path; }
141152

142153
virtual void addToDispatch(XmlRpc::XmlRpcDispatch* disp)
143154
{
@@ -172,11 +183,77 @@ class ROSCPP_DECL Subscription : public boost::enable_shared_from_this<Subscript
172183
private:
173184
XmlRpc::XmlRpcClient* client_;
174185
TransportUDPPtr udp_transport_;
186+
TransportUDSDatagramPtr uds_datagram_transport_;
187+
std::string uds_path_;
175188
SubscriptionWPtr parent_;
176189
std::string remote_uri_;
177190
};
178191
typedef boost::shared_ptr<PendingConnection> PendingConnectionPtr;
179192

193+
class ROSCPP_DECL PendingConnectionUDS : public ASyncXMLRPCConnection
194+
{
195+
public:
196+
PendingConnectionUDS(XmlRpc::XmlRpcClient* client, const SubscriptionWPtr& parent, const std::string& remote_uri, PendingConnectionPtr pending_connection)
197+
: client_(client)
198+
, parent_(parent)
199+
, remote_uri_(remote_uri)
200+
, pending_connection_(pending_connection)
201+
{}
202+
203+
~PendingConnectionUDS()
204+
{
205+
delete client_;
206+
}
207+
208+
virtual void addToDispatch(XmlRpc::XmlRpcDispatch* disp)
209+
{
210+
disp->addSource(client_, XmlRpc::XmlRpcDispatch::WritableEvent | XmlRpc::XmlRpcDispatch::Exception);
211+
}
212+
213+
virtual void removeFromDispatch(XmlRpc::XmlRpcDispatch* disp)
214+
{
215+
disp->removeSource(client_);
216+
}
217+
218+
virtual bool check()
219+
{
220+
SubscriptionPtr parent = parent_.lock();
221+
if (!parent)
222+
{
223+
return true;
224+
}
225+
226+
XmlRpc::XmlRpcValue result;
227+
if (client_->executeCheckDone(result))
228+
{
229+
230+
XmlRpc::XmlRpcValue proto;
231+
// validate the requestTopicUds response data
232+
if (XMLRPCManager::instance()->validateXmlrpcResponse("requestTopicUds", result, proto)) {
233+
// protocol data contains (TCPROS, uds_path) or (UDPROS, uds_path, ...)
234+
std::string proto_name = proto[0];
235+
if (proto_name == std::string("TCPROS") ||
236+
proto_name == std::string("UDPROS")) {
237+
std::string uds_path = std::string(proto[1]);
238+
pending_connection_->setUDSPath(uds_path);
239+
}
240+
}
241+
242+
XMLRPCManager::instance()->addASyncConnection(pending_connection_);
243+
return true;
244+
}
245+
246+
return false;
247+
}
248+
249+
private:
250+
XmlRpc::XmlRpcClient* client_;
251+
SubscriptionWPtr parent_;
252+
std::string remote_uri_;
253+
PendingConnectionPtr pending_connection_;
254+
};
255+
typedef boost::shared_ptr<PendingConnectionUDS> PendingConnectionUDSPtr;
256+
180257
void pendingConnectionDone(const PendingConnectionPtr& pending_conn, XmlRpc::XmlRpcValue& result);
181258

182259
void getPublishTypes(bool& ser, bool& nocopy, const std::type_info& ti);

clients/roscpp/include/ros/topic_manager.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -152,7 +152,9 @@ class ROSCPP_DECL TopicManager
152152
*
153153
* @todo Consider making this private
154154
*/
155-
bool requestTopic(const std::string &topic, XmlRpc::XmlRpcValue &protos, XmlRpc::XmlRpcValue &ret);
155+
bool requestTopic(const std::string &topic, XmlRpc::XmlRpcValue &protos, XmlRpc::XmlRpcValue &ret
156+
, bool uds_flag=false
157+
);
156158

157159
// Must lock the advertised topics mutex before calling this function
158160
bool isTopicAdvertised(const std::string& topic);
@@ -211,6 +213,7 @@ class ROSCPP_DECL TopicManager
211213

212214
void pubUpdateCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
213215
void requestTopicCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
216+
void requestTopicUdsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
214217
void getBusStatsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
215218
void getBusInfoCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
216219
void getSubscriptionsCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result);
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
/*
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2018, Open Source Robotics Foundation, Inc.
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of Willow Garage, Inc. nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*/
34+
35+
#ifndef ROSCPP_TRANSPORT_UDS_H
36+
#define ROSCPP_TRANSPORT_UDS_H
37+
38+
#include <ros/transport/transport.h>
39+
40+
/*! @name UDS Feature Bit Field
41+
Unix Domain Socket Feature Bit Field controlled by environmental value from user.
42+
*/
43+
/* @{ */
44+
#define ROS_UDS_EXT_ABSTRACT_SOCK_NAME 0x00000001 /*!< enable abstract named socket */
45+
/* @} */
46+
47+
#define ROS_UDS_EXT_IS_ENABLE(feature) (TransportUDS::s_uds_feature_ & feature)
48+
49+
namespace ros
50+
{
51+
52+
/**
53+
* \brief Abstract base class that allows abstraction of the transport type, eg. Unix domain socket(stream or datagram)
54+
*/
55+
class TransportUDS : public Transport
56+
{
57+
public:
58+
static uint32_t s_uds_feature_;
59+
60+
/**
61+
* \brief Returns the server UDS path this transport is using with
62+
*/
63+
const std::string getServerUDSPath() { return server_uds_path_; }
64+
65+
protected:
66+
/**
67+
* \brief Generate abstrace named socket".
68+
*/
69+
const std::string generateServerUDSPath();
70+
/**
71+
* \brief Generate a string of UDS path like "${TMP}/ros-uds-[stream|datagram]-${PID}-${COUNTER}", the default value of ${TMP} is "/tmp".
72+
*/
73+
const std::string generateServerUDSPath(uint32_t counter);
74+
75+
std::string server_type_;
76+
std::string server_uds_path_;
77+
};
78+
79+
}
80+
81+
#endif // ROSCPP_TRANSPORT_UDS_H

0 commit comments

Comments
 (0)