Module Api

rocon_app_manager

rocon_app_manager.standalone

Provides a class for instantiating a rapp manager for standalone use, i.e. not multi-robot.


class rocon_app_manager.standalone.Standalone[source]

Bases: object

Standalone version of the rapp manager. An instance of this type only concerns itself with one job - that of rapp management.

Publishers

  • ~status (rapp_manager_msgs.Status) - running status of the rapp manager [latched]
  • ~rapp_list (rapp_manager_msgs.RappList) - the successfully loaded rapp list [latched]
  • ~incompatible_rapp_list (rapp_manager_msgs.IncompatibleRappList) - rapps filtered from the startup list for various reasons [latched]
  • ~parameters (std_msgs.String) - displays the parameters used for this instantiation [latched]

Services

  • ~list_rapps (rapp_manager_srvs.GetRappList*) - service equivalent of the rapp_list topic
  • ~start_rapp (rapp_manager_srvs.StartRapp*) - service to start a rapp
  • ~stop_rapp (rapp_manager_srvs.StopRapp*) - service to stop a rapp

Parameters

Variables:
  • current_rapp (rocon_app_manager.rapp.Rapp) – currently running rapp, otherwise None
  • rocon_uri (str) – this platform’s signature used to determine if a rapp is compatible or not
  • runnable_apps – these apps pass all filters and can be run
  • installable_apps – if the auto_rapp_installation parameter is set, then these rapps can be installed
  • noninstallable_apps – if the auto_rapp_installation parameter is set, but dependencies aren’t met, it populates this list
  • platform_filtered_apps – rapps that don’t match the platform that this rapp manager is running on
  • capabilities_filtered_apps – rapps that don’t have the required runtime capability support on this platform
  • invalid_apps – rapps that are invalid for some reason, e.g. bad specification syntax
  • services (rocon_python_comms.Services) – all ros services this instance provides
  • publishers (rocon_python_comms.Publishers) – all ros publishers this instance provides
  • indexer (rocon_app_utilities.RappIndexer) – indexes all rapps on the system
  • parameters (dict of string:value pairs.) – all ros parameters for this instance organised in a dictionary
spin()[source]

A default spinner. Child classes will overload this with their own custom spinners.

rocon_app_manager.concertified

rocon_app_manager.rapp

class rocon_app_manager.rapp.Rapp(rapp_specification)[source]

Bases: object

Got many inspiration and imported from willow_app_manager implementation

install(dependency_checker)[source]

Installs all dependencies of the specified rapp

Parameters:dependency_checker (rocon_app_utilities.rapp_repositories.DependencyChecker) – DependencyChecker object for installation of the rapp dependencies
Returns:A C{tuple} of a flag for the installation success and a string containing the reason of failure
Return type:C{tuple}
is_running()[source]

Is the rapp both launched and currently running?

Actually three possible states 1) not launched 2) running, 3) stopped Could acutally return a tertiary value, but rapp manager doesn’t need to make any decision making about that (for now), so just return running or not.

Used by the rapp_manager_script.

Returns:True if the rapp is executing or False otherwise.
Return type:Bool
published_interfaces_to_msg_list()[source]

Convert the published interfaces as a rocon_app_manager_msgs.PublishedInterface list.

published_parameters_to_msg_list()[source]

Convert the published parameters as a rocon_std_msgs.KeyValue list.

start(launch_arg_mappings, remappings=[], parameters=[], force_screen=False, caps_list=None)[source]

Some important jobs here.

  1. run the rapp launcher under the unique robot name namespace

This guarantees that flipped entities generate unique node id’s that won’t collide when communicating with each other (refer to https://github.com/robotics-in-py/rocon_multimaster/issues/136).

  1. Apply remapping rules while ignoring the namespace underneath.

:param utils.LaunchArgMappings launch_arg_mappings : args to be passed down from the rapp manager to rapp :param remapping: rules for the app flips. :type remapping: list of rocon_std_msgs.msg.Remapping values. :param parameters: requested public_parameters :type parameters: list of rocon_std_msgs.msg.KeyValue :param bool force_screen: whether to roslaunch the app with –screen or not :param caps_list: this holds the list of available capabilities, if app needs capabilities :type caps_list: CapsList

to_msg()[source]

Converts this app definition to ros msg format.

Returns:ros message format of Rapp
Return type:rocon_app_manager_msgs.Rapp
rocon_app_manager.rapp.convert_rapps_from_rapp_specs(rapp_specs)[source]

Converts rocon_app_utilities.Rapp into rocon_app_manager.Rapp

Parameters:rapp_specs ({ancestor_name: rocon_app_utilities.Rapp}) – dict of rapp specification
Returns:runnable rapps
Return type:{ancestor_name:rocon_app_manager.Rapp}

rocon_app_manager.caps_list

Capabilities handling for the app manager

class rocon_app_manager.caps_list.CapsList[source]

Bases: object

CapsLists stores the data about the available capabilities retrieved from the capability server

compatibility_check(app)[source]

Checks, if all required capabilities of an app are available

Parameters:app (Rapp) – app data of the app to be checked
Raises:MissingCapabilitiesException – One or more required capabilities are not available.
get_cap_remappings(cap, caps_remap_from_list, caps_remap_to_list)[source]

Gathers the required remappings for a specific capability

The rapp description is expected to define all topics, services and actions required for the capability interfaces the rapp is depending on. This information is added to the ‘caps_remap_from_list’ list.

Next the (semantic) capability’s interface specification as well as the provider specification is parsed in order to determine the new topic, service and action names. Here three cases are possible:

  • if normal interface, remap to what is specified there
  • if semantic interface, remap to the semantic interface’s remappings
  • if the provider specifies own remappings, apply them as well

The final remapping is stored in ‘caps_remap_to_list’.

Parameters:
  • cap – cap data as specified in the rapp description
  • caps_remap_from_list – topics to be remapped
  • caps_remap_to_list – new names for remapped topics
Raises:
  • MissingCapabilitiesException – The requested capability is not available.
  • rospy.ServiceException – Failed to retrieve provider remappings from capability server.
start_capability(name, preferred_provider=None)[source]

Triggers the start of the capability via the capability server

Parameters:
  • name (string) – name of the capability to start
  • preferred_provider (string) – name of the preferred provider of the capability (optional)
Returns:

true, if using the capability succeeded, false otherwise

Return type:

boolean

stop_capability(name)[source]

Triggers the stop of the capability via the capability server

Parameters:name (string) – name of the capability to stop
Returns:true, if freeing the capability succeeded, false otherwise
Return type:boolean
rocon_app_manager.caps_list.start_capabilities_from_caps_list(capabilities, caps_list)[source]

Starts up all required capaibilities

Parameters:
  • capaibilities – list of starting capabilities
  • caps_list – capability list
Type:

list of capabilities

Type:

CapsList

Returns:

True if successful. False with reason if it fails

Return type:

boolean, string

rocon_app_manager.caps_list.stop_capabilities_from_caps_list(capabilities, caps_list)[source]

Starts up all required capaibilities

Parameters:
  • capaibilities – list of starting capabilities
  • caps_list – capability list
Type:

list of capabilities

Type:

CapsList

Returns:

True if successful. False with reason if it fails

Return type:

boolean, string

rocon_app_manager.ros_parameters

class rocon_app_manager.ros_parameters.ConcertParameters[source]

The variables of this class are default constructed from parameters on the ros parameter server. Each parameter is nested in the private namespace of the node which instantiates this class.

Variables:concert_whitelist – used for rocon_uri rapp compatibility checks [‘rapp_manager_script’]
class rocon_app_manager.ros_parameters.StandaloneParameters[source]

The variables of this class are default constructed from parameters on the ros parameter server. Each parameter is nested in the private namespace of the node which instantiates this class.

Variables:
  • robot_type (str) – used for rocon_uri rapp compatibility checks [‘robot’]
  • robot_name (str) – also used for rocon_uri rapp compatibility checks [‘robot’]
  • auto_start_rapp (str) – indicates via a resource name (e.g. gopher_rapps/delivery) a rapp to launch on startup [None]
  • rapp_package_whitelist ([ str ]) – restrict rapp search (default is the whole workspace) to these packages [[]]
  • rapp_package_blacklist ([ str ]) – if no whitelist, blacklist these packages from the search [[]]
  • screen (bool) – verbose rapp output to screen [False]
  • auto_rapp_installation (bool) – install dependencies on rapp start [False]
  • preferred ({str}) – configure a dict of preferred child rapps when there are several choices [{}]
  • public_namespace (str) – a hint for where rapps should lay down public connections [‘/applications’]

Each element in the dict of preferred rapps should identify the preferred child rapp for each parent rapp specification. e.g. if the parent rapp is rocon_apps/chirp and there are child rapps rocon_apps/moo, gopher_rapps/groot, then preferred = {‘rocon_apps/chirp’: ‘gopher_rapps/groot’} would ensure that groot is played each time the rocon_apps/chirp is requested. This is usually supplied to a ros launcher via yaml.

The screen flag also checks for the ros parameter in /rocon/screen to assist in providing verbose output when used in conjunction with rocon_launch.

rocon_app_manager.utils

class rocon_app_manager.utils.LaunchArgMappings[source]

Launch arguments that are transferrable to rapps from the rapp manager via the rapp manager manufactured relay launcher.

rocon_app_manager.utils.apply_remapping_rules_from_capabilities(launch_spec, data, caps_list)[source]

applies remapping rules from capabilities

Parameters:
  • launch_spec (roslaunch.parent.ROSLaunchParent) – rapp launch specification
  • data (dict) – rapp data
  • caps_list (CapsList) – this holds the list of available capabilities, if app needs capabilities
Raises:
  • MissingCapabilitiesException – One or more capabilities are unavailable
  • rospy.ServiceException – Coulnd’t get cap remappings from capability server
rocon_app_manager.utils.apply_remapping_rules_from_start_app_request(launch_spec, data, remappings, application_namespace)[source]

applies remapping rules which are requested by start_app service

Parameters:
  • launch_spec (roslaunch.parent.ROSLaunchParent) – rapp launch specification
  • data (dict) – rapp data
  • remapping (list of rocon_std_msgs.msg.Remapping values.) – rules for the app flips.
  • application_namespace (str) – unique name granted indirectly via the gateways, we namespace everything under this
Returns:

Remapped public_interface dictionary

Return type:

{ connection_type: Remapping topic list}

rocon_app_manager.utils.apply_requested_public_parameters(default_parameters, requested_parameters)[source]

validate the requested public parameters, and apply them

Parameters:
  • default_parameters (dict) – default public parameters written in rapp specification
  • requested_parameters ([rocon_std_msgs.KeyValue]) – given from start_rapp request
Returns:

A resolved public_parameters

Return type:

{name: value}

rocon_app_manager.utils.dict_to_key_value_msg(d)[source]

Converts a dictionary to key value ros msg type. :param d: dictionary :type d: dict :returns: KeyValue ros message :rtype: [rocon_std_msgs.KeyValue]

rocon_app_manager.utils.prepare_launcher(data, public_parameters, force_screen, launch_arg_mappings, temp)[source]

prepare roslaunch to start rapp.

rocon_app_manager.utils.resolve_chain_remappings(nodes)[source]

Resolve chain remapping rules contained in node remapping arguments replace the node remapping argument

Parameters:nodes (roslaunch.Nodes[]) – roslaunch nodes