From 6a0653acafc132e66f6364bb414ebb7c7c1cc6bf Mon Sep 17 00:00:00 2001 From: Lucas Walter Date: Mon, 9 May 2022 09:58:42 -0700 Subject: [PATCH] use boost::placeholders::_N instead of deprecated _N --- src/web_video_server.cpp | 19 +++++++++++++------ 1 file changed, 13 insertions(+), 6 deletions(-) diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index a1e76e3..3d68940 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -73,17 +73,24 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) stream_types_["h264"] = boost::shared_ptr(new H264StreamerType()); stream_types_["vp9"] = boost::shared_ptr(new Vp9StreamerType()); - handler_group_.addHandlerForPath("/", boost::bind(&WebVideoServer::handle_list_streams, this, _1, _2, _3, _4)); - handler_group_.addHandlerForPath("/stream", boost::bind(&WebVideoServer::handle_stream, this, _1, _2, _3, _4)); + handler_group_.addHandlerForPath("/", boost::bind(&WebVideoServer::handle_list_streams, this, + boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); + handler_group_.addHandlerForPath("/stream", boost::bind(&WebVideoServer::handle_stream, this, + boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); handler_group_.addHandlerForPath("/stream_viewer", - boost::bind(&WebVideoServer::handle_stream_viewer, this, _1, _2, _3, _4)); - handler_group_.addHandlerForPath("/snapshot", boost::bind(&WebVideoServer::handle_snapshot, this, _1, _2, _3, _4)); + boost::bind(&WebVideoServer::handle_stream_viewer, this, + boost::placeholders::_1, boost::placeholders::_2, + boost::placeholders::_3, boost::placeholders::_4)); + handler_group_.addHandlerForPath("/snapshot", boost::bind(&WebVideoServer::handle_snapshot, this, + boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); try { server_.reset( new async_web_server_cpp::HttpServer(address_, boost::lexical_cast(port_), - boost::bind(ros_connection_logger, handler_group_, _1, _2, _3, _4), + boost::bind(ros_connection_logger, handler_group_, + boost::placeholders::_1, boost::placeholders::_2, + boost::placeholders::_3, boost::placeholders::_4), server_threads)); } catch(boost::exception& e) @@ -138,7 +145,7 @@ void WebVideoServer::cleanup_inactive_streams() { typedef std::vector >::iterator itr_type; itr_type new_end = std::partition(image_subscribers_.begin(), image_subscribers_.end(), - !boost::bind(&ImageStreamer::isInactive, _1)); + !boost::bind(&ImageStreamer::isInactive, boost::placeholders::_1)); if (__verbose) { for (itr_type itr = new_end; itr < image_subscribers_.end(); ++itr)