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 <pthread.h>
00061     #include <netdb.h>       // getnameinfo in network.cpp
00062     #include <netinet/in.h>  // sockaddr_in in network.cpp
00063         #include <netinet/tcp.h> // TCP_NODELAY in transport/transport_tcp.cpp
00064 #endif
00065 
00066 /*****************************************************************************
00067 ** Cross Platform Macros
00068 *****************************************************************************/
00069 
00070 #ifdef WIN32
00071     #define getpid _getpid
00072         #define ROS_INVALID_SOCKET INVALID_SOCKET
00073         #define ROS_SOCKETS_SHUT_RDWR SD_BOTH /* Used by ::shutdown() */
00074         #define ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN WSAEWOULDBLOCK
00075         #ifndef POLLRDNORM
00076                 #define POLLRDNORM  0x0100 /* mapped to read fds_set */
00077         #endif
00078         #ifndef POLLRDBAND
00079                 #define POLLRDBAND  0x0200 /* mapped to exception fds_set */
00080         #endif
00081         #ifndef POLLIN
00082                 #define POLLIN      (POLLRDNORM | POLLRDBAND) /* There is data to read.  */
00083         #endif
00084         #ifndef POLLPRI
00085                 #define POLLPRI     0x0400 /* There is urgent data to read.  */
00086         #endif
00087 
00088         #ifndef POLLWRNORM
00089                 #define POLLWRNORM  0x0010 /* mapped to write fds_set */
00090         #endif
00091         #ifndef POLLOUT
00092                 #define POLLOUT     (POLLWRNORM) /* Writing now will not block.  */
00093         #endif
00094         #ifndef POLLWRBAND
00095                 #define POLLWRBAND  0x0020 /* mapped to write fds_set */
00096         #endif
00097         #ifndef POLLERR
00098                 #define POLLERR     0x0001 /* Error condition.  */
00099         #endif
00100         #ifndef POLLHUP
00101                 #define POLLHUP     0x0002 /* Hung up.  */
00102         #endif
00103         #ifndef POLLNVAL
00104                 #define POLLNVAL    0x0004 /* Invalid polling request.  */
00105         #endif
00106 #else
00107         #define ROS_SOCKETS_SHUT_RDWR SHUT_RDWR /* Used by ::shutdown() */
00108         #define ROS_INVALID_SOCKET ((int) -1)
00109         #define ROS_SOCKETS_ASYNCHRONOUS_CONNECT_RETURN EINPROGRESS
00110 #endif
00111 
00112 /*****************************************************************************
00113 ** Namespaces
00114 *****************************************************************************/
00115 
00116 namespace ros {
00117 
00118 /*****************************************************************************
00119 ** Cross Platform Types
00120 *****************************************************************************/
00121 
00122 #ifdef WIN32
00123   typedef SOCKET socket_fd_t;
00124   typedef SOCKET signal_fd_t;
00125   /* poll emulation support */
00126   typedef struct socket_pollfd {
00127     socket_fd_t fd;      /* file descriptor */
00128     short events;     /* requested events */
00129     short revents;    /* returned events */
00130   } socket_pollfd;
00131 
00132   typedef unsigned long int nfds_t;
00133   #ifdef _MSC_VER
00134     typedef int pid_t; /* return type for windows' _getpid */
00135   #endif
00136 #else
00137   typedef int socket_fd_t;
00138   typedef int signal_fd_t;
00139   typedef struct pollfd socket_pollfd;
00140 #endif
00141 
00142 /*****************************************************************************
00143 ** Functions
00144 *****************************************************************************/
00145 
00146 ROSCPP_DECL int last_socket_error();
00147 ROSCPP_DECL const char* last_socket_error_string();
00148 ROSCPP_DECL bool last_socket_error_is_would_block();
00149 ROSCPP_DECL int poll_sockets(socket_pollfd *fds, nfds_t nfds, int timeout);
00150 ROSCPP_DECL int set_non_blocking(socket_fd_t &socket);
00151 ROSCPP_DECL int close_socket(socket_fd_t &socket);
00152 ROSCPP_DECL int create_signal_pair(signal_fd_t signal_pair[2]);
00153 
00154 /*****************************************************************************
00155 ** Inlines - almost direct api replacements, should stay fast.
00156 *****************************************************************************/
00157 
00163 inline void close_signal_pair(signal_fd_t signal_pair[2]) {
00164 #ifdef WIN32 // use a socket pair
00165         ::closesocket(signal_pair[0]);
00166         ::closesocket(signal_pair[1]);
00167 #else // use a socket pair on mingw or pipe pair on linux, either way, close works
00168         ::close(signal_pair[0]);
00169         ::close(signal_pair[1]);
00170 #endif
00171 }
00172 
00178 #ifdef _MSC_VER
00179         inline int write_signal(const signal_fd_t &signal, const char *buffer, const unsigned int &nbyte) {
00180                 return ::send(signal, buffer, nbyte, 0);
00181 //              return write(signal, buffer, nbyte);
00182         }
00183 #else
00184         inline ssize_t write_signal(const signal_fd_t &signal, const void *buffer, const size_t &nbyte) {
00185                 return write(signal, buffer, nbyte);
00186         }
00187 #endif
00188 
00189 
00195 #ifdef _MSC_VER
00196         inline int read_signal(const signal_fd_t &signal, char *buffer, const unsigned int &nbyte) {
00197                 return ::recv(signal, buffer, nbyte, 0);
00198 //              return _read(signal, buffer, nbyte);
00199         }
00200 #else
00201         inline ssize_t read_signal(const signal_fd_t &signal, void *buffer, const size_t &nbyte) {
00202                 return read(signal, buffer, nbyte);
00203         }
00204 #endif
00205 
00206 } // namespace ros
00207 
00208 #endif /* ROSCPP_IO_H_ */
00209 


roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com, Troy Straszheim straszheim@willowgarage.com
autogenerated on Sat Dec 28 2013 17:35:52