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  else
76  {
77  shutdown();
78  }
79  }
80 
82  {
83  ROS_DEBUG("Opening serial port.");
84 
85  boost::system::error_code ec;
86  socket().open(port_, ec);
87  if (ec) {
89  if (failed_connection_attempts_ == 1) {
90  ROS_ERROR_STREAM("Unable to open port " << port_ << ": " << ec);
91  } else {
92  ROS_DEBUG_STREAM("Unable to open port " << port_ << " (" << failed_connection_attempts_ << "): " << ec);
93  }
94  return;
95  }
96  ROS_INFO_STREAM("Opened " << port_);
98 
99  typedef boost::asio::serial_port_base serial;
100  socket().set_option(serial::baud_rate(baud_));
101  socket().set_option(serial::character_size(8));
102  socket().set_option(serial::stop_bits(serial::stop_bits::one));
103  socket().set_option(serial::parity(serial::parity::none));
104  socket().set_option(serial::flow_control(serial::flow_control::none));
105 
106  // Kick off the session.
107  start();
108  }
109 
110  std::string port_;
111  int baud_;
112  boost::asio::deadline_timer timer_;
114 };
115 
116 } // namespace
117 
118 #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 Feb 28 2022 23:35:31