Class ResourceManager

Class Documentation

class ResourceManager

Public Functions

ResourceManager(unsigned int update_rate = 100, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface = nullptr)

Default constructor for the Resource Manager.

explicit ResourceManager(const std::string &urdf, bool validate_interfaces = true, bool activate_all = false, unsigned int update_rate = 100, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface = nullptr)

Constructor for the Resource Manager.

The implementation loads the specified urdf and initializes the hardware components listed within as well as populate their respective state and command interfaces.

If the interfaces ought to be validated, the constructor throws an exception in case the URDF lists interfaces which are not available.

Parameters:
  • urdf[in] string containing the URDF.

  • validate_interfaces[in] boolean argument indicating whether the exported interfaces ought to be validated. Defaults to true.

  • activate_all[in] boolean argument indicating if all resources should be immediately activated. Currently used only in tests.

ResourceManager(const ResourceManager&) = delete
~ResourceManager()
void load_urdf(const std::string &urdf, bool validate_interfaces = true, bool load_and_initialize_components = true)

Load resources from on a given URDF.

The resource manager can be post initialized with a given URDF. This is mainly used in conjunction with the default constructor in which the URDF might not be present at first initialization.

Parameters:
  • urdf[in] string containing the URDF.

  • validate_interfaces[in] boolean argument indicating whether the exported interfaces ought to be validated. Defaults to true.

  • load_and_initialize_components[in] boolean argument indicating whether to load and initialize the components present in the parsed URDF. Defaults to true.

bool is_urdf_already_loaded() const

if the resource manager load_urdf(…) function has been called this returns true. We want to permit to load the urdf later on but we currently don’t want to permit multiple calls to load_urdf (reloading/loading different urdf).

Returns:

true if resource manager’s load_urdf() has been already called.

Returns:

false if resource manager’s load_urdf() has not been yet called.

LoanedStateInterface claim_state_interface(const std::string &key)

Claim a state interface given its key.

The resource is claimed as long as being in scope. Once the resource is going out of scope, the destructor returns.

Parameters:

key[in] String identifier which state interface to claim

Returns:

state interface

std::vector<std::string> state_interface_keys() const

Returns all registered state interfaces keys.

The keys are collected from each loaded hardware component.

Returns:

Vector of strings, containing all registered keys.

std::vector<std::string> available_state_interfaces() const

Returns all available state interfaces keys.

The keys are collected from the available list.

Returns:

Vector of strings, containing all available state interface names.

bool state_interface_is_available(const std::string &name) const

Checks whether a state interface is available under the given key.

Returns:

true if interface is available, false otherwise.

void import_controller_reference_interfaces(const std::string &controller_name, std::vector<CommandInterface> &interfaces)

Add controllers’ reference interfaces to resource manager.

Interface for transferring management of reference interfaces to resource manager. When chaining controllers, reference interfaces are used as command interface of preceding controllers. Therefore, they should be managed in the same way as command interface of hardware.

Parameters:
  • controller_name[in] name of the controller which reference interfaces are imported.

  • interfaces[in] list of controller’s reference interfaces as CommandInterfaces.

std::vector<std::string> get_controller_reference_interface_names(const std::string &controller_name)

Get list of reference interface of a controller.

Returns lists of stored reference interfaces names for a controller.

Parameters:

controller_name[in] for which list of reference interface names is returned.

Returns:

list of reference interface names.

void make_controller_reference_interfaces_available(const std::string &controller_name)

Add controller’s reference interface to available list.

Adds interfaces of a controller with given name to the available list. This method should be called when a controller gets activated with chained mode turned on. That means, the controller’s reference interfaces can be used by another controller in chained architectures.

Parameters:

controller_name[in] name of the controller which interfaces should become available.

void make_controller_reference_interfaces_unavailable(const std::string &controller_name)

Remove controller’s reference interface to available list.

Removes interfaces of a controller with given name from the available list. This method should be called when a controller gets deactivated and its reference interfaces cannot be used by another controller anymore.

Parameters:

controller_name[in] name of the controller which interfaces should become unavailable.

void remove_controller_reference_interfaces(const std::string &controller_name)

Remove controllers reference interfaces from resource manager.

Remove reference interfaces from resource manager, i.e., resource storage. The interfaces will be deleted from all internal maps and lists.

Parameters:

controller_name[in] list of interface names that will be deleted from resource manager.

void cache_controller_to_hardware(const std::string &controller_name, const std::vector<std::string> &interfaces)

Cache mapping between hardware and controllers using it.

Find mapping between controller and hardware based on interfaces controller with controller_name is using and cache those for later usage.

Parameters:
  • controller_name[in] name of the controller which interfaces are provided.

  • interfaces[in] list of interfaces controller with controller_name is using.

std::vector<std::string> get_cached_controllers_to_hardware(const std::string &hardware_name)

Return cached controllers for a specific hardware.

Return list of cached controller names that use the hardware with name hardware_name.

Parameters:

hardware_name[in] the name of the hardware for which cached controllers should be returned.

Returns:

list of cached controller names that depend on hardware with name hardware_name.

bool command_interface_is_claimed(const std::string &key) const

Checks whether a command interface is already claimed.

Any command interface can only be claimed by a single instance.

Note

the equivalent function does not exist for state interfaces. These are solely read-only and can thus be used by multiple instances.

Parameters:

key[in] string identifying the interface to check.

Returns:

true if interface is already claimed, false if available.

LoanedCommandInterface claim_command_interface(const std::string &key)

Claim a command interface given its key.

The resource is claimed as long as being in scope. Once the resource is going out of scope, the destructor returns and thus frees the resource to claimed by others.

Parameters:

key[in] String identifier which command interface to claim

Returns:

command interface

std::vector<std::string> command_interface_keys() const

Returns all registered command interfaces keys.

The keys are collected from each loaded hardware component.

Returns:

vector of strings, containing all registered keys.

std::vector<std::string> available_command_interfaces() const

Returns all available command interfaces keys.

The keys are collected from the available list.

Returns:

vector of strings, containing all available command interface names.

bool command_interface_is_available(const std::string &interface) const

Checks whether a command interface is available under the given name.

Parameters:

name[in] string identifying the interface to check.

Returns:

true if interface is available, false otherwise.

size_t actuator_components_size() const

Return the number size_t of loaded actuator components.

Returns:

number of actuator components.

size_t sensor_components_size() const

Return the number of loaded sensor components.

Returns:

number of sensor components.

size_t system_components_size() const

Return the number of loaded system components.

Returns:

size_t number of system components.

void import_component(std::unique_ptr<ActuatorInterface> actuator, const HardwareInfo &hardware_info)

Import a hardware component which is not listed in the URDF.

Components which are initialized outside a URDF can be added post initialization. Nevertheless, there should still be HardwareInfo available for this component, either parsed from a URDF string (easiest) or filled manually.

Note

this might invalidate existing state and command interfaces and should thus not be called when a controller is running.

Note

given that no hardware_info is available, the component has to be configured externally and prior to the call to import.

Parameters:
  • actuator[in] pointer to the actuator interface.

  • hardware_info[in] hardware info

void import_component(std::unique_ptr<SensorInterface> sensor, const HardwareInfo &hardware_info)

Import a hardware component which is not listed in the URDF.

Components which are initialized outside a URDF can be added post initialization. Nevertheless, there should still be HardwareInfo available for this component, either parsed from a URDF string (easiest) or filled manually.

Note

this might invalidate existing state and command interfaces and should thus not be called when a controller is running.

Note

given that no hardware_info is available, the component has to be configured externally and prior to the call to import.

Parameters:
  • sensor[in] pointer to the sensor interface.

  • hardware_info[in] hardware info

void import_component(std::unique_ptr<SystemInterface> system, const HardwareInfo &hardware_info)

Import a hardware component which is not listed in the URDF.

Components which are initialized outside a URDF can be added post initialization. Nevertheless, there should still be HardwareInfo available for this component, either parsed from a URDF string (easiest) or filled manually.

Note

this might invalidate existing state and command interfaces and should thus not be called when a controller is running.

Note

given that no hardware_info is available, the component has to be configured externally and prior to the call to import.

Parameters:
  • system[in] pointer to the system interface.

  • hardware_info[in] hardware info

std::unordered_map<std::string, HardwareComponentInfo> get_components_status()

Return status for all components.

Returns:

map of hardware names and their status.

bool prepare_command_mode_switch(const std::vector<std::string> &start_interfaces, const std::vector<std::string> &stop_interfaces)

Prepare the hardware components for a new command interface mode.

Hardware components are asked to prepare a new command interface claim.

Note

this is intended for mode-switching when a hardware interface needs to change control mode depending on which command interface is claimed.

Note

this is for non-realtime preparing for and accepting new command resource combinations.

Note

accept_command_resource_claim is called on all actuators and system components and hardware interfaces should return hardware_interface::return_type::OK by default

Parameters:
  • start_interfaces[in] vector of string identifiers for the command interfaces starting.

  • stop_interfaces[in] vector of string identifiers for the command interfaces stopping.

Returns:

true if switch can be prepared; false if a component rejects switch request, and if at least one of the input interfaces are not existing or not available (i.e., component is not in ACTIVE or INACTIVE state).

bool perform_command_mode_switch(const std::vector<std::string> &start_interfaces, const std::vector<std::string> &stop_interfaces)

Notify the hardware components that realtime hardware mode switching should occur.

Hardware components are asked to perform the command interface mode switching.

Note

this is intended for mode-switching when a hardware interface needs to change control mode depending on which command interface is claimed.

Note

this is for realtime switching of the command interface.

Note

it is assumed that prepare_command_mode_switch is called just before this method with the same input arguments.

Parameters:
  • start_interfaces[in] vector of string identifiers for the command interfaces starting.

  • stop_interfaces[in] vector of string identifiers for the command interfacs stopping.

Returns:

true if switch is performed, false if a component rejects switching.

return_type set_component_state(const std::string &component_name, rclcpp_lifecycle::State &target_state)

Sets state of hardware component.

Set set of hardware component if possible. Takes care of all transitions needed to reach the target state. It implements the state machine from: https://design.ros2.org/articles/node_lifecycle.html

The method is not part of the real-time critical update loop.

Parameters:
  • component_name[in] component name to change state.

  • target_state[in] target state to set for a hardware component.

Returns:

hardware_interface::retun_type::OK if component successfully switched its state and hardware_interface::return_type::ERROR any of state transitions has failed.

HardwareReadWriteStatus read(const rclcpp::Time &time, const rclcpp::Duration &period)

Reads all loaded hardware components.

Reads from all active hardware components.

Part of the real-time critical update loop. It is realtime-safe if used hardware interfaces are implemented adequately.

HardwareReadWriteStatus write(const rclcpp::Time &time, const rclcpp::Duration &period)

Write all loaded hardware components.

Writes to all active hardware components.

Part of the real-time critical update loop. It is realtime-safe if used hardware interfaces are implemented adequately.

bool command_interface_exists(const std::string &key) const

Checks whether a command interface is registered under the given key.

Parameters:

key[in] string identifying the interface to check.

Returns:

true if interface exist, false otherwise.

bool state_interface_exists(const std::string &key) const

Checks whether a state interface is registered under the given key.

Returns:

true if interface exist, false otherwise.