Program Listing for File socket_server_pos.hpp

Return to documentation for file (/tmp/ws/src/ecl_core/ecl_devices/include/ecl/devices/socket_server_pos.hpp)

/*****************************************************************************
** Ifdefs
*****************************************************************************/

#ifndef ECL_DEVICES_SOCKET_SERVER_POS_HPP_
#define ECL_DEVICES_SOCKET_SERVER_POS_HPP_

/*****************************************************************************
** Cross platform
*****************************************************************************/

#include <ecl/config/ecl.hpp>
#ifndef ECL_IS_APPLE
#ifdef ECL_IS_POSIX

/*****************************************************************************
** Includes
*****************************************************************************/

#include <arpa/inet.h> // inet_addr()
#include <sys/ioctl.h> // used in remaining()
#include <errno.h>
#include <sys/socket.h>

#include "detail/socket_error_handler_pos.hpp"
#include "detail/socket_exception_handler_pos.hpp"
#include "traits.hpp"

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ecl {

/*****************************************************************************
** Interface [SocketServer]
*****************************************************************************/
class SocketServer {
public:
    /*********************
    ** C&D
    **********************/
    SocketServer() : is_open(false) {};
    SocketServer(const unsigned int &port_number);
    virtual ~SocketServer() { close(); };
    /*********************
    ** Configuration
    **********************/
    bool open( const unsigned int& port_number );
    void close() { is_open = false; ::close(socket_fd); }

    bool open() const { return is_open; }

    /*********************
    ** Writing
    **********************/
    long write(const char &c) { return write(&c,1); }

    long write(const char *s, unsigned long n);

    void flush() {}

    /*********************
    ** Reading
    **********************/
    long remaining();
    long read(char &c) { return read(&c,1); }
    long read(char *s, const unsigned long &n);
    long peek(char*s, const unsigned long &n);

    /*********************
    ** Socket Specific
    **********************/
    int listen();

    const Error& error() const { return error_handler; }

private:
    int port;
    int socket_fd;
    int client_socket_fd;
    bool is_open;
    Error error_handler;
};

/*****************************************************************************
** Traits [Serial]
*****************************************************************************/
template <>
class is_sink<SocketServer> : public True {};

template <>
class is_source<SocketServer> : public True {};

template <>
class is_sourcesink<SocketServer> : public True {};

} // namespace ecl

#endif  /* ECL_IS_POSIX */
#endif  /* !ECL_IS_APPLE */

#endif /* ECL_DEVICES_SOCKET_SERVER_POS_HPP_ */