@@ -131,6 +131,28 @@ bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &requ
131
131
std::string type = request.get_query_param_value_or_default (" type" , __default_stream_type);
132
132
if (stream_types_.find (type) != stream_types_.end ())
133
133
{
134
+ std::string topic = request.get_query_param_value_or_default (" topic" , " " );
135
+ // Fallback for topics without corresponding compressed topics
136
+ if (type == std::string (" ros_compressed" ))
137
+ {
138
+ std::string compressed_topic_name = topic + " /compressed" ;
139
+ ros::master::V_TopicInfo topics;
140
+ ros::master::getTopics (topics);
141
+ bool did_find_compressed_topic = false ;
142
+ for (ros::master::V_TopicInfo::iterator it = topics.begin (); it != topics.end (); ++it)
143
+ {
144
+ if (it->name == compressed_topic_name)
145
+ {
146
+ did_find_compressed_topic = true ;
147
+ break ;
148
+ }
149
+ }
150
+ if (!did_find_compressed_topic)
151
+ {
152
+ ROS_WARN_STREAM (" Could not find compressed image topic for " << topic << " , falling back to mjpeg" );
153
+ type = " mjpeg" ;
154
+ }
155
+ }
134
156
boost::shared_ptr<ImageStreamer> streamer = stream_types_[type]->create_streamer (request, connection, nh_);
135
157
streamer->start ();
136
158
boost::mutex::scoped_lock lock (subscriber_mutex_);
@@ -160,10 +182,32 @@ bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpReques
160
182
async_web_server_cpp::HttpConnectionPtr connection, const char * begin,
161
183
const char * end)
162
184
{
163
- std::string type = request.get_query_param_value_or_default (" type" , " mjpeg " );
185
+ std::string type = request.get_query_param_value_or_default (" type" , __default_stream_type );
164
186
if (stream_types_.find (type) != stream_types_.end ())
165
187
{
166
188
std::string topic = request.get_query_param_value_or_default (" topic" , " " );
189
+ // Fallback for topics without corresponding compressed topics
190
+ if (type == std::string (" ros_compressed" ))
191
+ {
192
+
193
+ std::string compressed_topic_name = topic + " /compressed" ;
194
+ ros::master::V_TopicInfo topics;
195
+ ros::master::getTopics (topics);
196
+ bool did_find_compressed_topic = false ;
197
+ for (ros::master::V_TopicInfo::iterator it = topics.begin (); it != topics.end (); ++it)
198
+ {
199
+ if (it->name == compressed_topic_name)
200
+ {
201
+ did_find_compressed_topic = true ;
202
+ break ;
203
+ }
204
+ }
205
+ if (!did_find_compressed_topic)
206
+ {
207
+ ROS_WARN_STREAM (" Could not find compressed image topic for " << topic << " , falling back to mjpeg" );
208
+ type = " mjpeg" ;
209
+ }
210
+ }
167
211
168
212
async_web_server_cpp::HttpReply::builder (async_web_server_cpp::HttpReply::ok).header (" Connection" , " close" ).header (
169
213
" Server" , " web_video_server" ).header (" Content-type" , " text/html;" ).write (connection);
0 commit comments