30 #include <boost/asio.hpp> 48 std::string recvr_ip_addr;
54 ROS_INFO_STREAM(
"Oem7Net " << (T::v4().protocol() == IPPROTO_TCP ?
"TCP" :
"UDP") <<
55 "['" << recvr_ip_addr <<
"' : " << recvr_port <<
"]");
57 boost::system::error_code err;
60 this->
endpoint_.connect(
typename T::endpoint(boost::asio::ip::address::from_string(recvr_ip_addr), recvr_port), err);
65 static const std::string CONN_PRIMER(
"\r\n");
69 virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code& err)
71 boost::array<boost::asio::mutable_buffer, 1> bufs = {buf};
72 return this->
endpoint_.receive(bufs, 0, err);
75 virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code& err)
77 const boost::array<boost::asio::const_buffer, 1> bufs = {buf};
78 return this->
endpoint_.send(bufs, 0, err);
T 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
virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code &err)