transport.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #ifndef ROSCPP_TRANSPORT_H
37 #define ROSCPP_TRANSPORT_H
38 
39 #include <ros/types.h>
40 //#include <boost/function.hpp>
41 #include <memory>
42 #include <memory>
43 #include <vector>
44 
45 namespace roswrap
46 {
47 
48 class Transport;
49 typedef std::shared_ptr<Transport> TransportPtr;
50 
51 class Header;
52 
56 class Transport : public std::enable_shared_from_this<Transport>
57 {
58 public:
59  Transport();
60  virtual ~Transport() {}
61 
68  virtual int32_t read(uint8_t* buffer, uint32_t size) = 0;
75  virtual int32_t write(uint8_t* buffer, uint32_t size) = 0;
76 
80  virtual void enableWrite() = 0;
84  virtual void disableWrite() = 0;
85 
89  virtual void enableRead() = 0;
93  virtual void disableRead() = 0;
94 
98  virtual void close() = 0;
99 
104  virtual const char* getType() = 0;
105 
106  typedef std::function<void(const TransportPtr&)> Callback;
114  void setReadCallback(const Callback& cb) { read_cb_ = cb; }
118  void setWriteCallback(const Callback& cb) { write_cb_ = cb; }
119 
123  virtual std::string getTransportInfo() = 0;
124 
128  virtual bool requiresHeader() {return true;}
129 
133  virtual void parseHeader(const Header& header) { (void)header; }
134 
135 protected:
139 
143  bool isHostAllowed(const std::string &host) const;
144 
149 
150 private:
152  std::vector<std::string> allowed_hosts_;
153 };
154 
155 }
156 
157 #endif // ROSCPP_TRANSPORT_H
roswrap::Transport::setWriteCallback
void setWriteCallback(const Callback &cb)
Set the function to call when there is space available to write on this transport.
Definition: transport.h:118
roswrap::Transport::requiresHeader
virtual bool requiresHeader()
Returns a boolean to indicate if the transport mechanism is reliable or not.
Definition: transport.h:128
roswrap::Transport::getType
virtual const char * getType()=0
Return a string that details the type of transport (Eg. TCPROS)
Header
roswrap::Transport::write
virtual int32_t write(uint8_t *buffer, uint32_t size)=0
Write a number of bytes from the supplied buffer. Not guaranteed to actually write that number of byt...
roswrap::Transport::disableRead
virtual void disableRead()=0
Disable reading on this transport. Allows derived classes to, for example, disable read polling for a...
roswrap::Transport::~Transport
virtual ~Transport()
Definition: transport.h:60
roswrap::Transport::enableWrite
virtual void enableWrite()=0
Enable writing on this transport. Allows derived classes to, for example, enable write polling for as...
roswrap::Transport::close
virtual void close()=0
Close this transport. Once this call has returned, writing on this transport should always return an ...
roswrap::Transport::read
virtual int32_t read(uint8_t *buffer, uint32_t size)=0
Read a number of bytes into the supplied buffer. Not guaranteed to actually read that number of bytes...
roswrap::Transport::setReadCallback
void setReadCallback(const Callback &cb)
Set the function to call when there is data available to be read by this transport.
Definition: transport.h:114
roswrap::Transport::read_cb_
Callback read_cb_
Definition: transport.h:137
roswrap::TransportPtr
std::shared_ptr< Transport > TransportPtr
Definition: connection.h:56
roswrap::Transport::parseHeader
virtual void parseHeader(const Header &header)
Provides an opportunity for transport-specific options to come in through the header.
Definition: transport.h:133
roswrap::Transport::setDisconnectCallback
void setDisconnectCallback(const Callback &cb)
Set the function to call when this transport has disconnected, either through a call to close()....
Definition: transport.h:110
roswrap::Transport::enableRead
virtual void enableRead()=0
Enable reading on this transport. Allows derived classes to, for example, enable read polling for asy...
roswrap::Transport::disconnect_cb_
Callback disconnect_cb_
Definition: transport.h:136
roswrap
Definition: param_modi.cpp:41
roswrap::Transport::isHostAllowed
bool isHostAllowed(const std::string &host) const
returns true if the transport is allowed to connect to the host passed to it.
roswrap::Transport::only_localhost_allowed_
bool only_localhost_allowed_
Definition: transport.h:151
roswrap::Transport::getTransportInfo
virtual std::string getTransportInfo()=0
Returns a string description of both the type of transport and who the transport is connected to.
roswrap::Transport::Transport
Transport()
roswrap::Header
Provides functionality to parse a connection header and retrieve values from it.
Definition: header.h:53
sick_scan_base.h
roswrap::Transport::Callback
std::function< void(const TransportPtr &)> Callback
Definition: transport.h:106
roswrap::Transport::write_cb_
Callback write_cb_
Definition: transport.h:138
roswrap::message_traits::header
std_msgs::Header * header(M &m)
returns Header<M>::pointer(m);
Definition: message_traits.h:281
roswrap::Transport
Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory,...
Definition: transport.h:56
roswrap::Transport::allowed_hosts_
std::vector< std::string > allowed_hosts_
Definition: transport.h:152
roswrap::Transport::isOnlyLocalhostAllowed
bool isOnlyLocalhostAllowed() const
returns true if this transport is only allowed to talk to localhost
Definition: transport.h:148
roswrap::Transport::disableWrite
virtual void disableWrite()=0
Disable writing on this transport. Allows derived classes to, for example, disable write polling for ...


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:12