An abstract unbuffered port. More...
#include <yarp/os/UnbufferedContactable.h>
Public Member Functions | |
virtual bool | write (const PortWriter &writer, const PortWriter *callback=nullptr) const =0 |
Write an object to the port. | |
virtual bool | write (const PortWriter &writer, PortReader &reader, const PortWriter *callback=nullptr) const =0 |
Write an object to the port, then expect one back. | |
virtual bool | read (PortReader &reader, bool willReply=false)=0 |
Read an object from the port. | |
virtual bool | reply (PortWriter &writer)=0 |
Send an object as a reply to an object read from the port. | |
virtual bool | replyAndDrop (PortWriter &writer)=0 |
Same as reply(), but closes connection after reply. | |
Public Member Functions inherited from yarp::os::Contactable | |
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 Property * | acquireProperties (bool readOnly)=0 |
Access unstructured port properties. | |
virtual void | releaseProperties (Property *prop)=0 |
End access unstructured port properties. | |
virtual void | includeNodeInName (bool flag)=0 |
Choose whether to prepend a node name (if one is available) to the port's name. | |
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. | |
An abstract unbuffered port.
Definition at line 17 of file UnbufferedContactable.h.
|
pure virtual |
Read an object from the port.
reader | any object that knows how to read itself from a network connection - see for example Bottle |
willReply | you must set this to true if you intend to call reply() |
Implemented in yarp::os::AbstractContactable, yarp::os::Port, yarp::os::RpcClient, yarp::os::Subscriber< T >, yarp::os::Subscriber< yarp::rosmsg::geometry_msgs::Twist >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Subscriber< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::Subscriber< yarp::rosmsg::tf2_msgs::TFMessage >, and yarp::os::RpcServer.
|
pure virtual |
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.
writer | any object that knows how to write itself to a network connection - see for example Bottle |
Implemented in yarp::os::AbstractContactable, yarp::os::Port, and yarp::os::RpcClient.
|
pure virtual |
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.
writer | any object that knows how to write itself to a network connection - see for example Bottle |
Implemented in yarp::os::AbstractContactable, yarp::os::Port, and yarp::os::RpcClient.
|
pure virtual |
Write an object to the port.
writer | any object that knows how to write itself to a network connection - see for example Bottle |
callback | object on which to call onCompletion() after write is done (otherwise writer.onCompletion() is called) |
Implemented in yarp::os::AbstractContactable, yarp::os::Port, yarp::os::Publisher< T >, yarp::os::Publisher< ROS_MSG >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::MagneticField >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::PointCloud2 >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Publisher< yarp::rosmsg::visualization_msgs::MarkerArray >, and yarp::os::RpcServer.
|
pure virtual |
Write an object to the port, then expect one back.
writer | any object that knows how to write itself to a network connection - see for example Bottle |
reader | any object that knows how to read itself from a network connection - see for example Bottle |
callback | object on which to call onCompletion() after write is done (otherwise writer.onCompletion() is called) |
Implemented in yarp::os::AbstractContactable, yarp::os::Port, yarp::os::Publisher< T >, yarp::os::Publisher< ROS_MSG >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::PoseStamped >, yarp::os::Publisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::MapMetaData >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::OccupancyGrid >, yarp::os::Publisher< yarp::rosmsg::nav_msgs::Odometry >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::CameraInfo >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Image >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::JointState >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::LaserScan >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::MagneticField >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::PointCloud2 >, yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Temperature >, yarp::os::Publisher< yarp::rosmsg::tf2_msgs::TFMessage >, yarp::os::Publisher< yarp::rosmsg::visualization_msgs::MarkerArray >, and yarp::os::RpcServer.