30 #include <boost/asio.hpp>    47       std::string recvr_tty_name;
    52       ROS_INFO_STREAM(
"Oem7SerialPort['" << recvr_tty_name << 
"' : " << baud_rate << 
"]");
    55       boost::system::error_code err;
    66         boost::asio::serial_port_base::baud_rate baud_option(baud_rate);
    68         ROS_INFO_STREAM(
"Oem7SerialPort set_option baud_rate: '" << baud_option.value() << 
" : " << err);
    72     virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code& err)
    74       boost::array<boost::asio::mutable_buffer, 1> bufs = {buf};
    78     virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code& err)
    80       boost::array<boost::asio::const_buffer, 1> bufs = {buf};
 virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code &err)
 
boost::asio::serial_port endpoint_
boost::asio communication endoint; socket, serial port, etc. 
 
virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code &err)
 
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
 
#define ROS_INFO_STREAM(args)
 
bool getParam(const std::string &key, std::string &s) const