-
Notifications
You must be signed in to change notification settings - Fork 522
Description
Feature request
Feature description
For SystemDefaultsQoS to work out of the box for IPC, it needs to always strictly have a depth setting > 0. When used in a subscription out of the box, this works fine. For example:
footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
"footprint",
nav2_util::DefaultQoS(),
std::bind(&Costmap2DROS::setRobotFootprintPolygon, this, std::placeholders::_1));
However, when used in a publisher, it fails. For example:
footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
"published_footprint", rclcpp::SystemDefaultsQoS());
or
state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionDetectorState>(
"collision_detector_state", rclcpp::SystemDefaultsQoS());
with the error
[component_container_isolated-7] [ERROR] [1734048098.404790594] [local_costmap.local_costmap]: Original error: intraprocess communication is not allowed with a zero qos history depth value
Thus, I feel that we should update the default for SystemDefaultsQoS for publishers (or in general) to be 1 if not already > 1 so that folks migrating or implementing IPC don't run into a cacophony of issues, one for each publisher. I understand this comes from the RMW/DDS, but it seems to me this needs to be updated since SystemDefaultsQoS is a key "default" QoS profile. Having that simply not work for a core ROS 2 feature seems intrinsically problematic :-) It was a bit subtle for me to identify this, so fixing this for everyone else in the future would be ideal.
For now, I'm creating a new nav2_util::DefaultPublisherQoS() to resolve this on my end, but I believe it should be fixed in rclcpp / below for the general user case