transport_udp.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 #ifndef ROSCPP_TRANSPORT_UDP_H
00036 #define ROSCPP_TRANSPORT_UDP_H
00037 
00038 #include <ros/types.h>
00039 #include <ros/transport/transport.h>
00040 
00041 #include <boost/thread/mutex.hpp>
00042 #include "ros/io.h"
00043 #include <ros/common.h>
00044 
00045 namespace ros
00046 {
00047 
00048 class TransportUDP;
00049 typedef boost::shared_ptr<TransportUDP> TransportUDPPtr;
00050 
00051 class PollSet;
00052 
00053 #define ROS_UDP_DATA0 0
00054 #define ROS_UDP_DATAN 1
00055 #define ROS_UDP_PING 2
00056 #define ROS_UDP_ERR 3
00057 typedef struct TransportUDPHeader {
00058   uint32_t connection_id_;
00059   uint8_t op_;
00060   uint8_t message_id_;
00061   uint16_t block_;
00062 } TransportUDPHeader;
00063 
00067 class ROSCPP_DECL TransportUDP : public Transport
00068 {
00069 public:
00070   enum Flags
00071   {
00072     SYNCHRONOUS = 1<<0,
00073   };
00074 
00075   TransportUDP(PollSet* poll_set, int flags = 0, int max_datagram_size = 0);
00076   virtual ~TransportUDP();
00077 
00084   bool connect(const std::string& host, int port, int conn_id);
00085 
00089   std::string getClientURI();
00090 
00095   bool createIncoming(int port, bool is_server);
00099   TransportUDPPtr createOutgoing(std::string host, int port, int conn_id, int max_datagram_size);
00103   int getServerPort() const {return server_port_;}
00104 
00105   // overrides from Transport
00106   virtual int32_t read(uint8_t* buffer, uint32_t size);
00107   virtual int32_t write(uint8_t* buffer, uint32_t size);
00108 
00109   virtual void enableWrite();
00110   virtual void disableWrite();
00111   virtual void enableRead();
00112   virtual void disableRead();
00113 
00114   virtual void close();
00115 
00116   virtual std::string getTransportInfo();
00117 
00118   virtual bool requiresHeader() {return false;}
00119 
00120   virtual const char* getType() {return "UDPROS";}
00121 
00122   int getMaxDatagramSize() const {return max_datagram_size_;}
00123 
00124 private:
00128   bool initializeSocket();
00129 
00135   bool setSocket(int sock);
00136 
00137   void socketUpdate(int events);
00138 
00139   socket_fd_t sock_;
00140   bool closed_;
00141   boost::mutex close_mutex_;
00142 
00143   bool expecting_read_;
00144   bool expecting_write_;
00145 
00146   bool is_server_;
00147   sockaddr_in server_address_;
00148   int server_port_;
00149 
00150   std::string cached_remote_host_;
00151 
00152   PollSet* poll_set_;
00153   int flags_;
00154 
00155   uint32_t connection_id_;
00156   uint8_t current_message_id_;
00157   uint16_t total_blocks_;
00158   uint16_t last_block_;
00159 
00160   uint32_t max_datagram_size_;
00161 
00162   uint8_t* data_buffer_;
00163   uint8_t* data_start_;
00164   uint32_t data_filled_;
00165 
00166   uint8_t* reorder_buffer_;
00167   uint8_t* reorder_start_;
00168   TransportUDPHeader reorder_header_;
00169   uint32_t reorder_bytes_;
00170 };
00171 
00172 }
00173 
00174 #endif // ROSCPP_TRANSPORT_UDP_H
00175 


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Fri Aug 28 2015 12:33:11