34 #ifndef ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H 35 #define ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H 38 #include <boost/bind.hpp> 39 #include <boost/asio.hpp> 50 using boost::asio::ip::udp;
56 udp::endpoint server_endpoint,
57 udp::endpoint client_endpoint)
61 ROS_INFO_STREAM(
"rosserial_server UDP session created between " << server_endpoint <<
" and " << client_endpoint);
78 timer_.expires_from_now(boost::posix_time::milliseconds(2000));
90 #endif // ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H udp::endpoint server_endpoint_
UdpSocketSession(boost::asio::io_service &io_service, udp::endpoint server_endpoint, udp::endpoint client_endpoint)
Adapter which allows a single-ended UDP connection to present the stream interface.
Class representing a session between this node and a templated rosserial client.
boost::asio::deadline_timer timer_
udp::endpoint client_endpoint_
void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
#define ROS_INFO_STREAM(args)