29 #include <boost/asio.hpp>    60       std::string oem7_file_name;;
    61       nh.
getParam(
"oem7_file_name", oem7_file_name);
    65       oem7_file_.open(oem7_file_name, std::ios::in | std::ios::binary);
    66       int errno_value = errno; 
    69         ROS_ERROR_STREAM(
"Could not open '" << oem7_file_name << 
"'; error= " << errno_value << 
" '"    70                                             << strerror(errno_value) << 
"'");
    81     virtual bool read( boost::asio::mutable_buffer buf, 
size_t& rlen)
    92       if(num_byte_read_ == 0)
    97       oem7_file_.read(boost::asio::buffer_cast<char*>(buf), boost::asio::buffer_size(buf));
    98       int errno_value = errno; 
   100       rlen = oem7_file_.gcount();
   101       num_byte_read_ += rlen;
   105         ROS_INFO_STREAM(
"No more input available. Read " << num_byte_read_ << 
" bytes." );
   112         ROS_ERROR_STREAM(
"Error " << errno_value << 
" reading input: '"  << strerror(errno_value) << 
"'" );
   125     virtual bool write(boost::asio::const_buffer buf)
 
virtual bool initialize(ros::NodeHandle &nh)
 
size_t num_byte_read_
Total number of bytes read from file. 
 
virtual bool write(boost::asio::const_buffer buf)
 
virtual bool read(boost::asio::mutable_buffer buf, size_t &rlen)
 
std::ifstream oem7_file_
Input. 
 
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
 
#define ROS_INFO_STREAM(args)
 
bool getParam(const std::string &key, std::string &s) const 
 
#define ROS_ERROR_STREAM(args)