Public Types | Public Member Functions | Private Attributes | List of all members
RTT::internal::ConnOutputEndpoint< T > Class Template Reference

#include <ConnOutputEndPoint.hpp>

Inheritance diagram for RTT::internal::ConnOutputEndpoint< T >:
Inheritance graph
[legend]

Public Types

typedef base::MultipleInputsChannelElement< T > Base
 
typedef boost::intrusive_ptr< ConnOutputEndpoint< T > > shared_ptr
 
- Public Types inherited from RTT::base::MultipleInputsChannelElement< T >
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

bool channelReady (base::ChannelElementBase::shared_ptr const &channel, ConnPolicy const &policy, ConnID *conn_id)
 
 ConnOutputEndpoint (InputPort< T > *port)
 
virtual bool disconnect (const base::ChannelElementBase::shared_ptr &channel, bool forward)
 
std::string getElementName () const
 
virtual base::ChannelElementBase::shared_ptr getOutputEndPoint ()
 
virtual base::PortInterfacegetPort () const
 
base::ChannelElement< T >::shared_ptr getReadEndpoint ()
 
virtual base::ChannelElement< T >::shared_ptr getSharedBuffer ()
 
virtual bool signal ()
 
virtual WriteStatus write (typename Base::param_t sample)
 
 ~ConnOutputEndpoint ()
 
- Public Member Functions inherited from RTT::base::MultipleInputsChannelElement< T >
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 inputReady (ChannelElementBase::shared_ptr const &caller)
 
 MultipleInputsChannelElementBase ()
 
bool signalFrom (ChannelElementBase *caller)
 
- Public Member Functions inherited from RTT::base::ChannelElementBase
 ChannelElementBase ()
 
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
 
shared_ptr getInput ()
 
virtual shared_ptr getInputEndPoint ()
 
virtual std::string getLocalURI () const
 
shared_ptr getOutput ()
 
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 ~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 ()
 

Private Attributes

InputPort< T > * port
 

Additional Inherited Members

- 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::MultipleInputsChannelElement< T >
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)
 
- 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::internal::ConnOutputEndpoint< T >

This is a channel element that represents the output endpoint of a connection, i.e. the part that is connected to the InputPort. In the RTT, connections are always created from input towards output. So this class is typically first created of the channel element chain and attached to the input port. Then we build further towards the outputport. Imagine a spider attaching a thread at one wall and moving along to the other side of the wall.

Definition at line 58 of file ConnOutputEndPoint.hpp.

Member Typedef Documentation

Definition at line 64 of file ConnOutputEndPoint.hpp.

template<typename T>
typedef boost::intrusive_ptr<ConnOutputEndpoint<T> > RTT::internal::ConnOutputEndpoint< T >::shared_ptr

Definition at line 65 of file ConnOutputEndPoint.hpp.

Constructor & Destructor Documentation

template<typename T>
RTT::internal::ConnOutputEndpoint< T >::ConnOutputEndpoint ( InputPort< T > *  port)
inline

Creates the connection end that represents the output and attach it to the input.

Parameters
portThe start point.
output_idEach connection must be identified by an ID that represents the other end. This id is passed to the input port port.
Returns

Definition at line 75 of file ConnOutputEndPoint.hpp.

template<typename T>
RTT::internal::ConnOutputEndpoint< T >::~ConnOutputEndpoint ( )
inline

Definition at line 80 of file ConnOutputEndPoint.hpp.

Member Function Documentation

template<typename T>
bool RTT::internal::ConnOutputEndpoint< T >::channelReady ( base::ChannelElementBase::shared_ptr const &  channel,
ConnPolicy const &  policy,
ConnID conn_id 
)
inlinevirtual

Call this to indicate that a connection leading to this port is ready to use. The input port will check its channel elements by sending an inputReady() message. If this succeeds, this function returns true and the input port is ready to use (this->connected() == true). If sending inputReady() returns failure, this method returns false and the connection is aborted (this->connected() == false).

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 92 of file ConnOutputEndPoint.hpp.

template<typename T>
virtual bool RTT::internal::ConnOutputEndpoint< T >::disconnect ( const base::ChannelElementBase::shared_ptr channel,
bool  forward 
)
inlinevirtual

Overridden implementation of ChannelElementBase::disconnect(forward, channel).

Reimplemented from RTT::base::MultipleInputsChannelElementBase.

Definition at line 130 of file ConnOutputEndPoint.hpp.

template<typename T>
std::string RTT::internal::ConnOutputEndpoint< 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 194 of file ConnOutputEndPoint.hpp.

template<typename T>
virtual base::ChannelElementBase::shared_ptr RTT::internal::ConnOutputEndpoint< T >::getOutputEndPoint ( )
inlinevirtual

Returns the last output channel element of this connection. Will return the channel element the furthest away from the output port, or this if none.

Returns
getOutput() ? getOutput()->getOutputEndPoint() : this

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 174 of file ConnOutputEndPoint.hpp.

template<typename T>
virtual base::PortInterface* RTT::internal::ConnOutputEndpoint< T >::getPort ( ) const
inlinevirtual

Gets the port this channel element is connected to.

Returns
null if no port is connected to this element, the port (or a proxy representing the port) otherwise.

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 170 of file ConnOutputEndPoint.hpp.

template<typename T>
base::ChannelElement<T>::shared_ptr RTT::internal::ConnOutputEndpoint< T >::getReadEndpoint ( )
inline

Definition at line 184 of file ConnOutputEndPoint.hpp.

template<typename T>
virtual base::ChannelElement<T>::shared_ptr RTT::internal::ConnOutputEndpoint< T >::getSharedBuffer ( )
inlinevirtual

Definition at line 179 of file ConnOutputEndPoint.hpp.

template<typename T>
virtual bool RTT::internal::ConnOutputEndpoint< T >::signal ( )
inlinevirtual

Signals that there is new data available on this channel By default, the channel element forwards the call to its output

Returns
false if an error occured that requires the channel to be invalidated. In no ways it indicates that the sample has been received by the other side of the channel.

Reimplemented from RTT::base::ChannelElementBase.

Definition at line 157 of file ConnOutputEndPoint.hpp.

template<typename T>
virtual WriteStatus RTT::internal::ConnOutputEndpoint< T >::write ( typename Base::param_t  sample)
inlinevirtual

Writes a new sample on this connection This should only be called if this endpoint has a buffer output, in which case the base class's write implementation will return true and the port is signalled. Otherwise, return false, as other type of connections are supposed to have a data storage element.

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

Definition at line 111 of file ConnOutputEndPoint.hpp.

Member Data Documentation

template<typename T>
InputPort<T>* RTT::internal::ConnOutputEndpoint< T >::port
private

Definition at line 61 of file ConnOutputEndPoint.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