@@ -368,22 +368,6 @@ virtual void disconnectionCallbackImpl() {
368368 }
369369}
370370
371- virtual void connectionCallback (const image_transport::SingleSubscriberPublisher&) {
372- connectionCallbackImpl ();
373- }
374-
375- virtual void infoConnectionCallback (const ros::SingleSubscriberPublisher&) {
376- connectionCallbackImpl ();
377- }
378-
379- virtual void disconnectionCallback (const image_transport::SingleSubscriberPublisher&) {
380- disconnectionCallbackImpl ();
381- }
382-
383- virtual void infoDisconnectionCallback (const ros::SingleSubscriberPublisher&) {
384- disconnectionCallbackImpl ();
385- }
386-
387371virtual void configCallback (VideoStreamConfig& new_config, uint32_t level) {
388372 NODELET_DEBUG (" configCallback" );
389373
@@ -470,13 +454,13 @@ virtual void onInit() {
470454 dyn_srv->setCallback (f);
471455
472456 image_transport::SubscriberStatusCallback connect_cb =
473- boost::bind (&VideoStreamNodelet::connectionCallback , this , _1 );
457+ boost::bind (&VideoStreamNodelet::connectionCallbackImpl , this );
474458 ros::SubscriberStatusCallback info_connect_cb =
475- boost::bind (&VideoStreamNodelet::infoConnectionCallback , this , _1 );
459+ boost::bind (&VideoStreamNodelet::connectionCallbackImpl , this );
476460 image_transport::SubscriberStatusCallback disconnect_cb =
477- boost::bind (&VideoStreamNodelet::disconnectionCallback , this , _1 );
461+ boost::bind (&VideoStreamNodelet::disconnectionCallbackImpl , this );
478462 ros::SubscriberStatusCallback info_disconnect_cb =
479- boost::bind (&VideoStreamNodelet::infoDisconnectionCallback , this , _1 );
463+ boost::bind (&VideoStreamNodelet::disconnectionCallbackImpl , this );
480464 pub = image_transport::ImageTransport (*nh).advertiseCamera (
481465 " image_raw" , 1 ,
482466 connect_cb, disconnect_cb,
0 commit comments