udp_socket_session.h
Go to the documentation of this file.
1 
34 #ifndef ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H
35 #define ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H
36 
37 #include <iostream>
38 #include <boost/bind.hpp>
39 #include <boost/asio.hpp>
40 
41 #include <ros/ros.h>
42 
45 
46 
47 namespace rosserial_server
48 {
49 
50 using boost::asio::ip::udp;
51 
52 class UdpSocketSession : public Session<UdpStream>
53 {
54 public:
55  UdpSocketSession(boost::asio::io_service& io_service,
56  udp::endpoint server_endpoint,
57  udp::endpoint client_endpoint)
58  : Session(io_service), timer_(io_service),
59  server_endpoint_(server_endpoint), client_endpoint_(client_endpoint)
60  {
61  ROS_INFO_STREAM("rosserial_server UDP session created between " << server_endpoint << " and " << client_endpoint);
63  }
64 
65 private:
67  {
68  if (!is_active())
69  {
71  start();
72  }
73 
74  // Every second, check again if the connection should be reinitialized,
75  // if the ROS node is still up.
76  if (ros::ok())
77  {
78  timer_.expires_from_now(boost::posix_time::milliseconds(2000));
79  timer_.async_wait(boost::bind(&UdpSocketSession::check_connection, this));
80  }
81  }
82 
83  boost::asio::deadline_timer timer_;
84  udp::endpoint server_endpoint_;
85  udp::endpoint client_endpoint_;
86 };
87 
88 } // namespace
89 
90 #endif // ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H
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_
ROSCPP_DECL bool ok()
void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
Definition: udp_stream.h:61
#define ROS_INFO_STREAM(args)


rosserial_server
Author(s): Mike Purvis
autogenerated on Fri Jun 7 2019 22:02:58