transport.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014, Open Source Robotics Foundation, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include "ros/transport/transport.h"
00036 #include "ros/console.h"
00037 #include <netinet/in.h>
00038 #include <sys/socket.h>
00039 #include <netdb.h>
00040 
00041 #if !defined(__ANDROID__)
00042 #include <ifaddrs.h>
00043 #endif
00044 
00045 #ifndef NI_MAXHOST
00046   #define NI_MAXHOST 1025
00047 #endif
00048 
00049 namespace ros
00050 {
00051 
00052 Transport::Transport()
00053 : only_localhost_allowed_(false)
00054 {
00055   char *ros_ip_env = NULL, *ros_hostname_env = NULL;
00056   #ifdef _MSC_VER
00057     _dupenv_s(&ros_ip_env, NULL, "ROS_IP");
00058     _dupenv_s(&ros_hostname_env, NULL, "ROS_HOSTNAME");
00059   #else
00060     ros_ip_env = getenv("ROS_IP");
00061     ros_hostname_env = getenv("ROS_HOSTNAME");
00062   #endif
00063   if (ros_hostname_env && !strcmp(ros_hostname_env, "localhost"))
00064     only_localhost_allowed_ = true;
00065   else if (ros_ip_env && !strncmp(ros_ip_env, "127.", 4))
00066     only_localhost_allowed_ = true;
00067   else if (ros_ip_env && !strcmp(ros_ip_env, "::1"))
00068     only_localhost_allowed_ = true;
00069 
00070   char our_hostname[256] = {0};
00071   gethostname(our_hostname, sizeof(our_hostname)-1);
00072   allowed_hosts_.push_back(std::string(our_hostname));
00073   allowed_hosts_.push_back("localhost");
00074 #if !defined(__ANDROID__)
00075   // for ipv4 loopback, we'll explicitly search for 127.* in isHostAllowed()
00076   // now we need to iterate all local interfaces and add their addresses
00077   // from the getifaddrs manpage:  (maybe something similar for windows ?) 
00078   ifaddrs *ifaddr;
00079   if (-1 == getifaddrs(&ifaddr))
00080   {
00081     ROS_ERROR("getifaddr() failed");
00082     return;
00083   }
00084   for (ifaddrs *ifa = ifaddr; ifa; ifa = ifa->ifa_next)
00085   {
00086     if(NULL == ifa->ifa_addr)
00087       continue; // ifa_addr can be NULL
00088     int family = ifa->ifa_addr->sa_family;
00089     if (family != AF_INET && family != AF_INET6)
00090       continue; // we're only looking for IP addresses
00091     char addr[NI_MAXHOST] = {0};
00092     if (getnameinfo(ifa->ifa_addr,
00093                     (family == AF_INET) ? sizeof(sockaddr_in)
00094                                         : sizeof(sockaddr_in6),
00095                     addr, NI_MAXHOST,
00096                     NULL, 0, NI_NUMERICHOST))
00097     {
00098       ROS_ERROR("getnameinfo() failed");
00099       continue;
00100     }
00101     allowed_hosts_.push_back(std::string(addr));
00102   }
00103   freeifaddrs(ifaddr);
00104 #endif
00105 }
00106 
00107 bool Transport::isHostAllowed(const std::string &host) const
00108 {
00109   if (!only_localhost_allowed_)
00110     return true; // doesn't matter; we'll connect to anybody
00111 
00112   if (host.length() >= 4 && host.substr(0, 4) == std::string("127."))
00113     return true; // ipv4 localhost
00114   // now, loop through the list of valid hostnames and see if we find it
00115   for (std::vector<std::string>::const_iterator it = allowed_hosts_.begin(); 
00116        it != allowed_hosts_.end(); ++it)
00117   {
00118     if (host == *it)
00119       return true; // hooray
00120   }
00121   ROS_WARN("ROS_HOSTNAME / ROS_IP is set to only allow local connections, so "
00122            "a requested connection to '%s' is being rejected.", host.c_str());
00123   return false; // sadness
00124 }
00125 
00126 }
00127 


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:44:47