serial_session.h
Go to the documentation of this file.
1 
34 #ifndef ROSSERIAL_SERVER_SERIAL_SESSION_H
35 #define ROSSERIAL_SERVER_SERIAL_SESSION_H
36 
37 #include <iostream>
38 #include <boost/bind.hpp>
39 #include <boost/asio.hpp>
40 
41 #include <ros/ros.h>
42 
44 
45 namespace rosserial_server
46 {
47 
48 class SerialSession : public Session<boost::asio::serial_port>
49 {
50 public:
51  SerialSession(boost::asio::io_service& io_service, std::string port, int baud)
52  : Session(io_service), port_(port), baud_(baud), timer_(io_service)
53  {
54  ROS_INFO_STREAM("rosserial_server session configured for " << port_ << " at " << baud << "bps.");
55 
58  }
59 
60 private:
62  {
63  if (!is_active())
64  {
66  }
67 
68  // Every second, check again if the connection should be reinitialized,
69  // if the ROS node is still up.
70  if (ros::ok())
71  {
72  timer_.expires_from_now(boost::posix_time::milliseconds(2000));
73  timer_.async_wait(boost::bind(&SerialSession::check_connection, this));
74  }
75  }
76 
78  {
79  ROS_DEBUG("Opening serial port.");
80 
81  boost::system::error_code ec;
82  socket().open(port_, ec);
83  if (ec) {
85  if (failed_connection_attempts_ == 1) {
86  ROS_ERROR_STREAM("Unable to open port " << port_ << ": " << ec);
87  } else {
88  ROS_DEBUG_STREAM("Unable to open port " << port_ << " (" << failed_connection_attempts_ << "): " << ec);
89  }
90  return;
91  }
92  ROS_INFO_STREAM("Opened " << port_);
94 
95  typedef boost::asio::serial_port_base serial;
96  socket().set_option(serial::baud_rate(baud_));
97  socket().set_option(serial::character_size(8));
98  socket().set_option(serial::stop_bits(serial::stop_bits::one));
99  socket().set_option(serial::parity(serial::parity::none));
100  socket().set_option(serial::flow_control(serial::flow_control::none));
101 
102  // Kick off the session.
103  start();
104  }
105 
106  std::string port_;
107  int baud_;
108  boost::asio::deadline_timer timer_;
110 };
111 
112 } // namespace
113 
114 #endif // ROSSERIAL_SERVER_SERIAL_SESSION_H
Class representing a session between this node and a templated rosserial client.
ROSCPP_DECL bool ok()
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
#define ROS_ERROR_STREAM(args)
boost::asio::deadline_timer timer_
SerialSession(boost::asio::io_service &io_service, std::string port, int baud)
#define ROS_DEBUG(...)


rosserial_server
Author(s): Mike Purvis
autogenerated on Mon Jun 10 2019 14:53:36