This module implements the Capability Interface concept
This module contains free functions which serve as factories for the CapabilityInterface class. These factories can take the spec file for a Capability Interface and create a CapabilityInterface instance out of it. The Interface class encapsulates the interface itself, representing the topics, services, params, etc... The CapabilityInterface class encapsulates meta information about the Interface like the name, description, and extends the Interface class. The Interface class is made up of InterfaceElement‘s which represent the elements of a Capability Interface, each consisting of a name, type, and description.
With an Interface RGBCamera.yaml, like this:
%YAML 1.1
# Capability Interface file for RGBCamera
---
# Name of the Interface
name: RGBCamera
spec_version: 1
spec_type: interface
description: 'This Capability describes the interface exposed by a generic RGBCamera.'
interface:
# Topics
topics:
# Topics provided by the interface
provides:
'camera/image_raw':
type: 'sensor_msgs/Image'
description: 'raw image from the camera'
'camera/camera_info':
type: 'sensor_msgs/CameraInfo'
# Topics expect by the interface
requires: {}
# Services provided by the interface
services:
'camera/set_info':
type: 'sensor_msgs/SetCameraInfo'
You can use this interface like so:
>>> from pprint import pprint
>>> from capabilities.specs.interface import capability_interface_from_file_path
>>> ci = capability_interface_from_file_path('test/unit/specs/interfaces/RGBCamera.yaml')
>>> pprint(ci.topics)
{'camera/camera_info': <capabilities.specs.interface.InterfaceElement object at 0x10736ced0>,
'camera/image_raw': <capabilities.specs.interface.InterfaceElement object at 0x10736cf10>}
>>> print(ci.topics.values()[0].name)
camera/image_raw
>>> print(ci.topics.values()[0].type)
sensor_msgs/Image
>>> print(ci.topics.values()[0].description)
raw image from the camera
>>> pprint(ci.required_services)
{}
>>> pprint(ci.provided_topics)
{'camera/camera_info': <capabilities.specs.interface.InterfaceElement object at 0x10774ce10>,
'camera/image_raw': <capabilities.specs.interface.InterfaceElement object at 0x10774ce50>}
>>> pprint(ci.actions)
{}
Represents a Capability Interface
A Capability Interface is defined by:
Represents the Interface part of a Capability Interface
An Interface can consist of zero to all of these elements:
The groupings ‘requires’ and ‘provides’ are purely semantic, and are not used by the capability system programatically, but instead are there to give more meaning to the developers.
Adds a action to the Interface
Parameters: |
|
---|---|
Raises : | ValueError if the grouping is invalid |
Raises : | RuntimeError if the action is already in the interface |
Adds a dynamic_parameter to the Interface
Parameters: | dynamic_parameter_name (str) – name of the dynamic_parameter |
---|---|
Raises : | RuntimeError if the dynamic_parameter is already in the interface |
Adds a parameter to the Interface
Parameters: |
|
---|---|
Raises : | ValueError if the grouping is invalid |
Raises : | RuntimeError if the parameter is already in the interface |
Adds a service to the Interface
Parameters: |
|
---|---|
Raises : | ValueError if the grouping is invalid |
Raises : | RuntimeError if the service is already in the interface |
Adds a topic to the Interface
Parameters: |
|
---|---|
Raises : | ValueError if the grouping is invalid |
Raises : | RuntimeError if the topic is already in the interface |
Represents a part of an interface
An interface element is defined by:
Raises : | ValueError if the element kind is invalid |
---|
InvalidInterface exception
Creates a CapabilityInterface instance from a dict version of the spec
Parameters: |
|
---|---|
Returns: | CapabilityInterface instance, populated with the provided spec |
Return type: | |
Raises : | InvalidInterface if the spec is not complete or has invalid entries |
Creates a CapabilityInterface instance from a given spec file handle
See capability_interface_from_dict() for list of possible exceptions
Parameters: | file_handle (file) – file handle for the Capability Interface spec file |
---|---|
Returns: | CapabilityInterface instance, populated with data from the spec file |
Return type: | CapabilityInterface |
Raises : | OSError if the given file does not exist |
Creates a CapabilityInterface instance from a spec file at a given path
See capability_interface_from_dict() for list of possible exceptions
Parameters: | file_path (str) – location of the Capability Interface spec file |
---|---|
Returns: | CapabilityInterface instance, populated with data from the spec file |
Return type: | CapabilityInterface |
Raises : | OSError if the given file does not exist |
Creates a CapabilityInterface instance from a string containing the spec
See capability_interface_from_dict() for list of possible exceptions
Parameters: |
|
---|---|
Returns: | CapabilityInterface instance, populated with the provided spec |
Return type: | |
Raises : | AttributeError if the given value for string is not a str |
This module implements the Capability Provider concept
This module contains free functions which serve as factories for the CapabilityProvider class. These factories can take the spec file for a Capability Provider and create a CapabilityProvider instance out of it. The CapabilityProvider class is designed to encapsualte the meta data which describes the Capability Provider.
With a provider spec like this:
%YAML 1.1
---
name: navigation_nav_stack
spec_version: 1
spec_type: provider
description: 'Implements the ability to navigate.'
implements: navigation/Navigation
launch_file: 'launch/navigation_nav_stack.launch'
depends_on:
'laser_capability/LaserObservation':
provider: 'hokuyo_capability/hokuyo_base'
remappings:
topics:
'scan': 'nav_stack/scan'
nodelet_manager: 'nav_manager'
You can use this API like this:
>>> from pprint import pprint
>>> from capabilities.specs.provider import capability_provider_from_file_path
>>> cp = capability_provider_from_file_path('test/unit/specs/providers/navigation_nav_stack.yaml')
>>> pprint(cp.dependencies)
{<capabilities.specs.common.SpecName object at 0x1099ebfd0>:
<capabilities.specs.provider.DependsOnRelationship object at 0x109a3fa50>}
>>> print(cp.dependencies['laser_capability/LaserObservation'])
laser_capability/LaserObservation:
preferred provider: hokuyo_capability/hokuyo_base
>>> print(cp.launch_file)
launch/navigation_nav_stack.launch
>>> print(cp.implements)
navigation/Navigation
>>> print(cp.nodelet_manager)
nav_manager
Represents a Capability Provider
A Capability Provider is defined by:
Models the depends_on relationship between a Capability Provider and a Capability
This relationship consists of:
InvalidProvider exception
Creates a CapabilityProvider instance from a dict version of the spec
Parameters: | |
---|---|
Returns: | CapabilityProvider instance, populated with the provided spec |
Return type: | |
Raises : | InvalidProvider if the spec is not complete or has invalid entries |
Creates a CapabilityProvider instance from a given spec file handle
See capability_provider_from_dict() for list of possible exceptions
Parameters: | file_handle (file) – file handle for the Capability Provider spec file |
---|---|
Returns: | CapabilityProvider instance, populated with data from the spec file |
Return type: | CapabilityProvider |
Raises : | OSError if the given file does not exist |
Creates a CapabilityProvider instance from a spec file at a given path
See capability_provider_from_dict() for list of possible exceptions
Parameters: | file_path (str) – location of the Capability Provider spec file |
---|---|
Returns: | CapabilityProvider instance, populated with data from the spec file |
Return type: | CapabilityProvider |
Raises : | OSError if the given file does not exist |
Creates a CapabilityProvider instance from a string containing the spec
See capability_provider_from_dict() for list of possible exceptions
Parameters: | |
---|---|
Returns: | CapabilityProvider instance, populated with the provided spec |
Return type: | |
Raises : | AttributeError if the given value for string is not a str |
This module implements the Semantic Capability Interface concept
This module contains free functions which serve as factories for the SemanticCapabilityInterface class. These factories can take the spec file for a Semantic Capability Interface and create a SemanticCapabilityInterface instance out of it. The SemanticCapabilityInterface class encapsulates meta information about the semantic interface. The SemanticCapabilityInterface class defines of:
With an Semantic Capability Interface FrontRGBCamera.yaml, like this:
%YAML 1.1
---
name: FrontRGBCamera
spec_version: 1
spec_type: semantic_interface
description: 'This is semantically the Front RGB camera.'
redefines: 'a_package/RGBCamera'
# First the global_namespace is applied to all ROS Names
global_namespace: 'front_camera'
# Then individual remappings are done, and override the global_namespace
remappings:
topics:
'camera/image_raw': 'front_camera/image_raw'
'camera/camera_info': 'front_camera/camera_info'
services:
'camera/set_info': 'front_camera/set_info'
You can use this interface like so:
>>> from pprint import pprint
>>> from capabilities.specs.semantic_interface import semantic_capability_interface_from_file_path
>>> sci = semantic_capability_interface_from_file_path('test/specs/semantic_interfaces/FrontRGBCamera.yaml')
>>> print(sci.redefines)
a_package/RGBCamera
>>> print(sci.global_namespace)
front_camera
>>> pprint(sci.remappings)
{'camera/camera_info': 'front_camera/camera_info',
'camera/image_raw': 'front_camera/image_raw',
'camera/set_info': 'front_camera/set_info'}
InvalidSemanticInterface exception
Represents a Semantic Capability Interface
A Semantic Capability Interface is defined by:
Creates a SemanticCapabilityInterface instance from a dict version of the spec
Parameters: | |
---|---|
Returns: | SemanticCapabilityInterface instance, populated with the provided spec |
Return type: | |
Raises : | InvalidSemanticInterface if the spec is not complete or has invalid entries |
Creates a SemanticCapabilityInterface instance from a given spec file handle
See semantic_capability_interface_from_dict() for list of possible exceptions
Parameters: | file_handle (file) – file handle for the Semantic Capability Interface spec file |
---|---|
Returns: | SemanticCapabilityInterface instance, populated with data from the spec file |
Return type: | SemanticCapabilityInterface |
Raises : | OSError if the given file does not exist |
Creates a SemanticCapabilityInterface instance from a spec file at a given path
See semantic_capability_interface_from_dict() for list of possible exceptions
Parameters: | file_path (str) – location of the Semantic Capability Interface spec file |
---|---|
Returns: | SemanticCapabilityInterface instance, populated with data from the spec file |
Return type: | SemanticCapabilityInterface |
Raises : | OSError if the given file does not exist |
Creates a SemanticCapabilityInterface instance from a string containing the spec
See semantic_capability_interface_from_dict() for list of possible exceptions
Parameters: | |
---|---|
Returns: | SemanticCapabilityInterface instance, populated with the provided spec |
Return type: | |
Raises : | AttributeError if the given value for string is not a str |