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), timer_(io_service)
00053   {
00054     ROS_INFO_STREAM("rosserial_server session configured for " << port_ << " at " << baud << "bps.");
00055 
00056     failed_connection_attempts_ = 0;
00057     check_connection();
00058   }
00059 
00060 private:
00061   void check_connection()
00062   {
00063     if (!is_active())
00064     {
00065       attempt_connection();
00066     }
00067 
00068     // Every second, check again if the connection should be reinitialized,
00069     // if the ROS node is still up.
00070     if (ros::ok())
00071     {
00072       timer_.expires_from_now(boost::posix_time::milliseconds(2000));
00073       timer_.async_wait(boost::bind(&SerialSession::check_connection, this));
00074     }
00075   }
00076 
00077   void attempt_connection()
00078   {
00079     ROS_DEBUG("Opening serial port.");
00080 
00081     boost::system::error_code ec;
00082     socket().open(port_, ec);
00083     if (ec) {
00084       failed_connection_attempts_++;
00085       if (failed_connection_attempts_ == 1) {
00086         ROS_ERROR_STREAM("Unable to open port " << port_ << ": " << ec);
00087       } else {
00088         ROS_DEBUG_STREAM("Unable to open port " << port_ << " (" << failed_connection_attempts_ << "): " << ec);
00089       }
00090       return;
00091     }
00092     ROS_INFO_STREAM("Opened " << port_);
00093     failed_connection_attempts_ = 0;
00094 
00095     typedef boost::asio::serial_port_base serial;
00096     socket().set_option(serial::baud_rate(baud_));
00097     socket().set_option(serial::character_size(8));
00098     socket().set_option(serial::stop_bits(serial::stop_bits::one));
00099     socket().set_option(serial::parity(serial::parity::none));
00100     socket().set_option(serial::flow_control(serial::flow_control::none));
00101 
00102     // Kick off the session.
00103     start();
00104   }
00105 
00106   std::string port_;
00107   int baud_;
00108   boost::asio::deadline_timer timer_;
00109   int failed_connection_attempts_;
00110 };
00111 
00112 }  // namespace
00113 
00114 #endif  // ROSSERIAL_SERVER_SERIAL_SESSION_H


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