udp_socket_session.h
Go to the documentation of this file.
00001 
00034 #ifndef ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H
00035 #define ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H
00036 
00037 #include <iostream>
00038 #include <boost/bind.hpp>
00039 #include <boost/asio.hpp>
00040 
00041 #include <ros/ros.h>
00042 
00043 #include "rosserial_server/session.h"
00044 #include "rosserial_server/udp_stream.h"
00045 
00046 
00047 namespace rosserial_server
00048 {
00049 
00050 using boost::asio::ip::udp;
00051 
00052 class UdpSocketSession : public Session<UdpStream>
00053 {
00054 public:
00055   UdpSocketSession(boost::asio::io_service& io_service,
00056                    udp::endpoint server_endpoint,
00057                    udp::endpoint client_endpoint)
00058     : Session(io_service), timer_(io_service),
00059       server_endpoint_(server_endpoint), client_endpoint_(client_endpoint)
00060   {
00061     ROS_INFO_STREAM("rosserial_server UDP session created between " << server_endpoint << " and " << client_endpoint);
00062     check_connection();
00063   }
00064 
00065 private:
00066   void check_connection()
00067   {
00068     if (!is_active())
00069     {
00070       socket().open(server_endpoint_, client_endpoint_);
00071       start();
00072     }
00073 
00074     // Every second, check again if the connection should be reinitialized,
00075     // if the ROS node is still up.
00076     if (ros::ok())
00077     {
00078       timer_.expires_from_now(boost::posix_time::milliseconds(2000));
00079       timer_.async_wait(boost::bind(&UdpSocketSession::check_connection, this));
00080     }
00081   }
00082 
00083   boost::asio::deadline_timer timer_;
00084   udp::endpoint server_endpoint_;
00085   udp::endpoint client_endpoint_;
00086 };
00087 
00088 }  // namespace
00089 
00090 #endif  // ROSSERIAL_SERVER_UDP_SOCKET_SESSION_H


rosserial_server
Author(s): Mike Purvis
autogenerated on Sat Oct 7 2017 03:08:51