Skip to content

Commit cadc7c2

Browse files
authored
Fix request logging, remove global parameters (#156)
1 parent 9fc0d63 commit cadc7c2

File tree

2 files changed

+34
-34
lines changed

2 files changed

+34
-34
lines changed

include/web_video_server/web_video_server.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,9 @@ class WebVideoServer
4343

4444
void setup_cleanup_inactive_streams();
4545

46+
bool handle_request(const async_web_server_cpp::HttpRequest &request,
47+
async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
48+
4649
bool handle_stream(const async_web_server_cpp::HttpRequest &request,
4750
async_web_server_cpp::HttpConnectionPtr connection, const char* begin, const char* end);
4851

@@ -61,10 +64,15 @@ class WebVideoServer
6164

6265
rclcpp::Node::SharedPtr node_;
6366
rclcpp::WallTimer<rclcpp::VoidCallbackType>::SharedPtr cleanup_timer_;
67+
68+
// Parameters
6469
int ros_threads_;
6570
double publish_rate_;
6671
int port_;
6772
std::string address_;
73+
bool verbose_;
74+
std::string default_stream_type_;
75+
6876
boost::shared_ptr<async_web_server_cpp::HttpServer> server_;
6977
async_web_server_cpp::HttpRequestHandlerGroup handler_group_;
7078

src/web_video_server.cpp

Lines changed: 26 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -21,34 +21,6 @@ using namespace boost::placeholders;
2121
namespace web_video_server
2222
{
2323

24-
static bool __verbose;
25-
26-
static std::string __default_stream_type;
27-
28-
static bool ros_connection_logger(async_web_server_cpp::HttpServerRequestHandler forward,
29-
const async_web_server_cpp::HttpRequest &request,
30-
async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
31-
const char* end)
32-
{
33-
if (__verbose)
34-
{
35-
// TODO reenable
36-
// RCLCPP_INFO(node->get_logger(), "Handling Request: %s", request.uri.c_str());
37-
}
38-
try
39-
{
40-
forward(request, connection, begin, end);
41-
return true;
42-
}
43-
catch (std::exception &e)
44-
{
45-
// TODO reenable
46-
// RCLCPP_WARN(node->get_logger(), "Error Handling Request: %s", e.what());
47-
return false;
48-
}
49-
return false;
50-
}
51-
5224
WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr & node) :
5325
node_(node), handler_group_(
5426
async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::not_found))
@@ -62,13 +34,13 @@ WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr & node) :
6234
node_->declare_parameter("default_stream_type", "mjpeg");
6335

6436
node_->get_parameter("port", port_);
65-
node_->get_parameter("verbose", __verbose);
37+
node_->get_parameter("verbose", verbose_);
6638
node_->get_parameter("address", address_);
6739
int server_threads;
6840
node_->get_parameter("server_threads", server_threads);
6941
node_->get_parameter("ros_threads", ros_threads_);
7042
node_->get_parameter("publish_rate", publish_rate_);
71-
node_->get_parameter("default_stream_type", __default_stream_type);
43+
node_->get_parameter("default_stream_type", default_stream_type_);
7244

7345
stream_types_["mjpeg"] = boost::shared_ptr<ImageStreamerType>(new MjpegStreamerType());
7446
stream_types_["png"] = boost::shared_ptr<ImageStreamerType>(new PngStreamerType());
@@ -87,7 +59,7 @@ WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr & node) :
8759
{
8860
server_.reset(
8961
new async_web_server_cpp::HttpServer(address_, boost::lexical_cast<std::string>(port_),
90-
boost::bind(ros_connection_logger, handler_group_, _1, _2, _3, _4),
62+
boost::bind(&WebVideoServer::handle_request, this, _1, _2, _3, _4),
9163
server_threads));
9264
}
9365
catch(boost::exception& e)
@@ -140,7 +112,7 @@ void WebVideoServer::cleanup_inactive_streams()
140112
typedef std::vector<boost::shared_ptr<ImageStreamer> >::iterator itr_type;
141113
itr_type new_end = std::partition(image_subscribers_.begin(), image_subscribers_.end(),
142114
!boost::bind(&ImageStreamer::isInactive, _1));
143-
if (__verbose)
115+
if (verbose_)
144116
{
145117
for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr)
146118
{
@@ -151,11 +123,31 @@ void WebVideoServer::cleanup_inactive_streams()
151123
}
152124
}
153125

126+
bool WebVideoServer::handle_request(const async_web_server_cpp::HttpRequest &request,
127+
async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
128+
const char* end)
129+
{
130+
if (verbose_)
131+
{
132+
RCLCPP_INFO(node_->get_logger(), "Handling Request: %s", request.uri.c_str());
133+
}
134+
135+
try
136+
{
137+
return handler_group_(request, connection, begin, end);
138+
}
139+
catch (std::exception &e)
140+
{
141+
RCLCPP_WARN(node_->get_logger(), "Error Handling Request: %s", e.what());
142+
return false;
143+
}
144+
}
145+
154146
bool WebVideoServer::handle_stream(const async_web_server_cpp::HttpRequest &request,
155147
async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
156148
const char* end)
157149
{
158-
std::string type = request.get_query_param_value_or_default("type", __default_stream_type);
150+
std::string type = request.get_query_param_value_or_default("type", default_stream_type_);
159151
if (stream_types_.find(type) != stream_types_.end())
160152
{
161153
std::string topic = request.get_query_param_value_or_default("topic", "");
@@ -211,7 +203,7 @@ bool WebVideoServer::handle_stream_viewer(const async_web_server_cpp::HttpReques
211203
async_web_server_cpp::HttpConnectionPtr connection, const char* begin,
212204
const char* end)
213205
{
214-
std::string type = request.get_query_param_value_or_default("type", __default_stream_type);
206+
std::string type = request.get_query_param_value_or_default("type", default_stream_type_);
215207
if (stream_types_.find(type) != stream_types_.end())
216208
{
217209
std::string topic = request.get_query_param_value_or_default("topic", "");

0 commit comments

Comments
 (0)