Skip to content

Commit

Permalink
check ROS_HOSTNAME for localhost / ROS_IP for 127./::1 and prevent co…
Browse files Browse the repository at this point in the history
…nnections from other hosts in that case
  • Loading branch information
codebot authored and dirk-thomas committed Jul 10, 2014
1 parent c171283 commit 8713a1e
Show file tree
Hide file tree
Showing 6 changed files with 161 additions and 4 deletions.
1 change: 1 addition & 0 deletions clients/roscpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ add_library(roscpp
src/libros/node_handle.cpp
src/libros/connection_manager.cpp
src/libros/file_log.cpp
src/libros/transport/transport.cpp
src/libros/transport/transport_udp.cpp
src/libros/transport/transport_tcp.cpp
src/libros/subscriber_link.cpp
Expand Down
17 changes: 16 additions & 1 deletion clients/roscpp/include/ros/transport/transport.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <boost/function.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/enable_shared_from_this.hpp>
#include <vector>

namespace ros
{
Expand All @@ -54,7 +55,7 @@ class Header;
class Transport : public boost::enable_shared_from_this<Transport>
{
public:
Transport() {}
Transport();
virtual ~Transport() {}

/**
Expand Down Expand Up @@ -134,6 +135,20 @@ class Transport : public boost::enable_shared_from_this<Transport>
Callback disconnect_cb_;
Callback read_cb_;
Callback write_cb_;

/**
* \brief returns true if the transport is allowed to connect to the host passed to it.
*/
bool isHostAllowed(const std::string &host) const;

/**
* \brief returns true if this transport is only allowed to talk to localhost
*/
bool isOnlyLocalhostAllowed() const { return only_localhost_allowed_; }

private:
bool only_localhost_allowed_;
std::vector<std::string> allowed_hosts_;
};

}
Expand Down
119 changes: 119 additions & 0 deletions clients/roscpp/src/libros/transport/transport.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,119 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2014, Open Source Robotics Foundation, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "ros/transport/transport.h"
#include "ros/console.h"
#include <ifaddrs.h>
#include <netinet/in.h>
#include <sys/socket.h>
#include <netdb.h>

#ifndef NI_MAXHOST
#define NI_MAXHOST 1025
#endif

namespace ros
{

Transport::Transport()
: only_localhost_allowed_(false)
{
char *ros_ip_env = NULL, *ros_hostname_env = NULL;
#ifdef _MSC_VER
_dupenv_s(&ros_ip_env, NULL, "ROS_IP");
_dupenv_s(&ros_hostname_env, NULL, "ROS_HOSTNAME");
#else
ros_ip_env = getenv("ROS_IP");
ros_hostname_env = getenv("ROS_HOSTNAME");
#endif
if (ros_hostname_env && !strcmp(ros_hostname_env, "localhost"))
only_localhost_allowed_ = true;
else if (ros_ip_env && !strncmp(ros_ip_env, "127.", 4))
only_localhost_allowed_ = true;
else if (ros_ip_env && !strcmp(ros_ip_env, "::1"))
only_localhost_allowed_ = true;

char our_hostname[256] = {0};
gethostname(our_hostname, sizeof(our_hostname)-1);
allowed_hosts_.push_back(std::string(our_hostname));
allowed_hosts_.push_back("localhost");
// for ipv4 loopback, we'll explicitly search for 127.* in isHostAllowed()
// now we need to iterate all local interfaces and add their addresses
// from the getifaddrs manpage: (maybe something similar for windows ?)
ifaddrs *ifaddr;
if (-1 == getifaddrs(&ifaddr))
{
ROS_ERROR("getifaddr() failed");
return;
}
for (ifaddrs *ifa = ifaddr; ifa; ifa = ifa->ifa_next)
{
int family = ifa->ifa_addr->sa_family;
if (family != AF_INET && family != AF_INET6)
continue; // we're only looking for IP addresses
char addr[NI_MAXHOST] = {0};
if (getnameinfo(ifa->ifa_addr,
(family == AF_INET) ? sizeof(sockaddr_in)
: sizeof(sockaddr_in6),
addr, NI_MAXHOST,
NULL, 0, NI_NUMERICHOST))
{
ROS_ERROR("getnameinfo() failed");
continue;
}
allowed_hosts_.push_back(std::string(addr));
}
}

bool Transport::isHostAllowed(const std::string &host) const
{
if (!only_localhost_allowed_)
return true; // doesn't matter; we'll connect to anybody

if (host.length() >= 4 && host.substr(0, 4) == std::string("127."))
return true; // ipv4 localhost
// now, loop through the list of valid hostnames and see if we find it
for (std::vector<std::string>::const_iterator it = allowed_hosts_.begin();
it != allowed_hosts_.end(); ++it)
{
if (host == *it)
return true; // hooray
}
ROS_WARN("ROS_HOSTNAME / ROS_IP is set to only allow local connections, so "
"a requested connection to '%s' is being rejected.", host.c_str());
return false; // sadness
}

}

11 changes: 9 additions & 2 deletions clients/roscpp/src/libros/transport/transport_tcp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -211,6 +211,9 @@ void TransportTCP::setKeepAlive(bool use, uint32_t idle, uint32_t interval, uint

bool TransportTCP::connect(const std::string& host, int port)
{
if (!isHostAllowed(host))
return false; // adios amigo

sock_ = socket(s_use_ipv6_ ? AF_INET6 : AF_INET, SOCK_STREAM, 0);
connected_host_ = host;
connected_port_ = port;
Expand Down Expand Up @@ -357,7 +360,9 @@ bool TransportTCP::listen(int port, int backlog, const AcceptCallback& accept_cb
sock_ = socket(AF_INET6, SOCK_STREAM, 0);
sockaddr_in6 *address = (sockaddr_in6 *)&server_address_;
address->sin6_family = AF_INET6;
address->sin6_addr = in6addr_any;
address->sin6_addr = isOnlyLocalhostAllowed() ?
in6addr_loopback :
in6addr_any;
address->sin6_port = htons(port);
sa_len_ = sizeof(sockaddr_in6);
}
Expand All @@ -366,7 +371,9 @@ bool TransportTCP::listen(int port, int backlog, const AcceptCallback& accept_cb
sock_ = socket(AF_INET, SOCK_STREAM, 0);
sockaddr_in *address = (sockaddr_in *)&server_address_;
address->sin_family = AF_INET;
address->sin_addr.s_addr = INADDR_ANY;
address->sin_addr.s_addr = isOnlyLocalhostAllowed() ?
htonl(INADDR_LOOPBACK) :
INADDR_ANY;
address->sin_port = htons(port);
sa_len_ = sizeof(sockaddr_in);
}
Expand Down
7 changes: 6 additions & 1 deletion clients/roscpp/src/libros/transport/transport_udp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,9 @@ std::string TransportUDP::getTransportInfo()

bool TransportUDP::connect(const std::string& host, int port, int connection_id)
{
if (!isHostAllowed(host))
return false; // adios amigo

sock_ = socket(AF_INET, SOCK_DGRAM, 0);
connection_id_ = connection_id;

Expand Down Expand Up @@ -242,7 +245,9 @@ bool TransportUDP::createIncoming(int port, bool is_server)

server_address_.sin_family = AF_INET;
server_address_.sin_port = htons(port);
server_address_.sin_addr.s_addr = INADDR_ANY;
server_address_.sin_addr.s_addr = isOnlyLocalhostAllowed() ?
htonl(INADDR_LOOPBACK) :
INADDR_ANY;
if (bind(sock_, (sockaddr *)&server_address_, sizeof(server_address_)) < 0)
{
ROS_ERROR("bind() failed with error [%s]", last_socket_error_string());
Expand Down
10 changes: 10 additions & 0 deletions clients/rospy/src/rospy/impl/tcpros_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -518,6 +518,16 @@ def connect(self, dest_addr, dest_port, endpoint_id, timeout=None):
@type timeout: float
@raise TransportInitError: if unable to create connection
"""
# first make sure that if ROS_HOSTNAME=localhost, we will not attempt
# to connect to anything other than localhost
if ("ROS_HOSTNAME" in os.environ) and (os.environ["ROS_HOSTNAME"] == "localhost"):
if not rosgraph.network.is_local_address(dest_addr):
msg = "attempted to connect to non-local host [%s] from a node launched with ROS_HOSTNAME=localhost" % (dest_addr)
logwarn(msg)
self.close()
raise TransportInitError(msg) # bubble up

# now we can proceed with trying to connect.
try:
self.endpoint_id = endpoint_id
self.dest_address = (dest_addr, dest_port)
Expand Down

0 comments on commit 8713a1e

Please sign in to comment.