Skip to content

Commit 5e4b1b4

Browse files
kineticsystemclaude
andcommitted
Fixed issue with first visualization mask not being received by the UI
Web Video Server subscriber now automatically detects publisher QoS when no qos_profile query parameter is specified (defaults to "auto"). Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
1 parent 9cdc6b2 commit 5e4b1b4

File tree

1 file changed

+77
-13
lines changed

1 file changed

+77
-13
lines changed

src/streamers/image_transport_streamer.cpp

Lines changed: 77 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
#include <exception>
3535
#include <functional>
3636
#include <mutex>
37+
#include <optional>
3738
#include <string>
3839
#include <vector>
3940

@@ -55,6 +56,7 @@
5556
#include "image_transport/transport_hints.hpp"
5657
#include "rclcpp/node.hpp"
5758
#include "rclcpp/logging.hpp"
59+
#include "rclcpp/qos.hpp"
5860
#include "rmw/qos_profiles.h"
5961
#include "sensor_msgs/msg/image.hpp"
6062

@@ -84,6 +86,78 @@ std::vector<std::string> get_image_topics(rclcpp::Node & node)
8486
return result;
8587
}
8688

89+
std::optional<rmw_qos_profile_t> detect_publisher_qos(
90+
const rclcpp::Node::SharedPtr & node,
91+
const rclcpp::Logger & logger,
92+
const std::string & topic)
93+
{
94+
RCLCPP_INFO(logger, "Attempting to auto-detect QoS for topic: %s", topic.c_str());
95+
96+
const auto topic_endpoint_info_array = node->get_publishers_info_by_topic(topic);
97+
if (topic_endpoint_info_array.empty()) {
98+
RCLCPP_WARN(logger, "No publishers found for topic: %s", topic.c_str());
99+
return std::nullopt;
100+
}
101+
102+
// Use the first publisher's QoS as reference.
103+
const auto & endpoint_info = topic_endpoint_info_array.front();
104+
const auto qos_profile = endpoint_info.qos_profile();
105+
106+
const std::string reliability =
107+
(qos_profile.reliability() == rclcpp::ReliabilityPolicy::Reliable) ? "RELIABLE" : "BEST_EFFORT";
108+
const std::string durability =
109+
(qos_profile.durability() == rclcpp::DurabilityPolicy::TransientLocal) ?
110+
"TRANSIENT_LOCAL" : "VOLATILE";
111+
112+
RCLCPP_INFO(
113+
logger, "Detected QoS - Reliability: %s, Durability: %s, History depth: %zu",
114+
reliability.c_str(), durability.c_str(), qos_profile.depth());
115+
116+
// Convert rclcpp QoS to rmw QoS profile.
117+
auto rmw_qos = rmw_qos_profile_default;
118+
rmw_qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
119+
rmw_qos.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
120+
rmw_qos.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
121+
rmw_qos.depth = qos_profile.depth();
122+
123+
if (qos_profile.reliability() == rclcpp::ReliabilityPolicy::Reliable) {
124+
rmw_qos.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
125+
}
126+
if (qos_profile.durability() == rclcpp::DurabilityPolicy::TransientLocal) {
127+
rmw_qos.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
128+
}
129+
130+
return rmw_qos;
131+
}
132+
133+
std::optional<rmw_qos_profile_t> get_qos_profile(
134+
const rclcpp::Node::SharedPtr & node,
135+
const rclcpp::Logger & logger,
136+
const std::string & profile_name,
137+
const std::string & topic)
138+
{
139+
if (profile_name == "auto") {
140+
auto qos_profile = detect_publisher_qos(node, logger, topic);
141+
if (!qos_profile) {
142+
RCLCPP_WARN(
143+
logger, "Could not auto-detect QoS for topic %s. Using default profile.", topic.c_str());
144+
return rmw_qos_profile_default;
145+
}
146+
RCLCPP_INFO(logger, "Using auto-detected QoS profile for topic %s", topic.c_str());
147+
return qos_profile;
148+
}
149+
150+
RCLCPP_INFO(
151+
logger, "Using specified QoS profile %s for topic %s", profile_name.c_str(), topic.c_str());
152+
auto qos_profile = web_video_server::get_qos_profile_from_name(profile_name);
153+
if (!qos_profile) {
154+
RCLCPP_ERROR(
155+
logger, "Invalid QoS profile %s specified. Using default profile.", profile_name.c_str());
156+
return rmw_qos_profile_default;
157+
}
158+
return qos_profile;
159+
}
160+
87161
} // namespace
88162

89163
ImageTransportStreamerBase::ImageTransportStreamerBase(
@@ -97,7 +171,7 @@ ImageTransportStreamerBase::ImageTransportStreamerBase(
97171
output_height_ = request.get_query_param_value_or_default<int>("height", -1);
98172
invert_ = request.has_query_param("invert");
99173
default_transport_ = request.get_query_param_value_or_default("default_transport", "raw");
100-
qos_profile_name_ = request.get_query_param_value_or_default("qos_profile", "default");
174+
qos_profile_name_ = request.get_query_param_value_or_default("qos_profile", "auto");
101175
}
102176

103177
ImageTransportStreamerBase::~ImageTransportStreamerBase()
@@ -133,18 +207,8 @@ void ImageTransportStreamerBase::start()
133207
}
134208
}
135209

136-
// Get QoS profile from query parameter
137-
RCLCPP_INFO(
138-
logger_, "Streaming topic %s with QoS profile %s", topic_.c_str(),
139-
qos_profile_name_.c_str());
140-
auto qos_profile = get_qos_profile_from_name(qos_profile_name_);
141-
if (!qos_profile) {
142-
qos_profile = rmw_qos_profile_default;
143-
RCLCPP_ERROR(
144-
logger_,
145-
"Invalid QoS profile %s specified. Using default profile.",
146-
qos_profile_name_.c_str());
147-
}
210+
// Get QoS profile based on user selection or auto-detect.
211+
const auto qos_profile = get_qos_profile(node, logger_, qos_profile_name_, topic_);
148212

149213
// Create subscriber
150214
image_sub_ = image_transport::create_subscription(

0 commit comments

Comments
 (0)