io.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, 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 ** Ifdefs
00036 *****************************************************************************/
00037 #ifndef ROSCPP_IO_H_
00038 #define ROSCPP_IO_H_
00039 
00040 /*****************************************************************************
00041 ** Includes
00042 *****************************************************************************/
00043 
00044 #include <string>
00045 #include "common.h"
00046 
00047 #ifdef WIN32
00048         #include <winsock2.h> // For struct timeval
00049         #include <ws2tcpip.h> // Must be after winsock2.h because MS didn't put proper inclusion guards in their headers.
00050         #include <sys/types.h>
00051         #include <io.h>
00052         #include <fcntl.h>
00053         #include <process.h> // for _getpid
00054 #else
00055         #include <poll.h> // should get cmake to explicitly check for poll.h?
00056         #include <sys/poll.h>
00057         #include <arpa/inet.h>
00058         #include <netdb.h>
00059     #include <unistd.h>
00060     #include <netdb.h>       // getnameinfo in network.cpp
00061     #include <netinet/in.h>  // sockaddr_in in network.cpp
00062         #include <netinet/tcp.h> // TCP_NODELAY in transport/transport_tcp.cpp
00063 #endif
00064 
00065 /*****************************************************************************
00066 ** Cross Platform Macros
00067 *****************************************************************************/
00068 
00069 #ifdef WIN32
00070     #define getpid _getpid
00071         #define ROS_INVALID_SOCKET INVALID_SOCKET
00072         #define ROS_SOCKETS_SHUT_RDWR SD_BOTH /* Used by ::shutdown() */
00073         #define ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN WSAEWOULDBLOCK
00074         #ifndef POLLRDNORM
00075                 #define POLLRDNORM  0x0100 /* mapped to read fds_set */
00076         #endif
00077         #ifndef POLLRDBAND
00078                 #define POLLRDBAND  0x0200 /* mapped to exception fds_set */
00079         #endif
00080         #ifndef POLLIN
00081                 #define POLLIN      (POLLRDNORM | POLLRDBAND) /* There is data to read.  */
00082         #endif
00083         #ifndef POLLPRI
00084                 #define POLLPRI     0x0400 /* There is urgent data to read.  */
00085         #endif
00086 
00087         #ifndef POLLWRNORM
00088                 #define POLLWRNORM  0x0010 /* mapped to write fds_set */
00089         #endif
00090         #ifndef POLLOUT
00091                 #define POLLOUT     (POLLWRNORM) /* Writing now will not block.  */
00092         #endif
00093         #ifndef POLLWRBAND
00094                 #define POLLWRBAND  0x0020 /* mapped to write fds_set */
00095         #endif
00096         #ifndef POLLERR
00097                 #define POLLERR     0x0001 /* Error condition.  */
00098         #endif
00099         #ifndef POLLHUP
00100                 #define POLLHUP     0x0002 /* Hung up.  */
00101         #endif
00102         #ifndef POLLNVAL
00103                 #define POLLNVAL    0x0004 /* Invalid polling request.  */
00104         #endif
00105 #else
00106         #define ROS_SOCKETS_SHUT_RDWR SHUT_RDWR /* Used by ::shutdown() */
00107         #define ROS_INVALID_SOCKET ((int) -1)
00108         #define ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN EINPROGRESS
00109 #endif
00110 
00111 /*****************************************************************************
00112 ** Namespaces
00113 *****************************************************************************/
00114 
00115 namespace ros {
00116 
00117 /*****************************************************************************
00118 ** Cross Platform Types
00119 *****************************************************************************/
00120 
00121 #ifdef WIN32
00122   typedef SOCKET socket_fd_t;
00123   typedef SOCKET signal_fd_t;
00124   /* poll emulation support */
00125   typedef struct socket_pollfd {
00126     socket_fd_t fd;      /* file descriptor */
00127     short events;     /* requested events */
00128     short revents;    /* returned events */
00129   } socket_pollfd;
00130 
00131   typedef unsigned long int nfds_t;
00132   #ifdef _MSC_VER
00133     typedef int pid_t; /* return type for windows' _getpid */
00134   #endif
00135 #else
00136   typedef int socket_fd_t;
00137   typedef int signal_fd_t;
00138   typedef struct pollfd socket_pollfd;
00139 #endif
00140 
00141 /*****************************************************************************
00142 ** Functions
00143 *****************************************************************************/
00144 
00145 ROSCPP_DECL int last_socket_error();
00146 ROSCPP_DECL const char* last_socket_error_string();
00147 ROSCPP_DECL bool last_socket_error_is_would_block();
00148 ROSCPP_DECL int poll_sockets(socket_pollfd *fds, nfds_t nfds, int timeout);
00149 ROSCPP_DECL int set_non_blocking(socket_fd_t &socket);
00150 ROSCPP_DECL int close_socket(socket_fd_t &socket);
00151 ROSCPP_DECL int create_signal_pair(signal_fd_t signal_pair[2]);
00152 
00153 /*****************************************************************************
00154 ** Inlines - almost direct api replacements, should stay fast.
00155 *****************************************************************************/
00156 
00162 inline void close_signal_pair(signal_fd_t signal_pair[2]) {
00163 #ifdef WIN32 // use a socket pair
00164         ::closesocket(signal_pair[0]);
00165         ::closesocket(signal_pair[1]);
00166 #else // use a socket pair on mingw or pipe pair on linux, either way, close works
00167         ::close(signal_pair[0]);
00168         ::close(signal_pair[1]);
00169 #endif
00170 }
00171 
00177 #ifdef _MSC_VER
00178         inline int write_signal(const signal_fd_t &signal, const char *buffer, const unsigned int &nbyte) {
00179                 return ::send(signal, buffer, nbyte, 0);
00180 //              return write(signal, buffer, nbyte);
00181         }
00182 #else
00183         inline ssize_t write_signal(const signal_fd_t &signal, const void *buffer, const size_t &nbyte) {
00184                 return write(signal, buffer, nbyte);
00185         }
00186 #endif
00187 
00188 
00194 #ifdef _MSC_VER
00195         inline int read_signal(const signal_fd_t &signal, char *buffer, const unsigned int &nbyte) {
00196                 return ::recv(signal, buffer, nbyte, 0);
00197 //              return _read(signal, buffer, nbyte);
00198         }
00199 #else
00200         inline ssize_t read_signal(const signal_fd_t &signal, void *buffer, const size_t &nbyte) {
00201                 return read(signal, buffer, nbyte);
00202         }
00203 #endif
00204 
00205 } // namespace ros
00206 
00207 #endif /* ROSCPP_IO_H_ */
00208 


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:46:44