Public Member Functions | Private Attributes | List of all members
RTT::mqueue::MQChannelElement< T > Class Template Reference

#include <MQChannelElement.hpp>

Inheritance diagram for RTT::mqueue::MQChannelElement< T >:
Inheritance graph
[legend]

Public Member Functions

virtual WriteStatus data_sample (typename base::ChannelElement< T >::param_t sample, bool reset=true)
 
virtual std::string getElementName () const
 
virtual std::string getLocalURI () const
 
virtual std::string getRemoteURI () const
 
virtual bool inputReady (base::ChannelElementBase::shared_ptr const &caller)
 
virtual bool isRemoteElement () const
 
 MQChannelElement (base::PortInterface *port, types::TypeMarshaller const &transport, const ConnPolicy &policy, bool is_sender)
 
FlowStatus read (typename base::ChannelElement< T >::reference_t sample, bool copy_old_data)
 
bool signal ()
 
WriteStatus write (typename base::ChannelElement< T >::param_t sample)
 
 ~MQChannelElement ()
 
- Public Member Functions inherited from RTT::base::ChannelElement< T >
virtual WriteStatus data_sample (param_t sample, bool reset=true)
 
virtual value_t data_sample ()
 
shared_ptr getInput ()
 
shared_ptr getOutput ()
 
virtual FlowStatus read (reference_t sample, bool copy_old_data=true)
 
virtual WriteStatus write (param_t sample)
 
- Public Member Functions inherited from RTT::base::ChannelElementBase
 ChannelElementBase ()
 
virtual bool channelReady (ChannelElementBase::shared_ptr const &caller, ConnPolicy const &policy, internal::ConnID *conn_id=0)
 
virtual void clear ()
 
virtual bool connected ()
 
virtual bool connectFrom (ChannelElementBase::shared_ptr const &input)
 
virtual bool connectTo (ChannelElementBase::shared_ptr const &output, bool mandatory=true)
 
virtual void disconnect (bool forward)
 
virtual bool disconnect (ChannelElementBase::shared_ptr const &channel, bool forward)
 
virtual const ConnPolicygetConnPolicy () const
 
shared_ptr getInput ()
 
virtual shared_ptr getInputEndPoint ()
 
shared_ptr getOutput ()
 
virtual shared_ptr getOutputEndPoint ()
 
virtual PortInterfacegetPort () const
 
template<typename T >
ChannelElement< T > * narrow ()
 
RTT_DEPRECATED void setInput (const ChannelElementBase::shared_ptr &input)
 
RTT_DEPRECATED void setOutput (const ChannelElementBase::shared_ptr &output)
 
virtual bool signalFrom (ChannelElementBase *)
 
virtual ~ChannelElementBase ()
 
- Public Member Functions inherited from RTT::mqueue::MQSendRecv
void cleanupStream ()
 
virtual void mqNewSample (base::DataSourceBase::shared_ptr ds)
 
bool mqRead (base::DataSourceBase::shared_ptr ds)
 
virtual bool mqReady (base::DataSourceBase::shared_ptr ds, base::ChannelElementBase *chan)
 
 MQSendRecv (types::TypeMarshaller const &transport)
 
bool mqWrite (base::DataSourceBase::shared_ptr ds)
 
void setupStream (base::DataSourceBase::shared_ptr ds, base::PortInterface *port, ConnPolicy const &policy, bool is_sender)
 
 ~MQSendRecv ()
 

Private Attributes

internal::ValueDataSource< T >::shared_ptr read_sample
 
internal::LateConstReferenceDataSource< T >::shared_ptr write_sample
 

Additional Inherited Members

- Public Types inherited from RTT::base::ChannelElement< T >
typedef boost::call_traits< T >::param_type param_t
 
typedef boost::call_traits< T >::reference reference_t
 
typedef boost::intrusive_ptr< ChannelElement< T > > shared_ptr
 
typedef T value_t
 
- Public Types inherited from RTT::base::ChannelElementBase
typedef boost::intrusive_ptr< ChannelElementBaseshared_ptr
 
- Static Public Member Functions inherited from RTT::base::ChannelElementBase
template<typename T >
static ChannelElement< T > * narrow (ChannelElementBase *e)
 
- Protected Member Functions inherited from RTT::base::ChannelElementBase
virtual bool addInput (shared_ptr const &input)
 
virtual bool addOutput (shared_ptr const &output, bool mandatory=true)
 
void deref ()
 
void ref ()
 
virtual void removeInput (shared_ptr const &input)
 
virtual void removeOutput (shared_ptr const &output)
 
- Protected Attributes inherited from RTT::base::ChannelElementBase
shared_ptr input
 
RTT::os::SharedMutex input_lock
 
shared_ptr output
 
RTT::os::SharedMutex output_lock
 
- Protected Attributes inherited from RTT::mqueue::MQSendRecv
char * buf
 
void * marshaller_cookie
 
int max_size
 
int mdata_size
 
bool minit_done
 
bool mis_sender
 
mqd_t mqdes
 
std::string mqname
 
types::TypeMarshaller const & mtransport
 

Detailed Description

template<typename T>
class RTT::mqueue::MQChannelElement< T >

Implements the a ChannelElement using message queues. It converts the C++ calls into MQ messages and vice versa.

Todo:

This class can be refactored into a base class with generic mqueue code and a subclass with type specific info.

This is an inspiration for a generic, transport independent channel element.

Definition at line 62 of file MQChannelElement.hpp.

Constructor & Destructor Documentation

template<typename T>
RTT::mqueue::MQChannelElement< T >::MQChannelElement ( base::PortInterface port,
types::TypeMarshaller const &  transport,
const ConnPolicy policy,
bool  is_sender 
)
inline

Create a channel element for remote data exchange.

Parameters
transportThe type specific object that will be used to marshal the data.

Definition at line 74 of file MQChannelElement.hpp.

template<typename T>
RTT::mqueue::MQChannelElement< T >::~MQChannelElement ( )
inline

Definition at line 85 of file MQChannelElement.hpp.

Member Function Documentation

template<typename T>
virtual WriteStatus RTT::mqueue::MQChannelElement< T >::data_sample ( typename base::ChannelElement< T >::param_t  sample,
bool  reset = true 
)
inlinevirtual

Definition at line 99 of file MQChannelElement.hpp.

template<typename T>
virtual std::string RTT::mqueue::MQChannelElement< T >::getElementName ( ) const
inlinevirtual

Returns the class name of this element. This is primary useful for special case handling in the connection tracking.

Returns
The name of the class of the ChannelElement

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 196 of file MQChannelElement.hpp.

template<typename T>
virtual std::string RTT::mqueue::MQChannelElement< T >::getLocalURI ( ) const
inlinevirtual

This function return the URI of this element. The URI must be unique.

Returns
URI of this element.

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 186 of file MQChannelElement.hpp.

template<typename T>
virtual std::string RTT::mqueue::MQChannelElement< T >::getRemoteURI ( ) const
inlinevirtual

This function returns the URI of the next channel element in the logical chain. The URI must be unique. E.g: In the local case output->getLocalURI() In the remote case the URI of the remote channel element.

Returns
URI of the next element.

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 176 of file MQChannelElement.hpp.

template<typename T>
virtual bool RTT::mqueue::MQChannelElement< T >::inputReady ( base::ChannelElementBase::shared_ptr const &  caller)
inlinevirtual

This is called by an input port when it is ready to receive data. Each channel element has the responsibility to pass this notification on to the next, in the direction of the output.

Returns
false if a fatal connection failure was encountered and the channel needs to be destroyed.

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 89 of file MQChannelElement.hpp.

template<typename T>
virtual bool RTT::mqueue::MQChannelElement< T >::isRemoteElement ( ) const
inlinevirtual

This function may be used to identify, if the current element uses a network transport, to send the data to the next Element in the logical chain.

Returns
true if a network transport is used.

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 171 of file MQChannelElement.hpp.

template<typename T>
FlowStatus RTT::mqueue::MQChannelElement< T >::read ( typename base::ChannelElement< T >::reference_t  sample,
bool  copy_old_data 
)
inline

Read from the message queue.

Parameters
samplestores the resulting data sample.
Returns
true if an item could be read.

Definition at line 152 of file MQChannelElement.hpp.

template<typename T>
bool RTT::mqueue::MQChannelElement< T >::signal ( )
inlinevirtual

Signal will cause a read-write cycle to transfer the data from the data/buffer element to the message queue and vice versa.

Note: this virtual function is a bit abused. For a sending MQ, signal triggers a direct read on the data element. For a receiving MQ, signal is used by the dispatcher thread to provoque a read from the MQ and forward it to the next channel element.

In the sending case, signal could trigger a dispatcher thread that does the read/write cycle, but that seems only causing overhead. The receiving case must use a thread which blocks on all mq file descriptors.

Returns
true in case the forwarding could be done, false otherwise.

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 128 of file MQChannelElement.hpp.

template<typename T>
WriteStatus RTT::mqueue::MQChannelElement< T >::write ( typename base::ChannelElement< T >::param_t  sample)
inline

Write to the message queue

Parameters
samplethe data sample to write
Returns
true if it could be sent.

Definition at line 162 of file MQChannelElement.hpp.

Member Data Documentation

template<typename T>
internal::ValueDataSource<T>::shared_ptr RTT::mqueue::MQChannelElement< T >::read_sample
private

Used as a temporary on the reading side

Definition at line 65 of file MQChannelElement.hpp.

template<typename T>
internal::LateConstReferenceDataSource<T>::shared_ptr RTT::mqueue::MQChannelElement< T >::write_sample
private

Used in write() to refer to the sample that needs to be written

Definition at line 67 of file MQChannelElement.hpp.


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


rtt
Author(s): RTT Developers
autogenerated on Tue Jun 25 2019 19:33:45