Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
RTT::base::MultipleInputsChannelElement< T > Class Template Reference

#include <ChannelElement.hpp>

Inheritance diagram for RTT::base::MultipleInputsChannelElement< T >:
Inheritance graph
[legend]

Public Types

typedef ChannelElement< T >::param_t param_t
 
typedef ChannelElement< T >::reference_t reference_t
 
typedef boost::intrusive_ptr< MultipleInputsChannelElement< T > > shared_ptr
 
typedef ChannelElement< T >::value_t value_t
 
- Public Types inherited from RTT::base::MultipleInputsChannelElementBase
typedef std::list< ChannelElementBase::shared_ptrInputs
 
typedef boost::intrusive_ptr< MultipleInputsChannelElementBaseshared_ptr
 
- Public Types inherited from RTT::base::ChannelElementBase
typedef boost::intrusive_ptr< ChannelElementBaseshared_ptr
 
- 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 Member Functions

virtual value_t data_sample ()
 
 MultipleInputsChannelElement ()
 
virtual FlowStatus read (reference_t sample, bool copy_old_data=true)
 
- Public Member Functions inherited from RTT::base::MultipleInputsChannelElementBase
virtual void clear ()
 
virtual bool connected ()
 
virtual bool disconnect (ChannelElementBase::shared_ptr const &channel, bool forward=true)
 
virtual bool inputReady (ChannelElementBase::shared_ptr const &caller)
 
 MultipleInputsChannelElementBase ()
 
bool signalFrom (ChannelElementBase *caller)
 
- 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 bool connectFrom (ChannelElementBase::shared_ptr const &input)
 
virtual bool connectTo (ChannelElementBase::shared_ptr const &output, bool mandatory=true)
 
virtual void disconnect (bool forward)
 
virtual const ConnPolicygetConnPolicy () const
 
virtual std::string getElementName () const
 
shared_ptr getInput ()
 
virtual shared_ptr getInputEndPoint ()
 
virtual std::string getLocalURI () const
 
shared_ptr getOutput ()
 
virtual shared_ptr getOutputEndPoint ()
 
virtual PortInterfacegetPort () const
 
virtual std::string getRemoteURI () const
 
virtual bool isRemoteElement () 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 signal ()
 
virtual ~ChannelElementBase ()
 
- Public Member Functions inherited from RTT::base::ChannelElement< T >
virtual WriteStatus data_sample (param_t sample, bool reset=true)
 
shared_ptr getInput ()
 
shared_ptr getOutput ()
 
virtual WriteStatus write (param_t sample)
 

Protected Member Functions

virtual void removeInput (ChannelElementBase::shared_ptr const &input)
 
- Protected Member Functions inherited from RTT::base::MultipleInputsChannelElementBase
virtual bool addInput (ChannelElementBase::shared_ptr const &input)
 
- Protected Member Functions inherited from RTT::base::ChannelElementBase
virtual bool addOutput (shared_ptr const &output, bool mandatory=true)
 
void deref ()
 
void ref ()
 
virtual void removeOutput (shared_ptr const &output)
 

Private Member Functions

ChannelElement< T >::shared_ptr currentInput ()
 
bool do_read (reference_t sample, FlowStatus &result, bool copy_old_data, typename ChannelElement< T >::shared_ptr &input)
 
template<typename Pred >
ChannelElement< T >::shared_ptr find_if (Pred pred, bool copy_old_data)
 
template<typename Pred >
void select_reader_channel (Pred pred, bool copy_old_data)
 

Private Attributes

ChannelElement< T > * last
 

Additional Inherited Members

- Static Public Member Functions inherited from RTT::base::ChannelElementBase
template<typename T >
static ChannelElement< T > * narrow (ChannelElementBase *e)
 
- Protected Attributes inherited from RTT::base::MultipleInputsChannelElementBase
Inputs inputs
 
RTT::os::SharedMutex inputs_lock
 
- Protected Attributes inherited from RTT::base::ChannelElementBase
shared_ptr input
 
RTT::os::SharedMutex input_lock
 
shared_ptr output
 
RTT::os::SharedMutex output_lock
 

Detailed Description

template<typename T>
class RTT::base::MultipleInputsChannelElement< T >

A typed version of MultipleInputsChannelElementBase.

Definition at line 131 of file ChannelElement.hpp.

Member Typedef Documentation

Definition at line 136 of file ChannelElement.hpp.

Definition at line 137 of file ChannelElement.hpp.

template<typename T>
typedef boost::intrusive_ptr< MultipleInputsChannelElement<T> > RTT::base::MultipleInputsChannelElement< T >::shared_ptr

Definition at line 134 of file ChannelElement.hpp.

Definition at line 135 of file ChannelElement.hpp.

Constructor & Destructor Documentation

Definition at line 139 of file ChannelElement.hpp.

Member Function Documentation

template<typename T>
ChannelElement<T>::shared_ptr RTT::base::MultipleInputsChannelElement< T >::currentInput ( )
inlineprivate

Definition at line 172 of file ChannelElement.hpp.

template<typename T>
virtual value_t RTT::base::MultipleInputsChannelElement< T >::data_sample ( )
inlinevirtual

Overridden implementation of MultipleInputsChannelElementBase::data_sample() that gets a sample from the currently selected input.

Reimplemented from RTT::base::ChannelElement< T >.

Reimplemented in RTT::internal::SharedConnection< T >.

Definition at line 146 of file ChannelElement.hpp.

template<typename T>
bool RTT::base::MultipleInputsChannelElement< T >::do_read ( reference_t  sample,
FlowStatus result,
bool  copy_old_data,
typename ChannelElement< T >::shared_ptr input 
)
inlineprivate

Definition at line 178 of file ChannelElement.hpp.

template<typename T>
template<typename Pred >
ChannelElement<T>::shared_ptr RTT::base::MultipleInputsChannelElement< T >::find_if ( Pred  pred,
bool  copy_old_data 
)
inlineprivate

Definition at line 218 of file ChannelElement.hpp.

template<typename T>
virtual FlowStatus RTT::base::MultipleInputsChannelElement< T >::read ( reference_t  sample,
bool  copy_old_data = true 
)
inlinevirtual

Reads a sample from the connection. sample is a reference which will get updated if a sample is available. The method returns true if a sample was available, and false otherwise. If false is returned, then sample is not modified by the method

Reimplemented from RTT::base::ChannelElement< T >.

Reimplemented in RTT::internal::SharedConnection< T >.

Definition at line 161 of file ChannelElement.hpp.

template<typename T>
virtual void RTT::base::MultipleInputsChannelElement< T >::removeInput ( ChannelElementBase::shared_ptr const &  input)
inlineprotectedvirtual

Remove an input from the inputs list.

Parameters
inputthe element to be removed

Reimplemented from RTT::base::MultipleInputsChannelElementBase.

Definition at line 240 of file ChannelElement.hpp.

template<typename T>
template<typename Pred >
void RTT::base::MultipleInputsChannelElement< T >::select_reader_channel ( Pred  pred,
bool  copy_old_data 
)
inlineprivate

Selects a connection as the current channel if pred(connection) is true. It will first check the current channel ( getCurrentChannel() ), if that does not satisfy pred, iterate over all connections. If none satisfy pred, the current channel remains unchanged.

Parameters
pred

Definition at line 204 of file ChannelElement.hpp.

Member Data Documentation

template<typename T>
ChannelElement<T>* RTT::base::MultipleInputsChannelElement< T >::last
private

Definition at line 247 of file ChannelElement.hpp.


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


rtt
Author(s): RTT Developers
autogenerated on Fri Oct 25 2019 03:59:46