ros2_control - rolling
Public Member Functions | Public Attributes | List of all members
hardware_interface::ResourceStorage Class Reference

Public Member Functions

 ResourceStorage (rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface)
 
template<class HardwareT , class HardwareInterfaceT >
bool load_hardware (const HardwareInfo &hardware_info, pluginlib::ClassLoader< HardwareInterfaceT > &loader, std::vector< HardwareT > &container)
 
template<class HardwareT >
bool initialize_hardware (const HardwareInfo &hardware_info, HardwareT &hardware)
 
template<class HardwareT >
bool configure_hardware (HardwareT &hardware)
 
void remove_all_hardware_interfaces_from_available_list (const std::string &hardware_name)
 
template<class HardwareT >
bool cleanup_hardware (HardwareT &hardware)
 
template<class HardwareT >
bool shutdown_hardware (HardwareT &hardware)
 
template<class HardwareT >
bool activate_hardware (HardwareT &hardware)
 
template<class HardwareT >
bool deactivate_hardware (HardwareT &hardware)
 
template<class HardwareT >
bool set_component_state (HardwareT &hardware, const rclcpp_lifecycle::State &target_state)
 
template<class HardwareT >
void import_state_interfaces (HardwareT &hardware)
 
void insert_command_interface (const CommandInterface::SharedPtr command_interface)
 
void insert_command_interface (CommandInterface &&command_interface)
 
template<class HardwareT >
void import_command_interfaces (HardwareT &hardware)
 
std::string add_state_interface (StateInterface::ConstSharedPtr interface)
 
std::vector< std::string > add_state_interfaces (std::vector< StateInterface::ConstSharedPtr > &interfaces)
 Adds exported state interfaces into internal storage. More...
 
void remove_state_interfaces (const std::vector< std::string > &interface_names)
 Removes state interfaces from internal storage. More...
 
std::vector< std::string > add_command_interfaces (std::vector< CommandInterface > &interfaces)
 Adds exported command interfaces into internal storage. More...
 
std::vector< std::string > add_command_interfaces (const std::vector< CommandInterface::SharedPtr > &interfaces)
 
void remove_command_interfaces (const std::vector< std::string > &interface_names)
 Removes command interfaces from internal storage. More...
 
bool load_and_initialize_actuator (const HardwareInfo &hardware_info)
 
bool load_and_initialize_sensor (const HardwareInfo &hardware_info)
 
bool load_and_initialize_system (const HardwareInfo &hardware_info)
 
void initialize_actuator (std::unique_ptr< ActuatorInterface > actuator, const HardwareInfo &hardware_info)
 
void initialize_sensor (std::unique_ptr< SensorInterface > sensor, const HardwareInfo &hardware_info)
 
void initialize_system (std::unique_ptr< SystemInterface > system, const HardwareInfo &hardware_info)
 
void clear ()
 
return_type update_hardware_component_group_state (const std::string &group_name, const return_type &value)
 
const rclcpp::Logger & get_logger () const
 Gets the logger for the resource storage. More...
 
rclcpp::Clock::SharedPtr get_clock () const
 Gets the clock for the resource storage. More...
 

Public Attributes

pluginlib::ClassLoader< ActuatorInterfaceactuator_loader_
 
pluginlib::ClassLoader< SensorInterfacesensor_loader_
 
pluginlib::ClassLoader< SystemInterfacesystem_loader_
 
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_
 
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface_
 
rclcpp::Logger rm_logger_
 
std::vector< Actuatoractuators_
 
std::vector< Sensorsensors_
 
std::vector< Systemsystems_
 
std::unordered_map< std::string, HardwareComponentInfohardware_info_map_
 
std::unordered_map< std::string, hardware_interface::return_type > hw_group_state_
 
std::unordered_map< std::string, std::vector< std::string > > hardware_used_by_controllers_
 Mapping between hardware and controllers that are using it (accessing data from it)
 
std::unordered_map< std::string, std::vector< std::string > > controllers_exported_state_interfaces_map_
 Mapping between controllers and list of interfaces they are using.
 
std::unordered_map< std::string, std::vector< std::string > > controllers_reference_interfaces_map_
 
std::map< std::string, StateInterface::ConstSharedPtr > state_interface_map_
 Storage of all available state interfaces.
 
std::map< std::string, CommandInterface::SharedPtr > command_interface_map_
 Storage of all available command interfaces.
 
std::vector< std::string > available_state_interfaces_
 Vectors with interfaces available to controllers (depending on hardware component state)
 
std::vector< std::string > available_command_interfaces_
 
std::unordered_map< std::string, bool > claimed_command_interface_map_
 List of all claimed command interfaces.
 
unsigned int cm_update_rate_ = 100
 

Member Function Documentation

◆ add_command_interfaces()

std::vector<std::string> hardware_interface::ResourceStorage::add_command_interfaces ( std::vector< CommandInterface > &  interfaces)
inline

Adds exported command interfaces into internal storage.

Add command interfaces to the internal storage. Command interfaces exported from hardware or chainable controllers are moved to the map with name-interface pairs, the interface names are added to the claimed map and available list's size is increased to reserve storage when interface change theirs status in real-time control loop.

Parameters
[interfaces]list of command interface to add into storage.
Returns
list of interface names that are added into internal storage. The output is used to avoid additional iterations to cache interface names, e.g., for initializing info structures.

◆ add_state_interfaces()

std::vector<std::string> hardware_interface::ResourceStorage::add_state_interfaces ( std::vector< StateInterface::ConstSharedPtr > &  interfaces)
inline

Adds exported state interfaces into internal storage.

Adds state interfaces to the internal storage. State interfaces exported from hardware or chainable controllers are moved to the map with name-interface pairs and available list's size is increased to reserve storage when interface change theirs status in real-time control loop.

Parameters
[interfaces]list of state interface to add into storage.
Returns
list of interface names that are added into internal storage. The output is used to avoid additional iterations to cache interface names, e.g., for initializing info structures.

◆ get_clock()

rclcpp::Clock::SharedPtr hardware_interface::ResourceStorage::get_clock ( ) const
inline

Gets the clock for the resource storage.

Returns
clock of the resource storage

◆ get_logger()

const rclcpp::Logger& hardware_interface::ResourceStorage::get_logger ( ) const
inline

Gets the logger for the resource storage.

Returns
logger of the resource storage

◆ remove_command_interfaces()

void hardware_interface::ResourceStorage::remove_command_interfaces ( const std::vector< std::string > &  interface_names)
inline

Removes command interfaces from internal storage.

Command interface are removed from the maps with theirs storage and their claimed status.

Parameters
[interface_names]list of command interface names to remove from storage.

◆ remove_state_interfaces()

void hardware_interface::ResourceStorage::remove_state_interfaces ( const std::vector< std::string > &  interface_names)
inline

Removes state interfaces from internal storage.

State interface are removed from the maps with theirs storage and their claimed status.

Parameters
[interface_names]list of state interface names to remove from storage.

◆ update_hardware_component_group_state()

return_type hardware_interface::ResourceStorage::update_hardware_component_group_state ( const std::string &  group_name,
const return_type &  value 
)
inline

Returns the return type of the hardware component group state, if the return type is other than OK, then updates the return type of the group to the respective one


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