ros2_control - rolling
Public Member Functions | List of all members
gz_ros2_control::GZResourceManager Class Reference
Inheritance diagram for gz_ros2_control::GZResourceManager:
Inheritance graph
[legend]
Collaboration diagram for gz_ros2_control::GZResourceManager:
Collaboration graph
[legend]

Public Member Functions

 GZResourceManager (rclcpp::Node::SharedPtr &node, sim::EntityComponentManager &ecm, std::map< std::string, sim::Entity > enabledJoints)
 
 GZResourceManager (const GZResourceManager &)=delete
 
bool load_and_initialize_components (const std::string &urdf, unsigned int update_rate) override
 Load resources from on a given URDF. More...
 
- Public Member Functions inherited from hardware_interface::ResourceManager
 ResourceManager (rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface)
 Default constructor for the Resource Manager.
 
 ResourceManager (const std::string &urdf, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface, bool activate_all=false, const unsigned int update_rate=100)
 Constructor for the Resource Manager. More...
 
 ResourceManager (const ResourceManager &)=delete
 
bool are_components_initialized () const
 if the resource manager load_and_initialize_components(...) function has been called this returns true. We want to permit to loading the urdf later on, but we currently don't want to permit multiple calls to load_and_initialize_components (reloading/loading different urdf). More...
 
LoanedStateInterface claim_state_interface (const std::string &key)
 Claim a state interface given its key. More...
 
std::vector< std::string > state_interface_keys () const
 Returns all registered state interfaces keys. More...
 
std::vector< std::string > available_state_interfaces () const
 Returns all available state interfaces keys. More...
 
bool state_interface_is_available (const std::string &name) const
 Checks whether a state interface is available under the given key. More...
 
void import_controller_exported_state_interfaces (const std::string &controller_name, std::vector< StateInterface::ConstSharedPtr > &interfaces)
 Add controllers' exported state interfaces to resource manager. More...
 
std::vector< std::string > get_controller_exported_state_interface_names (const std::string &controller_name)
 Get list of exported tate interface of a controller. More...
 
void make_controller_exported_state_interfaces_available (const std::string &controller_name)
 Add controller's exported state interfaces to available list. More...
 
void make_controller_exported_state_interfaces_unavailable (const std::string &controller_name)
 Remove controller's exported state interface to available list. More...
 
void remove_controller_exported_state_interfaces (const std::string &controller_name)
 Remove controllers exported state interfaces from resource manager. More...
 
void import_controller_reference_interfaces (const std::string &controller_name, const std::vector< hardware_interface::CommandInterface::SharedPtr > &interfaces)
 Add controllers' reference interfaces to resource manager. More...
 
std::vector< std::string > get_controller_reference_interface_names (const std::string &controller_name)
 Get list of reference interface of a controller. More...
 
void make_controller_reference_interfaces_available (const std::string &controller_name)
 Add controller's reference interface to available list. More...
 
void make_controller_reference_interfaces_unavailable (const std::string &controller_name)
 Remove controller's reference interface to available list. More...
 
void remove_controller_reference_interfaces (const std::string &controller_name)
 Remove controllers reference interfaces from resource manager. More...
 
void cache_controller_to_hardware (const std::string &controller_name, const std::vector< std::string > &interfaces)
 Cache mapping between hardware and controllers using it. More...
 
std::vector< std::string > get_cached_controllers_to_hardware (const std::string &hardware_name)
 Return cached controllers for a specific hardware. More...
 
bool command_interface_is_claimed (const std::string &key) const
 Checks whether a command interface is already claimed. More...
 
LoanedCommandInterface claim_command_interface (const std::string &key)
 Claim a command interface given its key. More...
 
std::vector< std::string > command_interface_keys () const
 Returns all registered command interfaces keys. More...
 
std::vector< std::string > available_command_interfaces () const
 Returns all available command interfaces keys. More...
 
bool command_interface_is_available (const std::string &interface) const
 Checks whether a command interface is available under the given name. More...
 
size_t actuator_components_size () const
 Return the number size_t of loaded actuator components. More...
 
size_t sensor_components_size () const
 Return the number of loaded sensor components. More...
 
size_t system_components_size () const
 Return the number of loaded system components. More...
 
void import_component (std::unique_ptr< ActuatorInterface > actuator, const HardwareInfo &hardware_info)
 Import a hardware component which is not listed in the URDF. More...
 
void import_component (std::unique_ptr< SensorInterface > sensor, const HardwareInfo &hardware_info)
 Import a hardware component which is not listed in the URDF. More...
 
void import_component (std::unique_ptr< SystemInterface > system, const HardwareInfo &hardware_info)
 Import a hardware component which is not listed in the URDF. More...
 
std::unordered_map< std::string, HardwareComponentInfoget_components_status ()
 Return status for all components. More...
 
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. More...
 
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. More...
 
return_type set_component_state (const std::string &component_name, rclcpp_lifecycle::State &target_state)
 Sets state of hardware component. More...
 
void shutdown_async_components ()
 Deletes all async components from the resource storage. More...
 
HardwareReadWriteStatus read (const rclcpp::Time &time, const rclcpp::Duration &period)
 Reads all loaded hardware components. More...
 
HardwareReadWriteStatus write (const rclcpp::Time &time, const rclcpp::Duration &period)
 Write all loaded hardware components. More...
 
bool command_interface_exists (const std::string &key) const
 Checks whether a command interface is registered under the given key. More...
 
bool state_interface_exists (const std::string &key) const
 Checks whether a state interface is registered under the given key. More...
 

Additional Inherited Members

- Protected Member Functions inherited from hardware_interface::ResourceManager
rclcpp::Logger get_logger () const
 Gets the logger for the resource manager. More...
 
rclcpp::Clock::SharedPtr get_clock () const
 Gets the clock for the resource manager. More...
 
- Protected Attributes inherited from hardware_interface::ResourceManager
bool components_are_loaded_and_initialized_ = false
 
std::recursive_mutex resource_interfaces_lock_
 
std::recursive_mutex claimed_command_interfaces_lock_
 
std::recursive_mutex resources_lock_
 

Member Function Documentation

◆ load_and_initialize_components()

bool gz_ros2_control::GZResourceManager::load_and_initialize_components ( const std::string &  urdf,
unsigned int  update_rate 
)
inlineoverridevirtual

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
[in]urdfstring containing the URDF.
[in]update_rateupdate rate of the main control loop, i.e., of the controller manager.
Returns
false if URDF validation has failed.

Reimplemented from hardware_interface::ResourceManager.


The documentation for this class was generated from the following file: