From 77b24fe8174669eace141f0a714ba2586cdb8a14 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alexander=20R=C3=B6ssler?= Date: Wed, 5 Feb 2020 15:15:15 +0000 Subject: [PATCH] video_stream: simplify callbacks --- src/video_stream.cpp | 24 ++++-------------------- 1 file changed, 4 insertions(+), 20 deletions(-) diff --git a/src/video_stream.cpp b/src/video_stream.cpp index 16772f5..8cf1cf5 100644 --- a/src/video_stream.cpp +++ b/src/video_stream.cpp @@ -373,22 +373,6 @@ virtual void disconnectionCallbackImpl() { } } -virtual void connectionCallback(const image_transport::SingleSubscriberPublisher&) { - connectionCallbackImpl(); -} - -virtual void infoConnectionCallback(const ros::SingleSubscriberPublisher&) { - connectionCallbackImpl(); -} - -virtual void disconnectionCallback(const image_transport::SingleSubscriberPublisher&) { - disconnectionCallbackImpl(); -} - -virtual void infoDisconnectionCallback(const ros::SingleSubscriberPublisher&) { - disconnectionCallbackImpl(); -} - virtual void configCallback(VideoStreamConfig& new_config, uint32_t level) { NODELET_DEBUG("configCallback"); @@ -477,13 +461,13 @@ virtual void onInit() { dyn_srv->setCallback(f); image_transport::SubscriberStatusCallback connect_cb = - boost::bind(&VideoStreamNodelet::connectionCallback, this, _1); + boost::bind(&VideoStreamNodelet::connectionCallbackImpl, this); ros::SubscriberStatusCallback info_connect_cb = - boost::bind(&VideoStreamNodelet::infoConnectionCallback, this, _1); + boost::bind(&VideoStreamNodelet::connectionCallbackImpl, this); image_transport::SubscriberStatusCallback disconnect_cb = - boost::bind(&VideoStreamNodelet::disconnectionCallback, this, _1); + boost::bind(&VideoStreamNodelet::disconnectionCallbackImpl, this); ros::SubscriberStatusCallback info_disconnect_cb = - boost::bind(&VideoStreamNodelet::infoDisconnectionCallback, this, _1); + boost::bind(&VideoStreamNodelet::disconnectionCallbackImpl, this); pub = image_transport::ImageTransport(*nh).advertiseCamera( "image_raw", 1, connect_cb, disconnect_cb,