#include <Session.h>
Public Types | |
enum | Version { PROTOCOL_UNKNOWN = 0, PROTOCOL_VER1 = 1, PROTOCOL_VER2 = 2, PROTOCOL_MAX } |
Public Member Functions | |
Session (boost::asio::io_service &io_service) | |
Socket & | socket () |
void | start () |
virtual | ~Session () |
Private Types | |
enum | { buffer_max = 1023 } |
Private Member Functions | |
void | attempt_sync () |
template<typename M > | |
bool | check_set (std::string param_name, M map) |
void | handle_time (ros::serialization::IStream &stream) |
void | read_body (ros::serialization::IStream &stream, uint16_t topic_id) |
void | read_failed (const boost::system::error_code &error) |
void | read_id_length (ros::serialization::IStream &stream) |
void | read_sync_first (ros::serialization::IStream &stream) |
void | read_sync_header () |
void | read_sync_second (ros::serialization::IStream &stream) |
void | request_topics () |
void | required_topics_check (const boost::system::error_code &error) |
void | set_sync_timeout (const boost::posix_time::time_duration &interval) |
void | setup_publisher (ros::serialization::IStream &stream) |
void | setup_subscriber (ros::serialization::IStream &stream) |
void | sync_timeout (const boost::system::error_code &error) |
void | write_buffer (BufferPtr buffer_ptr) |
void | write_cb (const boost::system::error_code &error, BufferPtr buffer_ptr) |
void | write_message (Buffer &message, const uint16_t topic_id, Session::Version version) |
Static Private Member Functions | |
static uint8_t | checksum (ros::serialization::IStream &stream) |
static uint8_t | checksum (uint16_t val) |
Private Attributes | |
AsyncReadBuffer< Socket > | async_read_buffer_ |
boost::posix_time::time_duration | attempt_interval_ |
std::map< uint16_t, boost::function< void(ros::serialization::IStream)> > | callbacks_ |
Session::Version | client_version |
Session::Version | client_version_try |
ros::NodeHandle | nh_ |
std::map< uint16_t, PublisherPtr > | publishers_ |
boost::posix_time::time_duration | require_check_interval_ |
boost::asio::deadline_timer | require_check_timer_ |
Socket | socket_ |
std::map< uint16_t, SubscriberPtr > | subscribers_ |
boost::asio::deadline_timer | sync_timer_ |
boost::posix_time::time_duration | timeout_interval_ |
anonymous enum [private] |
enum Session::Version |
void Session< Socket >::attempt_sync | ( | ) | [inline, private] |
static uint8_t Session< Socket >::checksum | ( | ros::serialization::IStream & | stream | ) | [inline, static, private] |
void Session< Socket >::handle_time | ( | ros::serialization::IStream & | stream | ) | [inline, private] |
void Session< Socket >::read_body | ( | ros::serialization::IStream & | stream, |
uint16_t | topic_id | ||
) | [inline, private] |
void Session< Socket >::read_failed | ( | const boost::system::error_code & | error | ) | [inline, private] |
void Session< Socket >::read_id_length | ( | ros::serialization::IStream & | stream | ) | [inline, private] |
void Session< Socket >::read_sync_first | ( | ros::serialization::IStream & | stream | ) | [inline, private] |
void Session< Socket >::read_sync_header | ( | ) | [inline, private] |
void Session< Socket >::read_sync_second | ( | ros::serialization::IStream & | stream | ) | [inline, private] |
void Session< Socket >::request_topics | ( | ) | [inline, private] |
void Session< Socket >::required_topics_check | ( | const boost::system::error_code & | error | ) | [inline, private] |
void Session< Socket >::set_sync_timeout | ( | const boost::posix_time::time_duration & | interval | ) | [inline, private] |
void Session< Socket >::setup_publisher | ( | ros::serialization::IStream & | stream | ) | [inline, private] |
void Session< Socket >::setup_subscriber | ( | ros::serialization::IStream & | stream | ) | [inline, private] |
void Session< Socket >::sync_timeout | ( | const boost::system::error_code & | error | ) | [inline, private] |
void Session< Socket >::write_buffer | ( | BufferPtr | buffer_ptr | ) | [inline, private] |
void Session< Socket >::write_message | ( | Buffer & | message, |
const uint16_t | topic_id, | ||
Session< Socket >::Version | version | ||
) | [inline, private] |
AsyncReadBuffer<Socket> Session< Socket >::async_read_buffer_ [private] |
boost::posix_time::time_duration Session< Socket >::attempt_interval_ [private] |
std::map< uint16_t, boost::function<void(ros::serialization::IStream)> > Session< Socket >::callbacks_ [private] |
Session::Version Session< Socket >::client_version [private] |
Session::Version Session< Socket >::client_version_try [private] |
ros::NodeHandle Session< Socket >::nh_ [private] |
std::map<uint16_t, PublisherPtr> Session< Socket >::publishers_ [private] |
boost::posix_time::time_duration Session< Socket >::require_check_interval_ [private] |
boost::asio::deadline_timer Session< Socket >::require_check_timer_ [private] |
std::map<uint16_t, SubscriberPtr> Session< Socket >::subscribers_ [private] |
boost::asio::deadline_timer Session< Socket >::sync_timer_ [private] |
boost::posix_time::time_duration Session< Socket >::timeout_interval_ [private] |