tcp.hpp
Go to the documentation of this file.
00001 //
00002 // TCP.hpp
00003 //
00004 // Ethernet TCP data sender/receiver.
00005 //
00006 // Sick AG
00007 //
00008 // HISTORY
00009 //
00010 // 1.0.0        10.11.2011, VWi
00011 //                      Initial version.
00012 //
00013 
00014 
00015 
00016 #ifndef TCP_HPP
00017 #define TCP_HPP
00018 
00019 #include "sick_scan/tcp/BasicDatatypes.hpp"
00020 #include <sys/socket.h> /* for socket(), bind(), and connect() */
00021 #include <arpa/inet.h>  /* for sockaddr_in and inet_ntoa() */
00022 #include "sick_scan/tcp/Mutex.hpp"
00023 #include "sick_scan/tcp/SickThread.hpp"
00024 #include <list>
00025 
00026 
00027 //
00028 // Sender and receiver for data over a TCP connection. Client!
00029 //
00030 class Tcp
00031 {
00032 public:
00033         Tcp();
00034         ~Tcp();
00035 
00036         // Opens the connection.
00037         bool open(std::string ipAddress, UINT16 port, bool enableVerboseDebugOutput = false);
00038         bool open(UINT32 ipAddress, UINT16 port, bool enableVerboseDebugOutput = false);
00039         void close();                                                                                   // Closes the connection, if it was open.
00040         bool isOpen();  // "True" if a connection is currently open.
00041         bool write(UINT8* buffer, UINT32 numberOfBytes);                // Writes numberOfBytes bytes to the open connection.
00042         std::string readString(UINT8 delimiter);                                // Reads a string, if available. Strings are separated with the delimiter char.
00043 
00044         // Buffer read function (for polling)
00045         UINT32 getNumReadableBytes();                                                   // Returns the number of bytes currently available for reading.
00046         UINT32 read(UINT8* buffer, UINT32 bufferLen);                   // Reads up to bufferLen bytes from the buffer.
00047 
00048         // Read callbacks (for being called when data is available)
00049         typedef void (*ReadFunction)(void* obj, UINT8* inputBuffer, UINT32& numBytes);  //  ReadFunction
00050         void setReadCallbackFunction(ReadFunction readFunction, void* obj);
00051 
00052         // Information if the connection is disconnected.
00053         typedef void (*DisconnectFunction)(void* obj);                                                          //  Called on disconnect
00054         void setDisconnectCallbackFunction(DisconnectFunction discFunction, void* obj);
00055 
00056         
00057 private:
00058         bool m_longStringWarningPrinted;
00059         std::string m_rxString;                                         // fuer readString()
00060         bool isClientConnected_unlocked();
00061         std::list<unsigned char> m_rxBuffer;            // Main input buffer
00062         void stopReadThread();
00063         void startServerThread();
00064         void stopServerThread();
00065         
00066     struct sockaddr_in m_serverAddr;                            // Local address
00067         bool m_beVerbose;
00068         Mutex m_socketMutex;
00069 #ifndef _MSC_VER        
00070         INT32 m_connectionSocket;       // Socket, wenn wir der Client sind (z.B. Verbindung zum Scanner)
00071 #else
00072         SOCKET m_connectionSocket;      // Socket, wenn wir der Client sind (z.B. Verbindung zum Scanner)
00073 
00074 #endif
00075         void readThreadFunction(bool& endThread, UINT16& waitTimeMs);
00076         SickThread<Tcp, &Tcp::readThreadFunction> m_readThread;
00077         INT32 readInputData();
00078         
00079         ReadFunction m_readFunction;            // Receive callback
00080         void* m_readFunctionObjPtr;                     // Object of the Receive callback
00081         DisconnectFunction m_disconnectFunction;
00082         void* m_disconnectFunctionObjPtr;       // Object of the Disconect callback
00083 
00084 
00085 /*      
00086         bool m_beVerbose;       ///< Enable *very* verbose debug output
00087         asio::io_service m_io_service;
00088         asio::ip::tcp::socket* m_socket;
00089 
00090         boost::thread* m_readThreadPtr;
00091         bool m_readThreadIsRunning;
00092         bool m_readThreadShouldRun;
00093         boost::condition m_readThreadCondition; ///< Condition to wait for the spawned thread to be started
00094         boost::mutex m_readThreadMutex;                 ///< Mutex to wait for the spawned thread to be started
00095         void readThread();                                              ///< Receive-thread for incoming scans.
00096         INT32 readInputData();
00097 
00101         EventMonitor* m_disconnectedEventMonitor;
00102 
00106         EventMonitor::Mask m_disconnectedEventMask;
00107 
00108         BoundedBuffer<UINT8> m_rxBuffer;                ///< Main input buffer
00109         std::string m_rxString;                                 ///< Eingangspuffer fuer Strings
00110         bool m_longStringWarningPrinted;
00111 */
00112 };
00113 
00114 #endif // TCP_HPP


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Tue Jul 9 2019 05:05:35