The Client Module

Provides a simple Python interface for interacting with the capability server.

Typical usage:

>>> from capabilities.client import Client
>>> client = Client()
>>> # Use the line below if the capability_server has a different name
>>> # client = Client(capability_server_node_name='/capability_server_node_name')
>>> if not client.wait_for_services(3.0):  # Wait upto 3.0 seconds for the required ROS services
...     import sys
...     sys.exit("capability_server, called '{0}', failed to come up.".format(client._name))
>>> client.use_capability('foo_pkg/Foo')
>>> client.use_capability('foo_pkg/Foo')
>>> client.free_capability('foo_pkg/Foo')
>>> client.shutdown()
class capabilities.client.CapabilitiesClient(capability_server_node_name='/capability_server')[source]

Single point of entry for interacting with a remote capability server.

Instantiation of this class does not check to see if the underlying services are available, call wait_for_services() if you want to ensure that the services are available before continuing.

Parameters:capability_server_node_name (str) – name of the remote capability server
establish_bond(timeout=None)[source]

Establishes a bond using the ~establish_bond service call

The bond id which is returned by the service call is stored internally and used implicitly by the use/free capabilities functions.

If establish_bond() had previously been called, then the old bond will be broken, which will result in any capability uses under that bond to be implicitly freed.

This function is called implicitly by use_capability() if no bond exists.

This function will block waiting for the service call to become available and to wait for the bond to be established. In both cases the timeout parameter is used.

None is returned if the timeout occurs while waiting on the service to become available or while waiting for the bond to form.

Parameters:timeout (float) – time in seconds to wait for the service to be available
Returns:the bond_id received from the server or None on failure
Return type:str
free_capability(capability_interface, timeout=None)[source]

Free’s a previously used capability.

Calls the ~free_capability service, which effectively decrements the internal reference count for that capability in the remote capability server.

If that results in a reference count of zero, then the capability server will shutdown that capability automatically.

Parameters:
  • capability_interface (str) – Name of the capability interface to free up
  • timeout (float) – time to wait on service to be available (optional)
Returns:

True if successful, otherwise False

Return type:

bool

Raises:

CapabilityNotInUseException if the capability has not been previously used

Raises:

CapabilityNotRunningException if the capability has already been stopped which can be caused by a capability it depends on stopping

Raises:

ServiceNotAvailableException if the required service is not available after the timeout has expired

shutdown()[source]

Cleanly frees any used capabilities.

use_capability(capability_interface, preferred_provider=None, timeout=None)[source]

Declares that this capability is being used.

Calls the ~use_capability service, and opens a bond with capability server if none exists. This will cause the capability to be started, if it has not been already, and the internal reference count for that capability in the capability server is incremented.

If the bond fails (i.e. this program crashes) then the reference is decremented automatically. The reference is also decremented if free_capability() is called.

Parameters:
  • capability_interface (str) – Name of the capability interface to use
  • preferred_provider (str) – preferred provider or None for default provider (optional)
  • timeout (float) – time to wait on service to be available (optional)
Returns:

True if successful, otherwise False

Return type:

bool

Raises:

ServiceNotAvailableException if the required service is not available after the timeout has expired

Raise:

CannotEstablishBondException is the bond with the capability_server cannot be established

wait_for_services(timeout=None, services=None)[source]

Blocks until the requested services are available.

Services are waited on one at a time. Therefore, if a non-None value for timeout is given, and one or more services are being waited on, the full timeout will be given to each wait, meaning that the total run time of this function can exceed the timeout provided.

Parameters:
  • timeout (float) – Seconds to wait for the services before returning False. If None is passed, then this will block indefinitely until the services are available.
  • services (list) – List of services to wait on. If None is passed, then this will check all the services.
Returns:

True is the services are available, False otherwise (timeout)

Return type:

bool

Previous topic

The capability_server ROS Node

Next topic

The Discovery Module

This Page