34 #ifndef ROSSERIAL_SERVER_SERIAL_SESSION_H
35 #define ROSSERIAL_SERVER_SERIAL_SESSION_H
38 #include <boost/bind.hpp>
39 #include <boost/asio.hpp>
51 SerialSession(boost::asio::io_service& io_service, std::string port,
int baud)
54 ROS_INFO_STREAM(
"rosserial_server session configured for " <<
port_ <<
" at " << baud <<
"bps.");
72 timer_.expires_from_now(boost::posix_time::milliseconds(2000));
85 boost::system::error_code ec;
99 typedef boost::asio::serial_port_base serial;
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));
118 #endif // ROSSERIAL_SERVER_SERIAL_SESSION_H