Skip to content

Commit 9cdc6b2

Browse files
feat: Add shutdown handler for client to call and close alive sockets (#194)
* feat: add /shutdown endpoint to stop active streams (resolves #193) Implements the feature requested in issue #193: a client-callable HTTP endpoint that gracefully closes alive MJPEG/stream connections server-side, preventing lingering TCP sockets when UI components unmount. Changes: - StreamerInterface: add virtual stop() (no-op default) and get_client_id() - StreamerBase: implement stop() (marks inactive, releases connection) and get_client_id(); populate client_id_ from 'client_id' query param - WebVideoServer: register /shutdown route and implement handle_shutdown() which stops all streams for a topic, or a single named stream if client_id is provided; returns plain-text 'stopped=<count>' - README: document /shutdown endpoint, parameters, and client_id usage Rewrite of PR #194 adapted to the pluginlib-based architecture introduced in #192 and the naming/style conventions enforced by #195. * Update include/web_video_server/streamer.hpp make pure virtual Co-authored-by: Błażej Sowa <bsowa123@gmail.com> * Update include/web_video_server/streamer.hpp make pure virtual Co-authored-by: Błażej Sowa <bsowa123@gmail.com> * feat-193: fixed client_id empty logging --------- Co-authored-by: Błażej Sowa <bsowa123@gmail.com>
1 parent 02a5ffc commit 9cdc6b2

File tree

5 files changed

+105
-1
lines changed

5 files changed

+105
-1
lines changed

README.md

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,35 @@ http://localhost:8080/snapshot?topic=/camera/image_raw
178178
| `default_transport` | string | "raw" | "raw", "compressed", "theora" | Image transport to use |
179179
| `qos_profile` | string | "default" | "default", "system_default", "sensor_data", "services_default" | QoS profile for ROS 2 subscribers |
180180

181+
### Stop an Active Stream
182+
183+
To stop one or more active streams from the server side (e.g. when a UI component unmounts), use the `/shutdown` endpoint:
184+
185+
```
186+
http://localhost:8080/shutdown?topic=/camera/image_raw
187+
```
188+
189+
This closes all active streams for the given topic. An optional `client_id` parameter scopes the shutdown to a single named connection:
190+
191+
```
192+
http://localhost:8080/shutdown?topic=/camera/image_raw&client_id=my-ui
193+
```
194+
195+
To associate a stream with a `client_id`, pass it when opening the stream:
196+
197+
```
198+
http://localhost:8080/stream?topic=/camera/image_raw&client_id=my-ui
199+
```
200+
201+
The response is plain text in the form `stopped=<count>`, where `<count>` is the number of streams that were stopped. Returns `400 Bad Request` if `topic` is omitted.
202+
203+
#### URL Parameters for Shutdown
204+
205+
| Parameter | Type | Default | Description |
206+
|-----------|------|---------|-------------|
207+
| `topic` | string | (required) | The ROS topic whose streams should be stopped |
208+
| `client_id` | string | (none) | If provided, only the stream with this client_id is stopped |
209+
181210
## Creating custom streamer plugins
182211
See the [custom streamer plugin tutorial](doc/custom-streamer-plugin.md) for information on how to write your own streamer plugins.
183212

include/web_video_server/streamer.hpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,11 @@ class StreamerInterface
5656
*/
5757
virtual void start() = 0;
5858

59+
/**
60+
* @brief Stops the streaming process and marks the streamer as inactive.
61+
*/
62+
virtual void stop() = 0;
63+
5964
/**
6065
* @brief Returns true if the streamer is inactive and should be deleted.
6166
*
@@ -73,6 +78,11 @@ class StreamerInterface
7378
* @brief Returns the topic being streamed.
7479
*/
7580
virtual std::string get_topic() = 0;
81+
82+
/**
83+
* @brief Returns the client_id associated with this stream, or an empty string if none.
84+
*/
85+
virtual std::string get_client_id() = 0;
7686
};
7787

7888
/**
@@ -87,6 +97,12 @@ class StreamerBase : public StreamerInterface
8797
rclcpp::Node::WeakPtr node,
8898
std::string logger_name = "streamer");
8999

100+
void stop() override
101+
{
102+
inactive_ = true;
103+
connection_.reset();
104+
}
105+
90106
bool is_inactive() override
91107
{
92108
return inactive_;
@@ -97,6 +113,11 @@ class StreamerBase : public StreamerInterface
97113
return topic_;
98114
}
99115

116+
std::string get_client_id() override
117+
{
118+
return client_id_;
119+
}
120+
100121
protected:
101122
rclcpp::Node::SharedPtr lock_node() const;
102123

@@ -106,6 +127,7 @@ class StreamerBase : public StreamerInterface
106127
rclcpp::Logger logger_;
107128
bool inactive_;
108129
std::string topic_;
130+
std::string client_id_;
109131
};
110132

111133
/**

include/web_video_server/web_video_server.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,11 @@ class WebVideoServer : public rclcpp::Node
8989
async_web_server_cpp::HttpConnectionPtr connection,
9090
const char * begin, const char * end);
9191

92+
bool handle_shutdown(
93+
const async_web_server_cpp::HttpRequest & request,
94+
async_web_server_cpp::HttpConnectionPtr connection,
95+
const char * begin, const char * end);
96+
9297
bool handle_list_streams(
9398
const async_web_server_cpp::HttpRequest & request,
9499
async_web_server_cpp::HttpConnectionPtr connection,

src/streamer.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,8 @@ StreamerBase::StreamerBase(
5151
std::string logger_name)
5252
: connection_(connection), request_(request), node_(std::move(node)),
5353
logger_(node_.lock()->get_logger().get_child(logger_name)), inactive_(false),
54-
topic_(request.get_query_param_value_or_default("topic", ""))
54+
topic_(request.get_query_param_value_or_default("topic", "")),
55+
client_id_(request.get_query_param_value_or_default("client_id", ""))
5556
{
5657
}
5758

src/web_video_server.cpp

Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -120,6 +120,9 @@ WebVideoServer::WebVideoServer(const rclcpp::NodeOptions & options)
120120
handler_group_.addHandlerForPath(
121121
"/snapshot",
122122
boost::bind(&WebVideoServer::handle_snapshot, this, _1, _2, _3, _4));
123+
handler_group_.addHandlerForPath(
124+
"/shutdown",
125+
boost::bind(&WebVideoServer::handle_shutdown, this, _1, _2, _3, _4));
123126

124127
try {
125128
server_.reset(
@@ -263,6 +266,50 @@ bool WebVideoServer::handle_stream_viewer(
263266
return true;
264267
}
265268

269+
bool WebVideoServer::handle_shutdown(
270+
const async_web_server_cpp::HttpRequest & request,
271+
async_web_server_cpp::HttpConnectionPtr connection, const char * begin,
272+
const char * end)
273+
{
274+
const std::string topic = request.get_query_param_value_or_default("topic", "");
275+
if (topic.empty()) {
276+
async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::bad_request)(
277+
request, connection, begin, end);
278+
return true;
279+
}
280+
281+
const std::string client_id = request.get_query_param_value_or_default("client_id", "");
282+
283+
int stopped = 0;
284+
{
285+
const std::scoped_lock lock(streamers_mutex_);
286+
for (auto & streamer : streamers_) {
287+
if (streamer->get_topic() == topic) {
288+
if (client_id.empty() || streamer->get_client_id() == client_id) {
289+
streamer->stop();
290+
++stopped;
291+
}
292+
}
293+
}
294+
}
295+
296+
if (verbose_) {
297+
const std::string client_id_info = client_id.empty() ? "" : " (client_id='" + client_id + "')";
298+
RCLCPP_INFO(
299+
get_logger(), "Shutdown request for topic '%s'%s: stopped %d stream(s)",
300+
topic.c_str(), client_id_info.c_str(), stopped);
301+
}
302+
303+
async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok)
304+
.header("Connection", "close")
305+
.header("Server", "web_video_server")
306+
.header("Content-type", "text/plain;")
307+
.write(connection);
308+
309+
connection->write("stopped=" + std::to_string(stopped));
310+
return true;
311+
}
312+
266313
bool WebVideoServer::handle_list_streams(
267314
const async_web_server_cpp::HttpRequest & /* request */,
268315
async_web_server_cpp::HttpConnectionPtr connection, const char * /* begin */,

0 commit comments

Comments
 (0)