serial_session.h
Go to the documentation of this file.
00001 
00034 #ifndef ROSSERIAL_SERVER_SERIAL_SESSION_H
00035 #define ROSSERIAL_SERVER_SERIAL_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 
00045 namespace rosserial_server
00046 {
00047 
00048 class SerialSession : public Session<boost::asio::serial_port>
00049 {
00050 public:
00051   SerialSession(boost::asio::io_service& io_service, std::string port, int baud)
00052     : Session(io_service), port_(port), baud_(baud), // io_service_(io_service),
00053       timer_(io_service), interval_(boost::posix_time::milliseconds(1000))
00054   {
00055     connect_with_reconnection();
00056   }
00057 
00058 private:
00059   ~SerialSession()
00060   {
00061     ROS_WARN("Serial session shutting down. Waiting 1 second for system state to settle.");
00062 
00063     boost::shared_ptr<boost::asio::deadline_timer> timer
00064           (new boost::asio::deadline_timer(
00065               socket().get_io_service(),
00066               boost::posix_time::seconds(1)));
00067 
00068     // The timer instance is only passed to the callback in order to keep it alive for the
00069     // required lifetime. When the callback completes, it goes out of scope and is destructed.
00070     timer->async_wait(
00071        boost::bind(&SerialSession::restart_session,
00072                    boost::ref(socket().get_io_service()), port_, baud_, timer));
00073   }
00074 
00075   static void restart_session(boost::asio::io_service& io_service, std::string port, int baud,
00076                               boost::shared_ptr<boost::asio::deadline_timer>& timer)
00077   {
00078     if (ros::ok()) {
00079       ROS_INFO("Recreating serial session.");
00080       new SerialSession(io_service, port, baud);
00081     } else {
00082       ROS_INFO("In shutdown, avoiding recreating serial session.");
00083     }
00084   }
00085 
00086   bool attempt_connection(bool log_errors = true)
00087   {
00088     if (log_errors) ROS_INFO("Opening serial port.");
00089     boost::system::error_code ec;
00090     socket().open(port_, ec);
00091     if (ec) {
00092       if (log_errors) ROS_ERROR_STREAM("Unable to open port " << port_);
00093       return false;
00094     }
00095 
00096     typedef boost::asio::serial_port_base serial;
00097     socket().set_option(serial::baud_rate(baud_));
00098     socket().set_option(serial::character_size(8));
00099     socket().set_option(serial::stop_bits(serial::stop_bits::one));
00100     socket().set_option(serial::parity(serial::parity::none));
00101     socket().set_option(serial::flow_control(serial::flow_control::none));
00102 
00103     // Kick off the session.
00104     start();
00105     return true;
00106   }
00107 
00108   void connect_with_reconnection(bool log_errors = true) {
00109     if (!attempt_connection(log_errors)) {
00110       if (log_errors) {
00111         ROS_INFO_STREAM("Attempting reconnection every " << interval_.total_milliseconds() << " ms.");
00112       }
00113       timer_.expires_from_now(interval_);
00114       timer_.async_wait(boost::bind(&SerialSession::connect_with_reconnection, this, false));
00115     } else {
00116     }
00117   }
00118 
00119   std::string port_;
00120   int baud_;
00121   boost::posix_time::time_duration interval_;
00122   boost::asio::deadline_timer timer_;
00123 };
00124 
00125 }  // namespace
00126 
00127 #endif  // ROSSERIAL_SERVER_SERIAL_SESSION_H


rosserial_server
Author(s): Mike Purvis
autogenerated on Thu Jun 6 2019 19:56:34