transport_udp.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef ROSCPP_TRANSPORT_UDP_H
36 #define ROSCPP_TRANSPORT_UDP_H
37 
38 #include <ros/types.h>
40 
41 #include <boost/thread/mutex.hpp>
42 #include "ros/io.h"
43 #include <ros/common.h>
44 
45 namespace ros
46 {
47 
48 class TransportUDP;
50 
51 class PollSet;
52 
53 #define ROS_UDP_DATA0 0
54 #define ROS_UDP_DATAN 1
55 #define ROS_UDP_PING 2
56 #define ROS_UDP_ERR 3
57 typedef struct TransportUDPHeader {
58  uint32_t connection_id_;
59  uint8_t op_;
60  uint8_t message_id_;
61  uint16_t block_;
63 
67 class ROSCPP_DECL TransportUDP : public Transport
68 {
69 public:
70  enum Flags
71  {
72  SYNCHRONOUS = 1<<0,
73  };
74 
75  TransportUDP(PollSet* poll_set, int flags = 0, int max_datagram_size = 0);
76  virtual ~TransportUDP();
77 
84  bool connect(const std::string& host, int port, int conn_id);
85 
89  std::string getClientURI();
90 
95  bool createIncoming(int port, bool is_server);
99  TransportUDPPtr createOutgoing(std::string host, int port, int conn_id, int max_datagram_size);
103  int getServerPort() const {return server_port_;}
104 
105  // overrides from Transport
106  virtual int32_t read(uint8_t* buffer, uint32_t size);
107  virtual int32_t write(uint8_t* buffer, uint32_t size);
108 
109  virtual void enableWrite();
110  virtual void disableWrite();
111  virtual void enableRead();
112  virtual void disableRead();
113 
114  virtual void close();
115 
116  virtual std::string getTransportInfo();
117 
118  virtual bool requiresHeader() {return false;}
119 
120  virtual const char* getType() {return "UDPROS";}
121 
122  int getMaxDatagramSize() const {return max_datagram_size_;}
123 
124 private:
128  bool initializeSocket();
129 
135  bool setSocket(int sock);
136 
137  void socketUpdate(int events);
138 
140  bool closed_;
141  boost::mutex close_mutex_;
142 
145 
147  sockaddr_in server_address_;
148  sockaddr_in local_address_;
151 
152  std::string cached_remote_host_;
153 
155  int flags_;
156 
157  uint32_t connection_id_;
159  uint16_t total_blocks_;
160  uint16_t last_block_;
161 
163 
164  uint8_t* data_buffer_;
165  uint8_t* data_start_;
166  uint32_t data_filled_;
167 
168  uint8_t* reorder_buffer_;
169  uint8_t* reorder_start_;
171  uint32_t reorder_bytes_;
172 };
173 
174 }
175 
176 #endif // ROSCPP_TRANSPORT_UDP_H
177 
ros::TransportUDP::Flags
Flags
Definition: transport_udp.h:70
ros::TransportUDP::getServerPort
int getServerPort() const
Returns the port this transport is listening on.
Definition: transport_udp.h:103
ros::TransportUDP::flags_
int flags_
Definition: transport_udp.h:155
ros::TransportUDP::data_start_
uint8_t * data_start_
Definition: transport_udp.h:165
ros::TransportUDP
UDPROS transport.
Definition: transport_udp.h:67
boost::shared_ptr< TransportUDP >
ros::TransportUDP::getMaxDatagramSize
int getMaxDatagramSize() const
Definition: transport_udp.h:122
ros
ros::TransportUDPHeader
Definition: transport_udp.h:57
ros::TransportUDP::server_port_
int server_port_
Definition: transport_udp.h:149
ros::TransportUDPPtr
boost::shared_ptr< TransportUDP > TransportUDPPtr
Definition: forwards.h:60
ros::TransportUDP::local_port_
int local_port_
Definition: transport_udp.h:150
ros::TransportUDP::reorder_header_
TransportUDPHeader reorder_header_
Definition: transport_udp.h:170
ros::Transport
Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory,...
Definition: transport.h:55
ros::TransportUDP::expecting_read_
bool expecting_read_
Definition: transport_udp.h:143
ros::TransportUDP::requiresHeader
virtual bool requiresHeader()
Returns a boolean to indicate if the transport mechanism is reliable or not.
Definition: transport_udp.h:118
ros::TransportUDP::max_datagram_size_
uint32_t max_datagram_size_
Definition: transport_udp.h:162
ros::TransportUDP::reorder_start_
uint8_t * reorder_start_
Definition: transport_udp.h:169
ros::TransportUDPHeader::block_
uint16_t block_
Definition: transport_udp.h:61
ros::TransportUDP::reorder_bytes_
uint32_t reorder_bytes_
Definition: transport_udp.h:171
ros::TransportUDP::getType
virtual const char * getType()
Return a string that details the type of transport (Eg. TCPROS)
Definition: transport_udp.h:120
ros::TransportUDP::last_block_
uint16_t last_block_
Definition: transport_udp.h:160
ros::TransportUDP::close_mutex_
boost::mutex close_mutex_
Definition: transport_udp.h:141
ros::TransportUDP::connection_id_
uint32_t connection_id_
Definition: transport_udp.h:157
ros::TransportUDP::sock_
socket_fd_t sock_
Definition: transport_udp.h:139
ros::TransportUDP::local_address_
sockaddr_in local_address_
Definition: transport_udp.h:148
ros::TransportUDP::poll_set_
PollSet * poll_set_
Definition: transport_udp.h:154
ros::TransportUDP::data_buffer_
uint8_t * data_buffer_
Definition: transport_udp.h:164
ros::TransportUDP::reorder_buffer_
uint8_t * reorder_buffer_
Definition: transport_udp.h:168
ros::TransportUDP::cached_remote_host_
std::string cached_remote_host_
Definition: transport_udp.h:152
ros::socket_fd_t
int socket_fd_t
Definition: io.h:138
ros::TransportUDP::is_server_
bool is_server_
Definition: transport_udp.h:146
ros::TransportUDPHeader::connection_id_
uint32_t connection_id_
Definition: transport_udp.h:58
ros::TransportUDPHeader::op_
uint8_t op_
Definition: transport_udp.h:59
io.h
ros::TransportUDP::closed_
bool closed_
Definition: transport_udp.h:140
ros::TransportUDP::expecting_write_
bool expecting_write_
Definition: transport_udp.h:144
transport.h
ros::TransportUDPHeader::message_id_
uint8_t message_id_
Definition: transport_udp.h:60
types.h
ros::TransportUDPHeader
struct ros::TransportUDPHeader TransportUDPHeader
ros::TransportUDP::server_address_
sockaddr_in server_address_
Definition: transport_udp.h:147
ros::PollSet
Manages a set of sockets being polled through the poll() function call.
Definition: poll_set.h:57
ros::TransportUDP::current_message_id_
uint8_t current_message_id_
Definition: transport_udp.h:158
ros::TransportUDP::data_filled_
uint32_t data_filled_
Definition: transport_udp.h:166
ros::TransportUDP::total_blocks_
uint16_t total_blocks_
Definition: transport_udp.h:159


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44