1 #include <rclcpp_components/component_manager.hpp> 3 int main(
int argc,
char* argv[]) {
4 rclcpp::init(argc, argv);
9 auto dummyNode = std::make_shared<rclcpp::Node>(
"dummy");
10 auto numThreadsDescription = rcl_interfaces::msg::ParameterDescriptor{};
11 numThreadsDescription.name =
"num_threads";
12 numThreadsDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
13 numThreadsDescription.description =
14 "The number of threads to use for the ROS node executor. 0 means one thread per CPU core.";
15 numThreadsDescription.read_only =
true;
16 numThreadsDescription.additional_constraints =
"Must be a non-negative integer";
17 numThreadsDescription.integer_range.resize(1);
18 numThreadsDescription.integer_range[0].from_value = 0;
19 numThreadsDescription.integer_range[0].to_value = INT32_MAX;
20 numThreadsDescription.integer_range[0].step = 1;
21 constexpr
int DEFAULT_NUM_THREADS = 0;
22 dummyNode->declare_parameter(numThreadsDescription.name, DEFAULT_NUM_THREADS,
23 numThreadsDescription);
24 numThreads =
static_cast<size_t>(dummyNode->get_parameter(numThreadsDescription.name).as_int());
28 rclcpp::executors::MultiThreadedExecutor::make_shared(rclcpp::ExecutorOptions{}, numThreads);
30 rclcpp_components::ComponentManager componentManager(executor,
31 "foxglove_bridge_component_manager");
32 const auto componentResources = componentManager.get_component_resources(
"foxglove_bridge");
34 if (componentResources.empty()) {
35 RCLCPP_INFO(componentManager.get_logger(),
"No loadable resources found");
39 auto componentFactory = componentManager.create_component_factory(componentResources.front());
40 auto node = componentFactory->create_node_instance(rclcpp::NodeOptions());
42 executor->add_node(node.get_node_base_interface());
int main(int argc, char *argv[])