3636#include < boost/algorithm/string/predicate.hpp>
3737#include < opencv2/opencv.hpp>
3838
39+ #include " rclcpp/rclcpp.hpp"
40+
3941#include " sensor_msgs/image_encodings.hpp"
4042#include " web_video_server/ros_compressed_streamer.hpp"
4143#include " web_video_server/jpeg_streamers.hpp"
@@ -51,26 +53,24 @@ using namespace boost::placeholders; // NOLINT
5153namespace web_video_server
5254{
5355
54- WebVideoServer::WebVideoServer (rclcpp::Node::SharedPtr & node )
55- : node_(node ), handler_group_(
56+ WebVideoServer::WebVideoServer (const rclcpp::NodeOptions & options )
57+ : rclcpp::Node( " web_video_server " , options ), handler_group_(
5658 async_web_server_cpp::HttpReply::stock_reply (async_web_server_cpp::HttpReply::not_found))
5759{
58- node_->declare_parameter (" port" , 8080 );
59- node_->declare_parameter (" verbose" , true );
60- node_->declare_parameter (" address" , " 0.0.0.0" );
61- node_->declare_parameter (" server_threads" , 1 );
62- node_->declare_parameter (" ros_threads" , 2 );
63- node_->declare_parameter (" publish_rate" , -1.0 );
64- node_->declare_parameter (" default_stream_type" , " mjpeg" );
65-
66- node_->get_parameter (" port" , port_);
67- node_->get_parameter (" verbose" , verbose_);
68- node_->get_parameter (" address" , address_);
60+ declare_parameter (" port" , 8080 );
61+ declare_parameter (" verbose" , true );
62+ declare_parameter (" address" , " 0.0.0.0" );
63+ declare_parameter (" server_threads" , 1 );
64+ declare_parameter (" publish_rate" , -1.0 );
65+ declare_parameter (" default_stream_type" , " mjpeg" );
66+
67+ get_parameter (" port" , port_);
68+ get_parameter (" verbose" , verbose_);
69+ get_parameter (" address" , address_);
6970 int server_threads;
70- node_->get_parameter (" server_threads" , server_threads);
71- node_->get_parameter (" ros_threads" , ros_threads_);
72- node_->get_parameter (" publish_rate" , publish_rate_);
73- node_->get_parameter (" default_stream_type" , default_stream_type_);
71+ get_parameter (" server_threads" , server_threads);
72+ get_parameter (" publish_rate" , publish_rate_);
73+ get_parameter (" default_stream_type" , default_stream_type_);
7474
7575 stream_types_[" mjpeg" ] = std::make_shared<MjpegStreamerType>();
7676 stream_types_[" png" ] = std::make_shared<PngStreamerType>();
@@ -102,32 +102,24 @@ WebVideoServer::WebVideoServer(rclcpp::Node::SharedPtr & node)
102102 );
103103 } catch (boost::exception & e) {
104104 RCLCPP_ERROR (
105- node_-> get_logger (), " Exception when creating the web server! %s:%d" ,
105+ get_logger (), " Exception when creating the web server! %s:%d" ,
106106 address_.c_str (), port_);
107107 throw ;
108108 }
109- }
110109
111- WebVideoServer::~WebVideoServer ()
112- {
113- }
110+ RCLCPP_INFO (get_logger (), " Waiting For connections on %s:%d" , address_.c_str (), port_);
114111
115- void WebVideoServer::setup_cleanup_inactive_streams ()
116- {
117- std::function<void ()> callback = std::bind (&WebVideoServer::cleanup_inactive_streams, this );
118- cleanup_timer_ = node_->create_wall_timer (500ms, callback);
112+ if (publish_rate_ > 0 ) {
113+ create_wall_timer (1s / publish_rate_, [this ]() {restreamFrames (1.0 / publish_rate_);});
114+ }
115+
116+ cleanup_timer_ = create_wall_timer (500ms, [this ]() {cleanup_inactive_streams ();});
117+
118+ server_->run ();
119119}
120120
121- void WebVideoServer::spin ()
121+ WebVideoServer::~WebVideoServer ()
122122{
123- server_->run ();
124- RCLCPP_INFO (node_->get_logger (), " Waiting For connections on %s:%d" , address_.c_str (), port_);
125- rclcpp::executors::MultiThreadedExecutor spinner (rclcpp::ExecutorOptions (), ros_threads_);
126- spinner.add_node (node_);
127- if (publish_rate_ > 0 ) {
128- node_->create_wall_timer (1s / publish_rate_, [this ]() {restreamFrames (1.0 / publish_rate_);});
129- }
130- spinner.spin ();
131123 server_->stop ();
132124}
133125
@@ -149,7 +141,7 @@ void WebVideoServer::cleanup_inactive_streams()
149141 [](const std::shared_ptr<ImageStreamer> & streamer) {return !streamer->isInactive ();});
150142 if (verbose_) {
151143 for (auto itr = new_end; itr < image_subscribers_.end (); ++itr) {
152- RCLCPP_INFO (node_-> get_logger (), " Removed Stream: %s" , (*itr)->getTopic ().c_str ());
144+ RCLCPP_INFO (get_logger (), " Removed Stream: %s" , (*itr)->getTopic ().c_str ());
153145 }
154146 }
155147 image_subscribers_.erase (new_end, image_subscribers_.end ());
@@ -162,13 +154,13 @@ bool WebVideoServer::handle_request(
162154 const char * end)
163155{
164156 if (verbose_) {
165- RCLCPP_INFO (node_-> get_logger (), " Handling Request: %s" , request.uri .c_str ());
157+ RCLCPP_INFO (get_logger (), " Handling Request: %s" , request.uri .c_str ());
166158 }
167159
168160 try {
169161 return handler_group_ (request, connection, begin, end);
170162 } catch (std::exception & e) {
171- RCLCPP_WARN (node_-> get_logger (), " Error Handling Request: %s" , e.what ());
163+ RCLCPP_WARN (get_logger (), " Error Handling Request: %s" , e.what ());
172164 return false ;
173165 }
174166}
@@ -184,7 +176,7 @@ bool WebVideoServer::handle_stream(
184176 // Fallback for topics without corresponding compressed topics
185177 if (type == std::string (" ros_compressed" )) {
186178 std::string compressed_topic_name = topic + " /compressed" ;
187- auto tnat = node_-> get_topic_names_and_types ();
179+ auto tnat = get_topic_names_and_types ();
188180 bool did_find_compressed_topic = false ;
189181 for (auto topic_and_types : tnat) {
190182 if (topic_and_types.second .size () > 1 ) {
@@ -201,13 +193,13 @@ bool WebVideoServer::handle_stream(
201193 }
202194 if (!did_find_compressed_topic) {
203195 RCLCPP_WARN (
204- node_-> get_logger (),
196+ get_logger (),
205197 " Could not find compressed image topic for %s, falling back to mjpeg" , topic.c_str ());
206198 type = " mjpeg" ;
207199 }
208200 }
209201 std::shared_ptr<ImageStreamer> streamer = stream_types_[type]->create_streamer (
210- request, connection, node_ );
202+ request, connection, shared_from_this () );
211203 streamer->start ();
212204 std::scoped_lock lock (subscriber_mutex_);
213205 image_subscribers_.push_back (streamer);
@@ -224,7 +216,7 @@ bool WebVideoServer::handle_snapshot(
224216 const char * end)
225217{
226218 std::shared_ptr<ImageStreamer> streamer = std::make_shared<JpegSnapshotStreamer>(
227- request, connection, node_ );
219+ request, connection, shared_from_this () );
228220 streamer->start ();
229221
230222 std::scoped_lock lock (subscriber_mutex_);
@@ -243,7 +235,7 @@ bool WebVideoServer::handle_stream_viewer(
243235 // Fallback for topics without corresponding compressed topics
244236 if (type == std::string (" ros_compressed" )) {
245237 std::string compressed_topic_name = topic + " /compressed" ;
246- auto tnat = node_-> get_topic_names_and_types ();
238+ auto tnat = get_topic_names_and_types ();
247239 bool did_find_compressed_topic = false ;
248240 for (auto topic_and_types : tnat) {
249241 if (topic_and_types.second .size () > 1 ) {
@@ -260,7 +252,7 @@ bool WebVideoServer::handle_stream_viewer(
260252 }
261253 if (!did_find_compressed_topic) {
262254 RCLCPP_WARN (
263- node_-> get_logger (),
255+ get_logger (),
264256 " Could not find compressed image topic for %s, falling back to mjpeg" , topic.c_str ());
265257 type = " mjpeg" ;
266258 }
@@ -292,7 +284,7 @@ bool WebVideoServer::handle_list_streams(
292284{
293285 std::vector<std::string> image_topics;
294286 std::vector<std::string> camera_info_topics;
295- auto tnat = node_-> get_topic_names_and_types ();
287+ auto tnat = get_topic_names_and_types ();
296288 for (auto topic_and_types : tnat) {
297289 if (topic_and_types.second .size () > 1 ) {
298290 // skip over topics with more than one type
@@ -380,14 +372,9 @@ bool WebVideoServer::handle_list_streams(
380372
381373} // namespace web_video_server
382374
383- int main (int argc, char ** argv)
384- {
385- rclcpp::init (argc, argv);
386- auto node = std::make_shared<rclcpp::Node>(" web_video_server" );
387-
388- web_video_server::WebVideoServer server (node);
389- server.setup_cleanup_inactive_streams ();
390- server.spin ();
375+ #include " rclcpp_components/register_node_macro.hpp"
391376
392- return 0 ;
393- }
377+ // Register the component with class_loader.
378+ // This acts as a sort of entry point, allowing the component to be discoverable when its library
379+ // is being loaded into a running process.
380+ RCLCPP_COMPONENTS_REGISTER_NODE (web_video_server::WebVideoServer)
0 commit comments