Struct ResourceManagerParams

Struct Documentation

struct ResourceManagerParams

Parameters required for the construction and initial setup of a ResourceManager. This struct is typically populated by the ControllerManager.

Public Functions

ResourceManagerParams() = default

Public Members

std::string robot_description = ""

The URDF string describing the robot’s hardware components. Can be empty if ResourceManager is constructed without an initial URDF and components are loaded later or via other means.

rclcpp::Clock::SharedPtr clock = nullptr

Shared pointer to the Clock used by the ResourceManager. This is typically obtained from the node via get_clock().

rclcpp::Logger logger = rclcpp::get_logger("resource_manager")

Logger instance used by the ResourceManager. This is typically obtained from the node via get_logger().

rclcpp::Executor::SharedPtr executor = nullptr

Shared pointer to the rclcpp::Executor instance that the ResourceManager and its components (including plugins that opt-in) will use. This is typically the ControllerManager’s main executor.

bool activate_all = false

Flag indicating if all hardware components found in the URDF should be automatically activated after successful loading and initialization.

bool allow_controller_activation_with_inactive_hardware = false

If true, controllers are allowed to claim resources from inactive hardware components. If false, controllers can only claim resources from active hardware components. Moreover, when the hardware component returns DEACTIVATE on read/write cycle: If set to true, the controllers using those interfaces will continue to run. If set to false, the controllers using those interfaces will be deactivated.

Note

This parameter might be deprecated or removed in the future releases. Please use with caution.

Warning

Allowing control with inactive hardware is not recommended for safety reasons. Use with caution only if you really know what you are doing.

bool return_failed_hardware_names_on_return_deactivate_write_cycle_ = true

If true, when a hardware component returns DEACTIVATE on the write cycle, its name will be included in the returned HardwareReadWriteStatus.failed_hardware_names list. If false, the names of such hardware components will not be included in that list. This can be useful when controllers are allowed to operate with inactive hardware components.

Note

This parameter might be deprecated or removed in future releases. Please use with caution.

unsigned int update_rate = 100

The update rate (in Hz) of the ControllerManager. This can be used by ResourceManager to configure asynchronous hardware components or for other timing considerations.