rclcpp_components  master
Package containing tools for dynamically loadable components
Public Types | Public Member Functions | Protected Member Functions | List of all members
rclcpp_components::ComponentManager Class Reference

ComponentManager handles the services to load, unload, and get the list of loaded components. More...

#include <component_manager.hpp>

Inheritance diagram for rclcpp_components::ComponentManager:
Inheritance graph
[legend]
Collaboration diagram for rclcpp_components::ComponentManager:
Collaboration graph
[legend]

Public Types

using LoadNode = composition_interfaces::srv::LoadNode
 
using UnloadNode = composition_interfaces::srv::UnloadNode
 
using ListNodes = composition_interfaces::srv::ListNodes
 
using ComponentResource = std::pair< std::string, std::string >
 Represents a component resource. More...
 
- Public Types inherited from rclcpp::Node
typedef rclcpp::node_interfaces::OnSetParametersCallbackHandle OnSetParametersCallbackHandle
 
typedef rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType OnParametersSetCallbackType
 

Public Member Functions

 ComponentManager (std::weak_ptr< rclcpp::Executor > executor, std::string node_name="ComponentManager", const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions() .start_parameter_services(false) .start_parameter_event_publisher(false))
 Default constructor. More...
 
virtual ~ComponentManager ()
 
virtual std::vector< ComponentResourceget_component_resources (const std::string &package_name, const std::string &resource_index="rclcpp_components") const
 Return a list of valid loadable components in a given package. More...
 
virtual std::shared_ptr< rclcpp_components::NodeFactorycreate_component_factory (const ComponentResource &resource)
 Instantiate a component from a dynamic library. More...
 
- Public Member Functions inherited from rclcpp::Node
 Node (const std::string &node_name, const NodeOptions &options=NodeOptions())
 
 Node (const std::string &node_name, const std::string &namespace_, const NodeOptions &options=NodeOptions())
 
virtual ~Node ()
 
const char * get_name () const
 
const char * get_namespace () const
 
const char * get_fully_qualified_name () const
 
rclcpp::Logger get_logger () const
 
rclcpp::CallbackGroup::SharedPtr create_callback_group (rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node=true)
 
const std::vector< rclcpp::CallbackGroup::WeakPtr > & get_callback_groups () const
 
std::shared_ptr< PublisherT > create_publisher (const std::string &topic_name, const rclcpp::QoS &qos, const PublisherOptionsWithAllocator< AllocatorT > &options=PublisherOptionsWithAllocator< AllocatorT >())
 
std::shared_ptr< SubscriptionT > create_subscription (const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator< AllocatorT > &options=SubscriptionOptionsWithAllocator< AllocatorT >(), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat=(MessageMemoryStrategyT::create_default()))
 
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer (std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
 
rclcpp::Client< ServiceT >::SharedPtr create_client (const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
 
rclcpp::Service< ServiceT >::SharedPtr create_service (const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
 
std::shared_ptr< rclcpp::GenericPublishercreate_generic_publisher (const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=(rclcpp::PublisherOptionsWithAllocator< AllocatorT >()))
 
std::shared_ptr< rclcpp::GenericSubscriptioncreate_generic_subscription (const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function< void(std::shared_ptr< rclcpp::SerializedMessage >)> callback, const rclcpp::SubscriptionOptionsWithAllocator< AllocatorT > &options=(rclcpp::SubscriptionOptionsWithAllocator< AllocatorT >()))
 
const rclcpp::ParameterValuedeclare_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
 
const rclcpp::ParameterValuedeclare_parameter (const std::string &name, rclcpp::ParameterType type, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor{}, bool ignore_override=false)
 
const rclcpp::ParameterValuedeclare_parameter (const std::string &name)
 
auto declare_parameter (const std::string &name, const ParameterT &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
 
auto declare_parameter (const std::string &name, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
 
std::vector< ParameterT > declare_parameters (const std::string &namespace_, const std::map< std::string, ParameterT > &parameters, bool ignore_overrides=false)
 
std::vector< ParameterT > declare_parameters (const std::string &namespace_, const std::map< std::string, std::pair< ParameterT, rcl_interfaces::msg::ParameterDescriptor > > &parameters, bool ignore_overrides=false)
 
void undeclare_parameter (const std::string &name)
 
bool has_parameter (const std::string &name) const
 
rcl_interfaces::msg::SetParametersResult set_parameter (const rclcpp::Parameter &parameter)
 
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters (const std::vector< rclcpp::Parameter > &parameters)
 
rcl_interfaces::msg::SetParametersResult set_parameters_atomically (const std::vector< rclcpp::Parameter > &parameters)
 
rclcpp::Parameter get_parameter (const std::string &name) const
 
bool get_parameter (const std::string &name, rclcpp::Parameter &parameter) const
 
bool get_parameter (const std::string &name, ParameterT &parameter) const
 
bool get_parameter_or (const std::string &name, ParameterT &parameter, const ParameterT &alternative_value) const
 
std::vector< rclcpp::Parameterget_parameters (const std::vector< std::string > &names) const
 
bool get_parameters (const std::string &prefix, std::map< std::string, ParameterT > &values) const
 
rcl_interfaces::msg::ParameterDescriptor describe_parameter (const std::string &name) const
 
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters (const std::vector< std::string > &names) const
 
std::vector< uint8_t > get_parameter_types (const std::vector< std::string > &names) const
 
rcl_interfaces::msg::ListParametersResult list_parameters (const std::vector< std::string > &prefixes, uint64_t depth) const
 
RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback (OnParametersSetCallbackType callback)
 
void remove_on_set_parameters_callback (const OnSetParametersCallbackHandle *const handler)
 
std::vector< std::stringget_node_names () const
 
std::map< std::string, std::vector< std::string > > get_topic_names_and_types () const
 
std::map< std::string, std::vector< std::string > > get_service_names_and_types () const
 
std::map< std::string, std::vector< std::string > > get_service_names_and_types_by_node (const std::string &node_name, const std::string &namespace_) const
 
size_t count_publishers (const std::string &topic_name) const
 
size_t count_subscribers (const std::string &topic_name) const
 
std::vector< rclcpp::TopicEndpointInfoget_publishers_info_by_topic (const std::string &topic_name, bool no_mangle=false) const
 
std::vector< rclcpp::TopicEndpointInfoget_subscriptions_info_by_topic (const std::string &topic_name, bool no_mangle=false) const
 
rclcpp::Event::SharedPtr get_graph_event ()
 
void wait_for_graph_change (rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout)
 
rclcpp::Clock::SharedPtr get_clock ()
 
rclcpp::Clock::ConstSharedPtr get_clock () const
 
Time now () const
 
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface ()
 
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface ()
 
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface ()
 
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface ()
 
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface ()
 
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface ()
 
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface ()
 
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface ()
 
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface ()
 
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface ()
 
const std::stringget_sub_namespace () const
 
const std::stringget_effective_namespace () const
 
rclcpp::Node::SharedPtr create_sub_node (const std::string &sub_namespace)
 
const rclcpp::NodeOptionsget_node_options () const
 
Client< ServiceT >::SharedPtr create_client (const std::string &service_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group)
 

Protected Member Functions

virtual void OnLoadNode (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< LoadNode::Request > request, std::shared_ptr< LoadNode::Response > response)
 Service callback to load a new node in the component. More...
 
virtual void OnUnloadNode (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< UnloadNode::Request > request, std::shared_ptr< UnloadNode::Response > response)
 Service callback to unload a node in the component. More...
 
virtual void OnListNodes (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< ListNodes::Request > request, std::shared_ptr< ListNodes::Response > response)
 Service callback to get the list of nodes in the component. More...
 
- Protected Member Functions inherited from rclcpp::Node
 Node (const Node &other, const std::string &sub_namespace)
 

Detailed Description

ComponentManager handles the services to load, unload, and get the list of loaded components.

Member Typedef Documentation

◆ LoadNode

using rclcpp_components::ComponentManager::LoadNode = composition_interfaces::srv::LoadNode

◆ UnloadNode

using rclcpp_components::ComponentManager::UnloadNode = composition_interfaces::srv::UnloadNode

◆ ListNodes

using rclcpp_components::ComponentManager::ListNodes = composition_interfaces::srv::ListNodes

◆ ComponentResource

Represents a component resource.

Is a pair of class name (for class loader) and library path (absolute)

Constructor & Destructor Documentation

◆ ComponentManager()

rclcpp_components::ComponentManager::ComponentManager ( std::weak_ptr< rclcpp::Executor executor,
std::string  node_name = "ComponentManager",
const rclcpp::NodeOptions node_options = rclcpp::NodeOptions() .start_parameter_services(false) .start_parameter_event_publisher(false) 
)

Default constructor.

Initializes the component manager. It creates the services: load node, unload node and list nodes.

Parameters
executorthe executor which will spin the node.
node_namethe name of the node that the data originates from.
node_optionsadditional options to control creation of the node.

◆ ~ComponentManager()

virtual rclcpp_components::ComponentManager::~ComponentManager ( )
virtual

Member Function Documentation

◆ get_component_resources()

virtual std::vector<ComponentResource> rclcpp_components::ComponentManager::get_component_resources ( const std::string package_name,
const std::string resource_index = "rclcpp_components" 
) const
virtual

Return a list of valid loadable components in a given package.

◆ create_component_factory()

virtual std::shared_ptr<rclcpp_components::NodeFactory> rclcpp_components::ComponentManager::create_component_factory ( const ComponentResource resource)
virtual

Instantiate a component from a dynamic library.

◆ OnLoadNode()

virtual void rclcpp_components::ComponentManager::OnLoadNode ( const std::shared_ptr< rmw_request_id_t request_header,
const std::shared_ptr< LoadNode::Request >  request,
std::shared_ptr< LoadNode::Response >  response 
)
protectedvirtual

Service callback to load a new node in the component.

◆ OnUnloadNode()

virtual void rclcpp_components::ComponentManager::OnUnloadNode ( const std::shared_ptr< rmw_request_id_t request_header,
const std::shared_ptr< UnloadNode::Request >  request,
std::shared_ptr< UnloadNode::Response >  response 
)
protectedvirtual

Service callback to unload a node in the component.

◆ OnListNodes()

virtual void rclcpp_components::ComponentManager::OnListNodes ( const std::shared_ptr< rmw_request_id_t request_header,
const std::shared_ptr< ListNodes::Request >  request,
std::shared_ptr< ListNodes::Response >  response 
)
protectedvirtual

Service callback to get the list of nodes in the component.


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