async_read_buffer.h
Go to the documentation of this file.
00001 
00034 #ifndef ROSSERIAL_SERVER_ASYNC_READ_BUFFER_H
00035 #define ROSSERIAL_SERVER_ASYNC_READ_BUFFER_H
00036 
00037 #include <boost/bind.hpp>
00038 #include <boost/asio.hpp>
00039 #include <boost/function.hpp>
00040 
00041 #include <ros/ros.h>
00042 
00043 namespace rosserial_server
00044 {
00045 
00046 template<typename AsyncReadStream>
00047 class AsyncReadBuffer
00048 {
00049 public:
00050   AsyncReadBuffer(AsyncReadStream& s, size_t capacity,
00051                   boost::function<void(const boost::system::error_code&)> error_callback)
00052        : stream_(s), error_callback_(error_callback) {
00053     mem_.resize(capacity);
00054     ROS_ASSERT_MSG(error_callback_, "Bad error callback passed to read buffer.");
00055   }
00056 
00057   void read(size_t read_count, boost::function<void(ros::serialization::IStream&)> callback) {
00058      if (read_count > mem_.size()) {
00059       // Insufficient room in the buffer for the requested bytes,
00060       ROS_ERROR_STREAM_NAMED("async_read", "Requested to read " << read_count << " bytes, but buffer capacity is only " << mem_.size() << ".");
00061       error_callback_(boost::system::errc::make_error_code(boost::system::errc::no_buffer_space));
00062       return;
00063     }
00064 
00065     boost::asio::async_read(stream_,
00066         boost::asio::buffer(&mem_[0], read_count),
00067         boost::asio::transfer_at_least(read_count),
00068         boost::bind(&AsyncReadBuffer::read_cb, this,
00069                     boost::asio::placeholders::error,
00070                     boost::asio::placeholders::bytes_transferred,
00071                     callback));
00072   }
00073 
00074 private:
00075   void read_cb(const boost::system::error_code& error, size_t bytes_transferred,
00076                boost::function<void(ros::serialization::IStream&)> callback) {
00077     if (error)
00078     {
00079       if (error == boost::asio::error::operation_aborted)
00080       {
00081         // Special case for operation_aborted. The abort callback comes when the owning Session
00082         // is in the middle of teardown, which means the callback is no longer valid and calling
00083         // it would be a segfault.
00084       }
00085       else
00086       {
00087         error_callback_(error);
00088       }
00089     } else {
00090       ROS_DEBUG_STREAM_NAMED("async_read", "Transferred " << bytes_transferred << " byte(s).");
00091 
00092       ros::serialization::IStream stream(&mem_[0], bytes_transferred);
00093       ROS_ASSERT_MSG(callback, "Bad read callback function.");
00094       callback(stream);
00095     }
00096   }
00097 
00098   AsyncReadStream& stream_;
00099   std::vector<uint8_t> mem_;
00100   boost::function<void(const boost::system::error_code&)> error_callback_;
00101 };
00102 
00103 }  // namespace
00104 
00105 #endif  // ROSSERIAL_SERVER_ASYNC_READ_BUFFER_H


rosserial_server
Author(s): Mike Purvis
autogenerated on Thu Jun 6 2019 19:56:34