Skip to content

Commit 2c8d2aa

Browse files
authored
fix(rclcpp_components): increase the service queue sizes in component_container (backport #2363) (#2380)
* fix(rclcpp_components): increase the service queue sizes in component_container (#2363) * Use rmw_qos_profile_t. Humble doesn't support create_service with the rclcpp::QoS object. Signed-off-by: M. Fatih Cırıt <[email protected]> (cherry picked from commit 9c098e5) Signed-off-by: Chris Lalancette <[email protected]>
1 parent 47712ec commit 2c8d2aa

File tree

1 file changed

+6
-2
lines changed

1 file changed

+6
-2
lines changed

rclcpp_components/src/component_manager.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,12 +37,16 @@ ComponentManager::ComponentManager(
3737
: Node(std::move(node_name), node_options),
3838
executor_(executor)
3939
{
40+
rmw_qos_profile_t service_qos = rmw_qos_profile_services_default;
41+
service_qos.depth = 200;
4042
loadNode_srv_ = create_service<LoadNode>(
4143
"~/_container/load_node",
42-
std::bind(&ComponentManager::on_load_node, this, _1, _2, _3));
44+
std::bind(&ComponentManager::on_load_node, this, _1, _2, _3),
45+
service_qos);
4346
unloadNode_srv_ = create_service<UnloadNode>(
4447
"~/_container/unload_node",
45-
std::bind(&ComponentManager::on_unload_node, this, _1, _2, _3));
48+
std::bind(&ComponentManager::on_unload_node, this, _1, _2, _3),
49+
service_qos);
4650
listNodes_srv_ = create_service<ListNodes>(
4751
"~/_container/list_nodes",
4852
std::bind(&ComponentManager::on_list_nodes, this, _1, _2, _3));

0 commit comments

Comments
 (0)