Struct ResourceManagerParams
Defined in File resource_manager_params.hpp
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.
-
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.
-
ResourceManagerParams() = default