Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
io_comm_rx::AsyncManager< StreamT > Class Template Reference

This is the central interface between ROSaic and the Rx(s), managing I/O operations such as reading messages and sending commands.. More...

#include <async_manager.hpp>

Inheritance diagram for io_comm_rx::AsyncManager< StreamT >:
Inheritance graph
[legend]

Public Member Functions

 AsyncManager (ROSaicNodeBase *node, boost::shared_ptr< StreamT > stream, boost::shared_ptr< boost::asio::io_service > io_service, std::size_t buffer_size=16384)
 Class constructor. More...
 
bool isOpen () const
 Determines whether or not the connection is open. More...
 
bool send (const std::string &cmd)
 Sends commands via the I/O stream. More...
 
void setCallback (const Callback &callback)
 Allows to connect to the CallbackHandlers class. More...
 
void wait (uint16_t *count)
 
virtual ~AsyncManager ()
 
- Public Member Functions inherited from io_comm_rx::Manager
virtual ~Manager ()
 

Protected Member Functions

void asyncReadSomeHandler (const boost::system::error_code &error, std::size_t bytes_transferred)
 Handler for async_read_some (Boost library).. More...
 
void callAsyncWait (uint16_t *count)
 Handles the ROS_INFO throwing (if no incoming message) More...
 
void close ()
 Closes stream "stream_". More...
 
void read ()
 
void tryParsing ()
 
void write (const std::string &cmd)
 Sends command "cmd" to the Rx. More...
 

Protected Attributes

bool allow_writing_
 
boost::shared_ptr< boost::thread > async_background_thread_
 New thread for receiving incoming messages. More...
 
const std::size_t buffer_size_
 Size of in_ buffers. More...
 
CircularBuffer circular_buffer_
 
const uint16_t count_max_
 
uint16_t do_read_count_
 
std::vector< uint8_t > in_
 Buffer for async_read_some() to read continuous SBF/NMEA stream. More...
 
boost::shared_ptr< boost::asio::io_service > io_service_
 io_context object More...
 
boost::mutex parse_mutex_
 Mutex to control changes of class variable "try_parsing". More...
 
boost::condition_variable parsing_condition_
 Condition variable complementing "parse_mutex". More...
 
boost::shared_ptr< boost::thread > parsing_thread_
 New thread for receiving incoming messages. More...
 
Callback read_callback_
 Callback to be called once message arrives. More...
 
Timestamp recvTime_
 Timestamp of receiving buffer. More...
 
bool stopping_
 Whether or not we want to sever the connection to the Rx. More...
 
boost::shared_ptr< StreamT > stream_
 Stream, represents either serial or TCP/IP connection. More...
 
boost::asio::deadline_timer timer_
 
bool try_parsing_
 Determines when the tryParsing() method will attempt parsing SBF/NMEA. More...
 
boost::shared_ptr< boost::thread > waiting_thread_
 New thread for receiving incoming messages. More...
 

Private Attributes

ROSaicNodeBasenode_
 Pointer to the node. More...
 

Additional Inherited Members

- Public Types inherited from io_comm_rx::Manager
typedef boost::function< void(Timestamp, const uint8_t *, std::size_t &)> Callback
 

Detailed Description

template<typename StreamT>
class io_comm_rx::AsyncManager< StreamT >

This is the central interface between ROSaic and the Rx(s), managing I/O operations such as reading messages and sending commands..

StreamT is either boost::asio::serial_port or boost::asio::tcp::ip

Definition at line 116 of file async_manager.hpp.

Constructor & Destructor Documentation

◆ AsyncManager()

template<typename StreamT >
io_comm_rx::AsyncManager< StreamT >::AsyncManager ( ROSaicNodeBase node,
boost::shared_ptr< StreamT >  stream,
boost::shared_ptr< boost::asio::io_service >  io_service,
std::size_t  buffer_size = 16384 
)

Class constructor.

Parameters
streamWhether TCP/IP or serial communication, either boost::asio::serial_port or boost::asio::tcp::ip
io_serviceThe io_context object. The io_context represents your program's link to the operating system's I/O services
[in]buffer_sizeSize of the circular buffer in bytes

Definition at line 329 of file async_manager.hpp.

◆ ~AsyncManager()

template<typename StreamT >
io_comm_rx::AsyncManager< StreamT >::~AsyncManager ( )
virtual

Definition at line 375 of file async_manager.hpp.

Member Function Documentation

◆ asyncReadSomeHandler()

template<typename StreamT >
void io_comm_rx::AsyncManager< StreamT >::asyncReadSomeHandler ( const boost::system::error_code &  error,
std::size_t  bytes_transferred 
)
protected

Handler for async_read_some (Boost library)..

Definition at line 401 of file async_manager.hpp.

◆ callAsyncWait()

template<typename StreamT >
void io_comm_rx::AsyncManager< StreamT >::callAsyncWait ( uint16_t *  count)
protected

Handles the ROS_INFO throwing (if no incoming message)

Definition at line 323 of file async_manager.hpp.

◆ close()

template<typename StreamT >
void io_comm_rx::AsyncManager< StreamT >::close ( )
protected

Closes stream "stream_".

Definition at line 432 of file async_manager.hpp.

◆ isOpen()

template<typename StreamT >
bool io_comm_rx::AsyncManager< StreamT >::isOpen ( ) const
inlinevirtual

Determines whether or not the connection is open.

Implements io_comm_rx::Manager.

Definition at line 147 of file async_manager.hpp.

◆ read()

template<typename StreamT >
void io_comm_rx::AsyncManager< StreamT >::read ( )
protected

Reads in via async_read_some and hands certain number of bytes (bytes_transferred) over to async_read_some_handler

Definition at line 387 of file async_manager.hpp.

◆ send()

template<typename StreamT >
bool io_comm_rx::AsyncManager< StreamT >::send ( const std::string &  cmd)
virtual

Sends commands via the I/O stream.

Parameters
cmdThe command to be sent

Implements io_comm_rx::Manager.

Definition at line 299 of file async_manager.hpp.

◆ setCallback()

template<typename StreamT >
void io_comm_rx::AsyncManager< StreamT >::setCallback ( const Callback callback)
inlinevirtual

Allows to connect to the CallbackHandlers class.

Parameters
callbackThe function that becomes our callback, typically the readCallback() method of CallbackHandlers

Implements io_comm_rx::Manager.

Definition at line 137 of file async_manager.hpp.

◆ tryParsing()

template<typename StreamT >
void io_comm_rx::AsyncManager< StreamT >::tryParsing ( )
protected

Tries parsing SBF/NMEA whenever the boolean class variable "try_parsing" is true

Definition at line 236 of file async_manager.hpp.

◆ wait()

template<typename StreamT >
void io_comm_rx::AsyncManager< StreamT >::wait ( uint16_t *  count)
virtual

Waits count seconds before throwing ROS_INFO message in case no message from the receiver arrived

Implements io_comm_rx::Manager.

Definition at line 445 of file async_manager.hpp.

◆ write()

template<typename StreamT >
void io_comm_rx::AsyncManager< StreamT >::write ( const std::string &  cmd)
protected

Sends command "cmd" to the Rx.

Definition at line 313 of file async_manager.hpp.

Member Data Documentation

◆ allow_writing_

template<typename StreamT >
bool io_comm_rx::AsyncManager< StreamT >::allow_writing_
protected

Determines when the asyncReadSomeHandler() method should write SBF/NMEA into the circular buffer

Definition at line 180 of file async_manager.hpp.

◆ async_background_thread_

template<typename StreamT >
boost::shared_ptr<boost::thread> io_comm_rx::AsyncManager< StreamT >::async_background_thread_
protected

New thread for receiving incoming messages.

Definition at line 199 of file async_manager.hpp.

◆ buffer_size_

template<typename StreamT >
const std::size_t io_comm_rx::AsyncManager< StreamT >::buffer_size_
protected

Size of in_ buffers.

Definition at line 214 of file async_manager.hpp.

◆ circular_buffer_

template<typename StreamT >
CircularBuffer io_comm_rx::AsyncManager< StreamT >::circular_buffer_
protected

Circular buffer to avoid unsuccessful SBF/NMEA parsing due to incomplete messages

Definition at line 196 of file async_manager.hpp.

◆ count_max_

template<typename StreamT >
const uint16_t io_comm_rx::AsyncManager< StreamT >::count_max_
protected

Number of seconds before ROS_INFO message is thrown (if no incoming message)

Definition at line 222 of file async_manager.hpp.

◆ do_read_count_

template<typename StreamT >
uint16_t io_comm_rx::AsyncManager< StreamT >::do_read_count_
protected

Number of times the DoRead() method has been called (only counts initially)

Definition at line 229 of file async_manager.hpp.

◆ in_

template<typename StreamT >
std::vector<uint8_t> io_comm_rx::AsyncManager< StreamT >::in_
protected

Buffer for async_read_some() to read continuous SBF/NMEA stream.

Definition at line 192 of file async_manager.hpp.

◆ io_service_

template<typename StreamT >
boost::shared_ptr<boost::asio::io_service> io_comm_rx::AsyncManager< StreamT >::io_service_
protected

io_context object

Definition at line 189 of file async_manager.hpp.

◆ node_

template<typename StreamT >
ROSaicNodeBase* io_comm_rx::AsyncManager< StreamT >::node_
private

Pointer to the node.

Definition at line 151 of file async_manager.hpp.

◆ parse_mutex_

template<typename StreamT >
boost::mutex io_comm_rx::AsyncManager< StreamT >::parse_mutex_
protected

Mutex to control changes of class variable "try_parsing".

Definition at line 173 of file async_manager.hpp.

◆ parsing_condition_

template<typename StreamT >
boost::condition_variable io_comm_rx::AsyncManager< StreamT >::parsing_condition_
protected

Condition variable complementing "parse_mutex".

Definition at line 183 of file async_manager.hpp.

◆ parsing_thread_

template<typename StreamT >
boost::shared_ptr<boost::thread> io_comm_rx::AsyncManager< StreamT >::parsing_thread_
protected

New thread for receiving incoming messages.

Definition at line 202 of file async_manager.hpp.

◆ read_callback_

template<typename StreamT >
Callback io_comm_rx::AsyncManager< StreamT >::read_callback_
protected

Callback to be called once message arrives.

Definition at line 208 of file async_manager.hpp.

◆ recvTime_

template<typename StreamT >
Timestamp io_comm_rx::AsyncManager< StreamT >::recvTime_
protected

Timestamp of receiving buffer.

Definition at line 232 of file async_manager.hpp.

◆ stopping_

template<typename StreamT >
bool io_comm_rx::AsyncManager< StreamT >::stopping_
protected

Whether or not we want to sever the connection to the Rx.

Definition at line 211 of file async_manager.hpp.

◆ stream_

template<typename StreamT >
boost::shared_ptr<StreamT> io_comm_rx::AsyncManager< StreamT >::stream_
protected

Stream, represents either serial or TCP/IP connection.

Definition at line 186 of file async_manager.hpp.

◆ timer_

template<typename StreamT >
boost::asio::deadline_timer io_comm_rx::AsyncManager< StreamT >::timer_
protected

Boost timer for throwing ROS_INFO message once timed out due to lack of incoming messages

Definition at line 218 of file async_manager.hpp.

◆ try_parsing_

template<typename StreamT >
bool io_comm_rx::AsyncManager< StreamT >::try_parsing_
protected

Determines when the tryParsing() method will attempt parsing SBF/NMEA.

Definition at line 176 of file async_manager.hpp.

◆ waiting_thread_

template<typename StreamT >
boost::shared_ptr<boost::thread> io_comm_rx::AsyncManager< StreamT >::waiting_thread_
protected

New thread for receiving incoming messages.

Definition at line 205 of file async_manager.hpp.


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


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Sat Mar 11 2023 03:12:56