Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
rosserial_server::Session< Socket > Class Template Reference

#include <session.h>

Inheritance diagram for rosserial_server::Session< Socket >:
Inheritance graph
[legend]

Public Member Functions

bool is_active ()
 
 Session (boost::asio::io_service &io_service)
 
void set_require_param (std::string param_name)
 
Socket & socket ()
 
void start ()
 
void stop ()
 

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_log (ros::serialization::IStream &stream)
 
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 ros_spin_timeout (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_service_client_publisher (ros::serialization::IStream &stream)
 
void setup_service_client_subscriber (ros::serialization::IStream &stream)
 
void setup_subscriber (ros::serialization::IStream &stream)
 
void sync_timeout (const boost::system::error_code &error)
 
void write_completion_cb (const boost::system::error_code &error, BufferPtr buffer_ptr)
 
void write_message (Buffer &message, const uint16_t topic_id)
 

Static Private Member Functions

static uint8_t checksum (ros::serialization::IStream &stream)
 
static uint8_t checksum (uint16_t val)
 

Private Attributes

bool active_
 
AsyncReadBuffer< Socket > async_read_buffer_
 
boost::posix_time::time_duration attempt_interval_
 
std::map< uint16_t, boost::function< void(ros::serialization::IStream &)> > callbacks_
 
ros::NodeHandle nh_
 
std::map< uint16_t, PublisherPtrpublishers_
 
boost::posix_time::time_duration require_check_interval_
 
boost::asio::deadline_timer require_check_timer_
 
std::string require_param_name_
 
ros::CallbackQueue ros_callback_queue_
 
boost::posix_time::time_duration ros_spin_interval_
 
boost::asio::deadline_timer ros_spin_timer_
 
std::map< std::string, ServiceClientPtrservices_
 
Socket socket_
 
std::map< uint16_t, SubscriberPtrsubscribers_
 
boost::asio::deadline_timer sync_timer_
 
boost::posix_time::time_duration timeout_interval_
 

Detailed Description

template<typename Socket>
class rosserial_server::Session< Socket >

Definition at line 60 of file session.h.

Member Enumeration Documentation

template<typename Socket>
anonymous enum
private
Enumerator
buffer_max 

Definition at line 487 of file session.h.

Constructor & Destructor Documentation

template<typename Socket>
rosserial_server::Session< Socket >::Session ( boost::asio::io_service &  io_service)
inline

Definition at line 63 of file session.h.

Member Function Documentation

template<typename Socket>
void rosserial_server::Session< Socket >::attempt_sync ( )
inlineprivate

Definition at line 301 of file session.h.

template<typename Socket>
template<typename M >
bool rosserial_server::Session< Socket >::check_set ( std::string  param_name,
map 
)
inlineprivate

Definition at line 349 of file session.h.

template<typename Socket>
static uint8_t rosserial_server::Session< Socket >::checksum ( ros::serialization::IStream stream)
inlinestaticprivate

Definition at line 374 of file session.h.

template<typename Socket>
static uint8_t rosserial_server::Session< Socket >::checksum ( uint16_t  val)
inlinestaticprivate

Definition at line 382 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::handle_log ( ros::serialization::IStream stream)
inlineprivate

Definition at line 458 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::handle_time ( ros::serialization::IStream stream)
inlineprivate

Definition at line 468 of file session.h.

template<typename Socket>
bool rosserial_server::Session< Socket >::is_active ( )
inline

Definition at line 138 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::read_body ( ros::serialization::IStream stream,
uint16_t  topic_id 
)
inlineprivate

Definition at line 219 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::read_failed ( const boost::system::error_code &  error)
inlineprivate

Definition at line 249 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::read_id_length ( ros::serialization::IStream stream)
inlineprivate

Definition at line 198 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::read_sync_first ( ros::serialization::IStream stream)
inlineprivate

Definition at line 178 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::read_sync_header ( )
inlineprivate

Definition at line 174 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::read_sync_second ( ros::serialization::IStream stream)
inlineprivate

Definition at line 188 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::request_topics ( )
inlineprivate

Definition at line 324 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::required_topics_check ( const boost::system::error_code &  error)
inlineprivate

Definition at line 336 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::ros_spin_timeout ( const boost::system::error_code &  error)
inlineprivate

Periodic function which handles calling ROS callbacks, executed on the same io_service thread to avoid a concurrency nightmare.

Definition at line 159 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::set_require_param ( std::string  param_name)
inline

This is to set the name of the required topics parameter from the default of ~require. You might want to do this to avoid a conflict with something else in that namespace, or because you're embedding multiple instances of rosserial_server in a single process.

Definition at line 149 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::set_sync_timeout ( const boost::posix_time::time_duration &  interval)
inlineprivate

Definition at line 306 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::setup_publisher ( ros::serialization::IStream stream)
inlineprivate

Definition at line 388 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::setup_service_client_publisher ( ros::serialization::IStream stream)
inlineprivate

Definition at line 416 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::setup_service_client_subscriber ( ros::serialization::IStream stream)
inlineprivate

Definition at line 436 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::setup_subscriber ( ros::serialization::IStream stream)
inlineprivate

Definition at line 399 of file session.h.

template<typename Socket>
Socket& rosserial_server::Session< Socket >::socket ( )
inline

Definition at line 90 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::start ( )
inline

Definition at line 95 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::stop ( )
inline

Definition at line 117 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::sync_timeout ( const boost::system::error_code &  error)
inlineprivate

Definition at line 316 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::write_completion_cb ( const boost::system::error_code &  error,
BufferPtr  buffer_ptr 
)
inlineprivate

Definition at line 285 of file session.h.

template<typename Socket>
void rosserial_server::Session< Socket >::write_message ( Buffer message,
const uint16_t  topic_id 
)
inlineprivate

Definition at line 264 of file session.h.

Member Data Documentation

template<typename Socket>
bool rosserial_server::Session< Socket >::active_
private

Definition at line 488 of file session.h.

template<typename Socket>
AsyncReadBuffer<Socket> rosserial_server::Session< Socket >::async_read_buffer_
private

Definition at line 486 of file session.h.

template<typename Socket>
boost::posix_time::time_duration rosserial_server::Session< Socket >::attempt_interval_
private

Definition at line 494 of file session.h.

template<typename Socket>
std::map<uint16_t, boost::function<void(ros::serialization::IStream&)> > rosserial_server::Session< Socket >::callbacks_
private

Definition at line 502 of file session.h.

template<typename Socket>
ros::NodeHandle rosserial_server::Session< Socket >::nh_
private

Definition at line 490 of file session.h.

template<typename Socket>
std::map<uint16_t, PublisherPtr> rosserial_server::Session< Socket >::publishers_
private

Definition at line 503 of file session.h.

template<typename Socket>
boost::posix_time::time_duration rosserial_server::Session< Socket >::require_check_interval_
private

Definition at line 495 of file session.h.

template<typename Socket>
boost::asio::deadline_timer rosserial_server::Session< Socket >::require_check_timer_
private

Definition at line 498 of file session.h.

template<typename Socket>
std::string rosserial_server::Session< Socket >::require_param_name_
private

Definition at line 500 of file session.h.

template<typename Socket>
ros::CallbackQueue rosserial_server::Session< Socket >::ros_callback_queue_
private

Definition at line 491 of file session.h.

template<typename Socket>
boost::posix_time::time_duration rosserial_server::Session< Socket >::ros_spin_interval_
private

Definition at line 496 of file session.h.

template<typename Socket>
boost::asio::deadline_timer rosserial_server::Session< Socket >::ros_spin_timer_
private

Definition at line 499 of file session.h.

template<typename Socket>
std::map<std::string, ServiceClientPtr> rosserial_server::Session< Socket >::services_
private

Definition at line 505 of file session.h.

template<typename Socket>
Socket rosserial_server::Session< Socket >::socket_
private

Definition at line 485 of file session.h.

template<typename Socket>
std::map<uint16_t, SubscriberPtr> rosserial_server::Session< Socket >::subscribers_
private

Definition at line 504 of file session.h.

template<typename Socket>
boost::asio::deadline_timer rosserial_server::Session< Socket >::sync_timer_
private

Definition at line 497 of file session.h.

template<typename Socket>
boost::posix_time::time_duration rosserial_server::Session< Socket >::timeout_interval_
private

Definition at line 493 of file session.h.


The documentation for this class was generated from the following file:


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