YARP
Yet Another Robot Platform
yarp::os::AbstractContactable Class Referenceabstract

A default implementation of an abstract port. More...

#include <yarp/os/AbstractContactable.h>

+ Inheritance diagram for yarp::os::AbstractContactable:

Public Member Functions

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

Detailed Description

A default implementation of an abstract port.

The class hierarchy for ports is misshapen because we want to keep it SWIG compatible, and SWIG can't yet produce good translations of code that in C++ looks like multiple inheritance but is in fact just implementing multiple interfaces. There's work in SWIG on supporting interfaces, so this can be simplified a lot at that point.

Definition at line 27 of file AbstractContactable.h.

Member Function Documentation

◆ acquireProperties()

yarp::os::Property * yarp::os::AbstractContactable::acquireProperties ( bool  readOnly)
overridevirtual

Access unstructured port properties.

Parameters
readOnlyset this if you won't be modifying the properties.
Returns
the port properties (or nullptr if readOnly and none have been set)
Warning
Must be called in the same thread as releaseProperties

Implements yarp::os::Contactable.

Definition at line 139 of file AbstractContactable.cpp.

◆ addOutput() [1/3]

bool yarp::os::AbstractContactable::addOutput ( const Contact contact)
overridevirtual

Add an output connection to the specified port, using specified network parameters.

Parameters
contactinformation on how to reach the target
Returns
true iff the connection is successfully created

Implements yarp::os::Contactable.

Definition at line 34 of file AbstractContactable.cpp.

◆ addOutput() [2/3]

bool yarp::os::AbstractContactable::addOutput ( const std::string &  name)
overridevirtual

Add an output connection to the specified port.

Parameters
namethe name of the target port
Returns
true iff the connection is successfully created

Implements yarp::os::Contactable.

Definition at line 23 of file AbstractContactable.cpp.

◆ addOutput() [3/3]

bool yarp::os::AbstractContactable::addOutput ( const std::string &  name,
const std::string &  carrier 
)
overridevirtual

Add an output connection to the specified port, using a specified carrier.

Parameters
namethe name of the target port
carrierthe carrier (network protocol) to use, e.g. "tcp", "udp", "mcast", "text", ...
Returns
true iff the connection is successfully created

Implements yarp::os::Contactable.

Definition at line 28 of file AbstractContactable.cpp.

◆ asPort() [1/2]

virtual const Port& yarp::os::AbstractContactable::asPort ( ) const
pure virtual

Get the concrete Port being used for communication, const version.

Implemented in yarp::os::Subscriber< T >, yarp::os::RpcServer, yarp::os::RpcClient, and yarp::os::Publisher< T >.

◆ asPort() [2/2]

virtual Port& yarp::os::AbstractContactable::asPort ( )
pure virtual

Get the concrete Port being used for communication.

Implemented in yarp::os::Subscriber< T >, yarp::os::Subscriber< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::Image >, yarp::os::RpcServer, yarp::os::RpcClient, yarp::os::Publisher< T >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::Publisher< ROS_MSG >, yarp::os::Publisher< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::MagneticField >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu >, yarp::os::Subscriber< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::Publisher< ROS_MSG >, yarp::os::Publisher< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::MagneticField >, and yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu >.

◆ close()

◆ getEnvelope()

bool yarp::os::AbstractContactable::getEnvelope ( PortReader envelope)
overridevirtual

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

Implements yarp::os::Contactable.

Definition at line 69 of file AbstractContactable.cpp.

◆ getInputCount()

int yarp::os::AbstractContactable::getInputCount ( )
overridevirtual

Determine how many connections are arriving into this port.

In other words, how many other ports have this port listed as an output?

Returns
number of input connections

Implements yarp::os::Contactable.

Definition at line 74 of file AbstractContactable.cpp.

◆ getName()

std::string yarp::os::AbstractContactable::getName ( ) const
overridevirtual

Get name of port.

Returns
name of port

Reimplemented from yarp::os::Contactable.

Definition at line 59 of file AbstractContactable.cpp.

◆ getOutputCount()

int yarp::os::AbstractContactable::getOutputCount ( )
overridevirtual

Determine how many output connections this port has.

Returns
number of output connections

Implements yarp::os::Contactable.

Definition at line 79 of file AbstractContactable.cpp.

◆ getReport()

void yarp::os::AbstractContactable::getReport ( PortReport reporter)
overridevirtual

Get information on the state of the port - connections etc.

PortReport::report will be called once for each connection to the port that exists right now. To request callbacks for any future connections/disconnections, use the setReporter method instead.

Parameters
reportercallback for port event/state information

Implements yarp::os::Contactable.

Definition at line 84 of file AbstractContactable.cpp.

◆ getType()

yarp::os::Type yarp::os::AbstractContactable::getType ( )
overridevirtual

Get the type of data the port has committed to send/receive.

Not all ports commit to a particular type of data.

Returns
type of data to expect/provide

Implements yarp::os::Contactable.

Definition at line 129 of file AbstractContactable.cpp.

◆ includeNodeInName()

void yarp::os::AbstractContactable::includeNodeInName ( bool  flag)
overridevirtual

Choose whether to prepend a node name (if one is available) to the port's name.

Node names are set using yarp::os::Node.

Parameters
flagtrue if the node name should be added to port names

Implements yarp::os::Contactable.

Definition at line 178 of file AbstractContactable.cpp.

◆ interrupt()

void yarp::os::AbstractContactable::interrupt ( )
overridevirtual

Interrupt any current reads or writes attached to the port.

This is useful prior to calling close(), if there are multiple threads operating on the port. Any reads or writes after the call to interrupt() will fail - unless resume() is called.

Implements yarp::os::Contactable.

Reimplemented in yarp::os::Subscriber< T >, yarp::os::Subscriber< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< T >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::Publisher< ROS_MSG >, yarp::os::Publisher< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::MagneticField >, and yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu >.

Definition at line 44 of file AbstractContactable.cpp.

◆ isWriting()

bool yarp::os::AbstractContactable::isWriting ( )
overridevirtual

Report whether the port is currently writing data.

Returns
true iff the port is writing in the background.

Implements yarp::os::Contactable.

Definition at line 99 of file AbstractContactable.cpp.

◆ lockCallback()

bool yarp::os::AbstractContactable::lockCallback ( )
overridevirtual

Lock callbacks until unlockCallback() is called.

Has no effect if no lock has been set via a call to setCallbackLock(). Will block if callbacks are already locked.

Returns
true if callbacks were locked

Implements yarp::os::Contactable.

Definition at line 203 of file AbstractContactable.cpp.

◆ open() [1/2]

bool yarp::os::AbstractContactable::open ( const Contact contact,
bool  registerName = true 
)
overridevirtual

Start port operation with user-chosen network parameters.

Contact information is supplied by the user rather than the name server. If the Contact information is incomplete, the name server is used to complete it (set registerName to false if you don't want name server help).

Returns
true iff the port started operation successfully and is now visible on the YARP network

Implements yarp::os::Contactable.

Reimplemented in yarp::os::Subscriber< T >, yarp::os::Subscriber< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< T >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::Publisher< ROS_MSG >, yarp::os::Publisher< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::MagneticField >, and yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu >.

Definition at line 17 of file AbstractContactable.cpp.

◆ open() [2/2]

bool yarp::os::AbstractContactable::open ( const std::string &  name)
overridevirtual

Start port operation, with a specific name, with automatically-chosen network parameters.

The port is registered with the given name, and allocated network resources, by communicating with the YARP name server.

Returns
true iff the port started operation successfully and is now visible on the YARP network

Implements yarp::os::Contactable.

Reimplemented in yarp::os::Subscriber< T >, yarp::os::Subscriber< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< T >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::Publisher< ROS_MSG >, yarp::os::Publisher< yarp::rosmsg::visualization_msgs::MarkerArray >, yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::MagneticField >, and yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu >.

Definition at line 12 of file AbstractContactable.cpp.

◆ promiseType()

void yarp::os::AbstractContactable::promiseType ( const Type typ)
overridevirtual

Commit the port to a particular type of data.

Parameters
typthe type of data the port will send/receive

Implements yarp::os::Contactable.

Definition at line 134 of file AbstractContactable.cpp.

◆ read()

bool yarp::os::AbstractContactable::read ( PortReader reader,
bool  willReply = false 
)
overridevirtual

Read an object from the port.

Parameters
readerany object that knows how to read itself from a network connection - see for example Bottle
willReplyyou must set this to true if you intend to call reply()
Returns
true iff the object is successfully read

Implements yarp::os::UnbufferedContactable.

Reimplemented in yarp::os::RpcServer, and yarp::os::RpcClient.

Definition at line 162 of file AbstractContactable.cpp.

◆ releaseProperties()

void yarp::os::AbstractContactable::releaseProperties ( Property prop)
overridevirtual

End access unstructured port properties.

Parameters
propthe port property object provided by acquireProperties()
Warning
Must be called in the same thread as acquireProperties

Implements yarp::os::Contactable.

Definition at line 144 of file AbstractContactable.cpp.

◆ removeCallbackLock()

bool yarp::os::AbstractContactable::removeCallbackLock ( )
overridevirtual

Remove a lock on callbacks added with setCallbackLock()

Implements yarp::os::Contactable.

Definition at line 198 of file AbstractContactable.cpp.

◆ reply()

bool yarp::os::AbstractContactable::reply ( PortWriter writer)
overridevirtual

Send an object as a reply to an object read from the port.

Only call this method if you set the willReply flag to true when you called Port::read.

Parameters
writerany object that knows how to write itself to a network connection - see for example Bottle
Returns
true iff the object is successfully written

Implements yarp::os::UnbufferedContactable.

Reimplemented in yarp::os::RpcClient.

Definition at line 168 of file AbstractContactable.cpp.

◆ replyAndDrop()

bool yarp::os::AbstractContactable::replyAndDrop ( PortWriter writer)
overridevirtual

Same as reply(), but closes connection after reply.

This is useful for interoperation with XML/RPC clients that do not expect to reuse a connection.

Parameters
writerany object that knows how to write itself to a network connection - see for example Bottle
Returns
true iff the object is successfully written

Implements yarp::os::UnbufferedContactable.

Reimplemented in yarp::os::RpcClient.

Definition at line 173 of file AbstractContactable.cpp.

◆ resetReporter()

void yarp::os::AbstractContactable::resetReporter ( )
overridevirtual

Remove the callback which is called upon any future connections and disconnections to/from the port.

Implements yarp::os::Contactable.

Definition at line 94 of file AbstractContactable.cpp.

◆ resume()

void yarp::os::AbstractContactable::resume ( )
overridevirtual

◆ setAdminReader()

void yarp::os::AbstractContactable::setAdminReader ( PortReader reader)
overridevirtual

Set an external reader for unrecognized administrative port messages.

Parameters
readerthe external reader to use

Implements yarp::os::Contactable.

Definition at line 109 of file AbstractContactable.cpp.

◆ setCallbackLock() [1/2]

bool yarp::os::AbstractContactable::setCallbackLock ( std::mutex *  mutex = nullptr)
overridevirtual

Add a lock to use when invoking callbacks.

mutex.lock() will be called before and mutex.unlock() will be called after the callback. This applies at least to callbacks set by setReader and setAdminReader, and in future may apply to other callbacks.

Parameters
mutexthe lock to use. If nullptr, a mutex will be allocated internally by the port, and destroyed with the port.

Implements yarp::os::Contactable.

Definition at line 193 of file AbstractContactable.cpp.

◆ setCallbackLock() [2/2]

bool yarp::os::AbstractContactable::setCallbackLock ( yarp::os::Mutex mutex)
overridevirtual

Add a lock to use when invoking callbacks.

mutex.lock() will be called before and mutex.unlock() will be called after the callback. This applies at least to callbacks set by setReader and setAdminReader, and in future may apply to other callbacks.

Parameters
mutexthe lock to use. If nullptr, a mutex will be allocated internally by the port, and destroyed with the port.
Deprecated:
since YARP 3.3

Implements yarp::os::Contactable.

Definition at line 186 of file AbstractContactable.cpp.

◆ setEnvelope()

bool yarp::os::AbstractContactable::setEnvelope ( PortWriter envelope)
overridevirtual

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

Implements yarp::os::Contactable.

Definition at line 64 of file AbstractContactable.cpp.

◆ setInputMode()

void yarp::os::AbstractContactable::setInputMode ( bool  expectInput)
overridevirtual

Configure the port to allow or forbid inputs.

By default, ports allow anything.

Parameters
expectInputset to true if this port will be used for input

Implements yarp::os::Contactable.

Reimplemented in yarp::os::RpcServer, and yarp::os::RpcClient.

Definition at line 114 of file AbstractContactable.cpp.

◆ setOutputMode()

void yarp::os::AbstractContactable::setOutputMode ( bool  expectOutput)
overridevirtual

Configure the port to allow or forbid outputs.

By default, ports allow anything.

Parameters
expectOutputset to true if this port will be used for output

Implements yarp::os::Contactable.

Reimplemented in yarp::os::RpcServer, and yarp::os::RpcClient.

Definition at line 119 of file AbstractContactable.cpp.

◆ setReader()

void yarp::os::AbstractContactable::setReader ( PortReader reader)
overridevirtual

◆ setReporter()

void yarp::os::AbstractContactable::setReporter ( PortReport reporter)
overridevirtual

Set a callback to be called upon any future connections and disconnections to/from the port.

To get information on the current connections that exist, use the getReport method instead.

Parameters
reportercallback for port event/state information

Implements yarp::os::Contactable.

Definition at line 89 of file AbstractContactable.cpp.

◆ setRpcMode()

void yarp::os::AbstractContactable::setRpcMode ( bool  expectRpc)
overridevirtual

Configure the port to be RPC only.

By default all ports can be used for RPC or streaming communication.

Parameters
expectRpcset to true if this port will be used for RPC only

Implements yarp::os::Contactable.

Reimplemented in yarp::os::RpcServer, and yarp::os::RpcClient.

Definition at line 124 of file AbstractContactable.cpp.

◆ tryLockCallback()

bool yarp::os::AbstractContactable::tryLockCallback ( )
overridevirtual

Try to lock callbacks until unlockCallback() is called.

Has no effect if no lock has been set via a call to setCallbackLock(). Returns immediately.

Returns
true if callbacks were locked by this call, false if they were already locked.

Implements yarp::os::Contactable.

Definition at line 208 of file AbstractContactable.cpp.

◆ unlockCallback()

void yarp::os::AbstractContactable::unlockCallback ( )
overridevirtual

Unlock callbacks.

Implements yarp::os::Contactable.

Definition at line 213 of file AbstractContactable.cpp.

◆ where()

yarp::os::Contact yarp::os::AbstractContactable::where ( ) const
overridevirtual

Returns information about how this port can be reached.

Returns
network parameters for this port

Implements yarp::os::Contactable.

Definition at line 54 of file AbstractContactable.cpp.

◆ write() [1/2]

bool yarp::os::AbstractContactable::write ( const PortWriter writer,
const PortWriter callback = nullptr 
) const
overridevirtual

Write an object to the port.

Parameters
writerany object that knows how to write itself to a network connection - see for example Bottle
callbackobject on which to call onCompletion() after write is done (otherwise writer.onCompletion() is called)
Returns
true iff the object is successfully written

Implements yarp::os::UnbufferedContactable.

Reimplemented in yarp::os::RpcServer.

Definition at line 149 of file AbstractContactable.cpp.

◆ write() [2/2]

bool yarp::os::AbstractContactable::write ( const PortWriter writer,
PortReader reader,
const PortWriter callback = nullptr 
) const
overridevirtual

Write an object to the port, then expect one back.

Parameters
writerany object that knows how to write itself to a network connection - see for example Bottle
readerany object that knows how to read itself from a network connection - see for example Bottle
callbackobject on which to call onCompletion() after write is done (otherwise writer.onCompletion() is called)
Returns
true iff an object is successfully written and read

Implements yarp::os::UnbufferedContactable.

Reimplemented in yarp::os::RpcServer.

Definition at line 155 of file AbstractContactable.cpp.


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