29 #include <boost/asio.hpp> 41 boost::asio::io_service
io_;
60 if(num_io_errors_ >= max_num_io_errors_)
62 ROS_ERROR_STREAM(
"Oem7Receiver: Max Num IO errors exceeded: " << max_num_io_errors_);
80 virtual size_t endpoint_read( boost::asio::mutable_buffer buf, boost::system::error_code& err) = 0;
86 virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code& err) = 0;
93 boost::system::error_code err;
116 this->nh_.
getParam(
"oem7_max_io_errors", max_num_io_errors_);
121 virtual bool read( boost::asio::mutable_buffer buf,
size_t& rlen)
127 boost::system::error_code err;
129 if(err.value() == boost::system::errc::success)
142 <<
"; endpoint open: " << endpoint_.is_open()
143 <<
" errors/max: " << num_io_errors_
151 virtual bool write(boost::asio::const_buffer buf)
158 boost::system::error_code err;
160 if(err.value() != boost::system::errc::success)
164 ROS_ERROR_STREAM(
"Oem7Receiver: write error: " << err.value() <<
"; endpoint open: " << endpoint_.is_open());
int num_io_errors_
Number of consecuitive io errors.
virtual bool initialize(ros::NodeHandle &h)
virtual bool read(boost::asio::mutable_buffer buf, size_t &rlen)
T endpoint_
boost::asio communication endoint; socket, serial port, etc.
int max_num_io_errors_
Number of consecutive io errors before declaring failure and quitting.
virtual bool write(boost::asio::const_buffer buf)
boost::asio::io_service io_
ROSCPP_DECL bool isShuttingDown()
virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code &err)=0
virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code &err)=0
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
virtual void endpoint_try_open()=0