YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
yarp::os::Contactable Class Referenceabstract

An abstract port. More...

#include <yarp/os/Contactable.h>

+ Inheritance diagram for yarp::os::Contactable:

Public Member Functions

virtual ~Contactable ()
 Destructor.
 
virtual bool open (const std::string &name)=0
 Start port operation, with a specific name, with automatically-chosen network parameters.
 
virtual bool open (const Contact &contact, bool registerName=true)=0
 Start port operation with user-chosen network parameters.
 
virtual bool addOutput (const std::string &name)=0
 Add an output connection to the specified port.
 
virtual bool addOutput (const std::string &name, const std::string &carrier)=0
 Add an output connection to the specified port, using a specified carrier.
 
virtual bool addOutput (const Contact &contact)=0
 Add an output connection to the specified port, using specified network parameters.
 
virtual void close ()=0
 Stop port activity.
 
virtual void interrupt ()=0
 Interrupt any current reads or writes attached to the port.
 
virtual void resume ()=0
 Put the port back in an operative state after interrupt() has been called.
 
virtual Contact where () const =0
 Returns information about how this port can be reached.
 
virtual std::string getName () const
 Get name of port.
 
virtual bool setEnvelope (PortWriter &envelope)=0
 Set an envelope (e.g., a timestamp) to the next message which will be sent.
 
virtual bool getEnvelope (PortReader &envelope)=0
 Get the envelope information (e.g., a timestamp) from the last message received on the port.
 
virtual int getInputCount ()=0
 Determine how many connections are arriving into this port.
 
virtual int getOutputCount ()=0
 Determine how many output connections this port has.
 
virtual void getReport (PortReport &reporter)=0
 Get information on the state of the port - connections etc.
 
virtual void setReporter (PortReport &reporter)=0
 Set a callback to be called upon any future connections and disconnections to/from the port.
 
virtual void resetReporter ()=0
 Remove the callback which is called upon any future connections and disconnections to/from the port.
 
virtual bool isWriting ()=0
 Report whether the port is currently writing data.
 
virtual void setReader (PortReader &reader)=0
 Set an external reader for port data.
 
virtual void setAdminReader (PortReader &reader)=0
 Set an external reader for unrecognized administrative port messages.
 
virtual void setInputMode (bool expectInput)=0
 Configure the port to allow or forbid inputs.
 
virtual void setOutputMode (bool expectOutput)=0
 Configure the port to allow or forbid outputs.
 
virtual void setRpcMode (bool expectRpc)=0
 Configure the port to be RPC only.
 
virtual Type getType ()=0
 Get the type of data the port has committed to send/receive.
 
virtual void promiseType (const Type &typ)=0
 Commit the port to a particular type of data.
 
virtual PropertyacquireProperties (bool readOnly)=0
 Access unstructured port properties.
 
virtual void releaseProperties (Property *prop)=0
 End access unstructured port properties.
 
void setReadOnly ()
 Shorthand for setInputMode(true), setOutputMode(false), setRpcMode(false)
 
void setWriteOnly ()
 Shorthand for setInputMode(false), setOutputMode(true), setRpcMode(false)
 
void setRpcServer ()
 Shorthand for setInputMode(true), setOutputMode(false), setRpcMode(true)
 
void setRpcClient ()
 Shorthand for setInputMode(false), setOutputMode(true), setRpcMode(true)
 
virtual bool setCallbackLock (std::mutex *mutex=nullptr)=0
 Add a lock to use when invoking callbacks.
 
virtual bool removeCallbackLock ()=0
 Remove a lock on callbacks added with setCallbackLock()
 
virtual bool lockCallback ()=0
 Lock callbacks until unlockCallback() is called.
 
virtual bool tryLockCallback ()=0
 Try to lock callbacks until unlockCallback() is called.
 
virtual void unlockCallback ()=0
 Unlock callbacks.
 

Detailed Description

An abstract port.

Anything that can be expressed via a Contact.

Definition at line 27 of file Contactable.h.

Constructor & Destructor Documentation

◆ ~Contactable()

yarp::os::Contactable::~Contactable ( )
virtualdefault

Destructor.

Member Function Documentation

◆ acquireProperties()

◆ addOutput() [1/3]

◆ addOutput() [2/3]

◆ addOutput() [3/3]

◆ close()

◆ getEnvelope()

virtual bool yarp::os::Contactable::getEnvelope ( PortReader envelope)
pure virtual

Get the envelope information (e.g., a timestamp) from the last message received on the port.

You must be sure to match the type of your envelope for getEnvelope with whatever is being sent using setEnvelope. The Stamp class is a typical choice for timestamps. The Bottle class also works as an envelope, but it is not specialized to be efficient.

Parameters
enveloperecipient for envelope information for last message received by port.
Returns
true iff reading the envelope was successful

Implemented in yarp::os::AbstractContactable, yarp::os::BufferedPort< T >, yarp::os::BufferedPort< DepthImage >, yarp::os::BufferedPort< ImageType >, yarp::os::BufferedPort< JoyData >, yarp::os::BufferedPort< return_getAllTransforms >, yarp::os::BufferedPort< SensorStreamingData >, yarp::os::BufferedPort< VectorOf< unsigned char > >, yarp::os::BufferedPort< yarp::dev::BatteryData >, yarp::os::BufferedPort< yarp::dev::impl::jointData >, yarp::os::BufferedPort< yarp::dev::MobileBaseVelocity >, yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocation >, yarp::os::BufferedPort< yarp::dev::OdometryData >, yarp::os::BufferedPort< yarp::os::Bottle >, yarp::os::BufferedPort< yarp::os::PortablePair >, yarp::os::BufferedPort< yarp::sig::FlexImage >, yarp::os::BufferedPort< yarp::sig::Image >, yarp::os::BufferedPort< yarp::sig::ImageOf< yarp::sig::PixelBgra > >, yarp::os::BufferedPort< yarp::sig::ImageOf< yarp::sig::PixelFloat > >, yarp::os::BufferedPort< yarp::sig::LaserScan2D >, yarp::os::BufferedPort< yarp::sig::Sound >, yarp::os::BufferedPort< yarp::sig::VectorOf >, and yarp::os::Port.

◆ getInputCount()

◆ getName()

◆ getOutputCount()

◆ getReport()

◆ getType()

◆ interrupt()

◆ isWriting()

◆ lockCallback()

◆ open() [1/2]

virtual bool yarp::os::Contactable::open ( const Contact contact,
bool  registerName = true 
)
pure virtual

◆ open() [2/2]

◆ promiseType()

◆ releaseProperties()

◆ removeCallbackLock()

◆ resetReporter()

◆ resume()

◆ setAdminReader()

◆ setCallbackLock()

virtual bool yarp::os::Contactable::setCallbackLock ( std::mutex *  mutex = nullptr)
pure virtual

◆ setEnvelope()

virtual bool yarp::os::Contactable::setEnvelope ( PortWriter envelope)
pure virtual

Set an envelope (e.g., a timestamp) to the next message which will be sent.

You must be sure to match the type of your envelope for setEnvelope with whatever will be read using getEnvelope. The Stamp class is a typical choice for timestamps. The Bottle class also works as an envelope, but it is not specialized to be efficient.

Currently, for proper operation, the envelope must serialize correctly in text-mode (even if you do not explicitly use text-mode connections). Bottle or Stamp are good choices.

Parameters
envelopeinformation to add to the next message which will be sent
Returns
true iff setting the envelope was successful

Implemented in yarp::os::AbstractContactable, yarp::os::BufferedPort< T >, yarp::os::BufferedPort< DepthImage >, yarp::os::BufferedPort< ImageType >, yarp::os::BufferedPort< JoyData >, yarp::os::BufferedPort< return_getAllTransforms >, yarp::os::BufferedPort< SensorStreamingData >, yarp::os::BufferedPort< VectorOf< unsigned char > >, yarp::os::BufferedPort< yarp::dev::BatteryData >, yarp::os::BufferedPort< yarp::dev::impl::jointData >, yarp::os::BufferedPort< yarp::dev::MobileBaseVelocity >, yarp::os::BufferedPort< yarp::dev::Nav2D::Map2DLocation >, yarp::os::BufferedPort< yarp::dev::OdometryData >, yarp::os::BufferedPort< yarp::os::Bottle >, yarp::os::BufferedPort< yarp::os::PortablePair >, yarp::os::BufferedPort< yarp::sig::FlexImage >, yarp::os::BufferedPort< yarp::sig::Image >, yarp::os::BufferedPort< yarp::sig::ImageOf< yarp::sig::PixelBgra > >, yarp::os::BufferedPort< yarp::sig::ImageOf< yarp::sig::PixelFloat > >, yarp::os::BufferedPort< yarp::sig::LaserScan2D >, yarp::os::BufferedPort< yarp::sig::Sound >, yarp::os::BufferedPort< yarp::sig::VectorOf >, and yarp::os::Port.

◆ setInputMode()

◆ setOutputMode()

◆ setReader()

◆ setReadOnly()

void yarp::os::Contactable::setReadOnly ( )

Shorthand for setInputMode(true), setOutputMode(false), setRpcMode(false)

Definition at line 19 of file Contactable.cpp.

◆ setReporter()

◆ setRpcClient()

void yarp::os::Contactable::setRpcClient ( )

Shorthand for setInputMode(false), setOutputMode(true), setRpcMode(true)

Definition at line 40 of file Contactable.cpp.

◆ setRpcMode()

◆ setRpcServer()

void yarp::os::Contactable::setRpcServer ( )

Shorthand for setInputMode(true), setOutputMode(false), setRpcMode(true)

Definition at line 33 of file Contactable.cpp.

◆ setWriteOnly()

void yarp::os::Contactable::setWriteOnly ( )

Shorthand for setInputMode(false), setOutputMode(true), setRpcMode(false)

Definition at line 26 of file Contactable.cpp.

◆ tryLockCallback()

◆ unlockCallback()

◆ where()


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