From 8713a1e22f69535a88b1a2f9c3b6a4c73abf6cf1 Mon Sep 17 00:00:00 2001 From: Morgan Quigley Date: Fri, 27 Jun 2014 17:27:22 -0700 Subject: [PATCH] check ROS_HOSTNAME for localhost / ROS_IP for 127./::1 and prevent connections from other hosts in that case --- clients/roscpp/CMakeLists.txt | 1 + .../roscpp/include/ros/transport/transport.h | 17 ++- .../roscpp/src/libros/transport/transport.cpp | 119 ++++++++++++++++++ .../src/libros/transport/transport_tcp.cpp | 11 +- .../src/libros/transport/transport_udp.cpp | 7 +- clients/rospy/src/rospy/impl/tcpros_base.py | 10 ++ 6 files changed, 161 insertions(+), 4 deletions(-) create mode 100644 clients/roscpp/src/libros/transport/transport.cpp diff --git a/clients/roscpp/CMakeLists.txt b/clients/roscpp/CMakeLists.txt index 0e75f20bc5..252d43fd0b 100644 --- a/clients/roscpp/CMakeLists.txt +++ b/clients/roscpp/CMakeLists.txt @@ -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 diff --git a/clients/roscpp/include/ros/transport/transport.h b/clients/roscpp/include/ros/transport/transport.h index c53d16d19e..8c7ca7852e 100644 --- a/clients/roscpp/include/ros/transport/transport.h +++ b/clients/roscpp/include/ros/transport/transport.h @@ -39,6 +39,7 @@ #include #include #include +#include namespace ros { @@ -54,7 +55,7 @@ class Header; class Transport : public boost::enable_shared_from_this { public: - Transport() {} + Transport(); virtual ~Transport() {} /** @@ -134,6 +135,20 @@ class Transport : public boost::enable_shared_from_this 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 allowed_hosts_; }; } diff --git a/clients/roscpp/src/libros/transport/transport.cpp b/clients/roscpp/src/libros/transport/transport.cpp new file mode 100644 index 0000000000..3374f4f51d --- /dev/null +++ b/clients/roscpp/src/libros/transport/transport.cpp @@ -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 +#include +#include +#include + +#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::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 +} + +} + diff --git a/clients/roscpp/src/libros/transport/transport_tcp.cpp b/clients/roscpp/src/libros/transport/transport_tcp.cpp index ae44cda5c9..316b788754 100644 --- a/clients/roscpp/src/libros/transport/transport_tcp.cpp +++ b/clients/roscpp/src/libros/transport/transport_tcp.cpp @@ -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; @@ -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); } @@ -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); } diff --git a/clients/roscpp/src/libros/transport/transport_udp.cpp b/clients/roscpp/src/libros/transport/transport_udp.cpp index 759463de89..75bf6081cb 100644 --- a/clients/roscpp/src/libros/transport/transport_udp.cpp +++ b/clients/roscpp/src/libros/transport/transport_udp.cpp @@ -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; @@ -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()); diff --git a/clients/rospy/src/rospy/impl/tcpros_base.py b/clients/rospy/src/rospy/impl/tcpros_base.py index 9dbb97ab27..21b376e740 100644 --- a/clients/rospy/src/rospy/impl/tcpros_base.py +++ b/clients/rospy/src/rospy/impl/tcpros_base.py @@ -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)