diff --git a/jsk_topic_tools/include/jsk_topic_tools/connection_based_nodelet.h b/jsk_topic_tools/include/jsk_topic_tools/connection_based_nodelet.h index 075ac3897..643b56cb5 100644 --- a/jsk_topic_tools/include/jsk_topic_tools/connection_based_nodelet.h +++ b/jsk_topic_tools/include/jsk_topic_tools/connection_based_nodelet.h @@ -192,13 +192,13 @@ namespace jsk_topic_tools { boost::mutex::scoped_lock lock(connection_mutex_); ros::SubscriberStatusCallback connect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConnectionBasedNodelet::connectionCallback, this, _1); #else = [this](auto& pub){ connectionCallback(pub); }; #endif ros::SubscriberStatusCallback disconnect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConnectionBasedNodelet::connectionCallback, this, _1); #else = [this](auto& pub){ connectionCallback(pub); }; @@ -262,14 +262,14 @@ namespace jsk_topic_tools { boost::mutex::scoped_lock lock(connection_mutex_); image_transport::SubscriberStatusCallback connect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConnectionBasedNodelet::imageConnectionCallback, this, _1); #else = [this](auto& pub){ imageConnectionCallback(pub); }; #endif image_transport::SubscriberStatusCallback disconnect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConnectionBasedNodelet::imageConnectionCallback, this, _1); #else @@ -334,28 +334,28 @@ namespace jsk_topic_tools { boost::mutex::scoped_lock lock(connection_mutex_); image_transport::SubscriberStatusCallback connect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConnectionBasedNodelet::cameraConnectionCallback, this, _1); #else = [this](auto& pub){ cameraConnectionCallback(pub); }; #endif image_transport::SubscriberStatusCallback disconnect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConnectionBasedNodelet::cameraConnectionCallback, this, _1); #else = [this](auto& pub){ cameraConnectionCallback(pub); }; #endif ros::SubscriberStatusCallback info_connect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConnectionBasedNodelet::cameraInfoConnectionCallback, this, _1); #else = [this](auto& pub){ cameraInfoConnectionCallback(pub); }; #endif ros::SubscriberStatusCallback info_disconnect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConnectionBasedNodelet::cameraInfoConnectionCallback, this, _1); #else diff --git a/jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp b/jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp index f43a4ac54..cb486fc46 100644 --- a/jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp +++ b/jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp @@ -12,7 +12,7 @@ namespace jsk_topic_tools srv_ = boost::make_shared >(pnh_); dynamic_reconfigure::Server::CallbackType f -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConstantRateThrottle::configCallback, this, _1, _2); #else = [this](auto& config, auto level) {configCallback(config, level); }; @@ -68,7 +68,7 @@ namespace jsk_topic_tools if (!advertised_) { sub_->shutdown(); ros::SubscriberStatusCallback connect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&ConstantRateThrottle::connectionCallback, this, _1); #else = [this](auto& pub){ connectionCallback(pub); }; diff --git a/jsk_topic_tools/src/diagnostic_nodelet.cpp b/jsk_topic_tools/src/diagnostic_nodelet.cpp index 365968ec0..a5bef07b5 100644 --- a/jsk_topic_tools/src/diagnostic_nodelet.cpp +++ b/jsk_topic_tools/src/diagnostic_nodelet.cpp @@ -56,7 +56,7 @@ namespace jsk_topic_tools diagnostic_updater_->setHardwareID(getName()); diagnostic_updater_->add( getName(), -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind( &DiagnosticNodelet::updateDiagnostic, this, diff --git a/jsk_topic_tools/src/hz_measure_nodelet.cpp b/jsk_topic_tools/src/hz_measure_nodelet.cpp index f859fe9b9..af662a271 100644 --- a/jsk_topic_tools/src/hz_measure_nodelet.cpp +++ b/jsk_topic_tools/src/hz_measure_nodelet.cpp @@ -78,7 +78,7 @@ namespace jsk_topic_tools diagnostic_updater_.reset(new TimeredDiagnosticUpdater(pnh_, ros::Duration(1.0))); diagnostic_updater_->setHardwareID(getName()); -#if __cplusplus < 201100L +#if __cplusplus < 201400L diagnostic_updater_->add(getName(), boost::bind(&HzMeasure::updateDiagnostic, this, _1)); diff --git a/jsk_topic_tools/src/lightweight_throttle_nodelet.cpp b/jsk_topic_tools/src/lightweight_throttle_nodelet.cpp index dd59d9551..62cf7ee50 100644 --- a/jsk_topic_tools/src/lightweight_throttle_nodelet.cpp +++ b/jsk_topic_tools/src/lightweight_throttle_nodelet.cpp @@ -45,7 +45,7 @@ namespace jsk_topic_tools srv_ = boost::make_shared >(pnh_); dynamic_reconfigure::Server::CallbackType f = -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind(&LightweightThrottle::configCallback, this, _1, _2); #else [this](auto& config, auto level){ configCallback(config, level); }; @@ -99,7 +99,7 @@ namespace jsk_topic_tools // This section should be called once sub_->shutdown(); // Shutdown before advertising topic ros::SubscriberStatusCallback connect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&LightweightThrottle::connectionCallback, this, _1); #else = [this](auto& pub){ connectionCallback(pub); }; diff --git a/jsk_topic_tools/src/mux_nodelet.cpp b/jsk_topic_tools/src/mux_nodelet.cpp index fe27fcff2..9997ff40d 100644 --- a/jsk_topic_tools/src/mux_nodelet.cpp +++ b/jsk_topic_tools/src/mux_nodelet.cpp @@ -194,7 +194,7 @@ namespace jsk_topic_tools { if (!advertised_) { // first time ros::SubscriberStatusCallback connect_cb -#if __cplusplus < 201100L +#if __cplusplus < 201400L = boost::bind(&MUX::connectCb, this, _1); #else = [this](auto& pub){ connectCb(pub); }; diff --git a/jsk_topic_tools/src/relay_nodelet.cpp b/jsk_topic_tools/src/relay_nodelet.cpp index d26bd254a..c862fcddc 100644 --- a/jsk_topic_tools/src/relay_nodelet.cpp +++ b/jsk_topic_tools/src/relay_nodelet.cpp @@ -50,7 +50,7 @@ namespace jsk_topic_tools diagnostic_updater_->setHardwareID(getName()); diagnostic_updater_->add( getName() + "::Relay", -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind( &Relay::updateDiagnostic, this, _1)); #else diff --git a/jsk_topic_tools/src/stealth_relay_nodelet.cpp b/jsk_topic_tools/src/stealth_relay_nodelet.cpp index 7b309839e..2060f6352 100644 --- a/jsk_topic_tools/src/stealth_relay_nodelet.cpp +++ b/jsk_topic_tools/src/stealth_relay_nodelet.cpp @@ -69,7 +69,7 @@ namespace jsk_topic_tools srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind(&StealthRelay::configCallback, this, _1, _2); #else [this](auto& config, auto level){ configCallback(config, level); }; diff --git a/jsk_topic_tools/src/synchronized_throttle_nodelet.cpp b/jsk_topic_tools/src/synchronized_throttle_nodelet.cpp index 995a6db6b..56c053092 100644 --- a/jsk_topic_tools/src/synchronized_throttle_nodelet.cpp +++ b/jsk_topic_tools/src/synchronized_throttle_nodelet.cpp @@ -87,7 +87,7 @@ void SynchronizedThrottle::onInit() srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind(&SynchronizedThrottle::configCallback, this, _1, _2); #else [this](auto& config, auto level){ configCallback(config, level); }; @@ -114,7 +114,7 @@ void SynchronizedThrottle::onInit() { check_sub_[i] = pnh_->subscribe( input_topics_[i], 1, -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind(&SynchronizedThrottle::checkCallback, this, _1, i) #else [this,i](auto& msg){ checkCallback(msg, i); } @@ -208,7 +208,7 @@ void SynchronizedThrottle::subscribe() if (n_topics < MAX_SYNC_NUM) { sub_[0]->registerCallback( -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind(&SynchronizedThrottle::fillNullMessage, this, _1) #else [this](auto& msg){ fillNullMessage(msg); } diff --git a/jsk_topic_tools/src/timered_diagnostic_updater.cpp b/jsk_topic_tools/src/timered_diagnostic_updater.cpp index c3b384e9d..0bbe549d2 100644 --- a/jsk_topic_tools/src/timered_diagnostic_updater.cpp +++ b/jsk_topic_tools/src/timered_diagnostic_updater.cpp @@ -44,7 +44,7 @@ namespace jsk_topic_tools { timer_ = nh.createTimer( timer_duration, -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind(&TimeredDiagnosticUpdater::timerCallback,this,_1) #else [this](auto& event){ timerCallback(event); } diff --git a/jsk_topic_tools/src/topic_buffer_client.cpp b/jsk_topic_tools/src/topic_buffer_client.cpp index 5ab8db2d3..e0d884123 100644 --- a/jsk_topic_tools/src/topic_buffer_client.cpp +++ b/jsk_topic_tools/src/topic_buffer_client.cpp @@ -201,7 +201,7 @@ int main(int argc, char **argv) pub_info->topic_with_header = false; ROS_INFO_STREAM("subscribe " << pub_info->topic_name+string("_update")); pub_info->sub = new ros::Subscriber(n.subscribe(pub_info->topic_name+string("_update"), 10, -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind(in_cb, _1, pub_info) #else [pub_info](auto& msg){ in_cb(msg, pub_info); } diff --git a/jsk_topic_tools/src/topic_buffer_server.cpp b/jsk_topic_tools/src/topic_buffer_server.cpp index b79b0f2a5..be881a7d6 100644 --- a/jsk_topic_tools/src/topic_buffer_server.cpp +++ b/jsk_topic_tools/src/topic_buffer_server.cpp @@ -220,7 +220,7 @@ int main(int argc, char **argv) sub_info->periodic = false; ROS_INFO_STREAM("subscribe " << sub_info->topic_name); sub_info->sub = new ros::Subscriber(n.subscribe(sub_info->topic_name, 10, -#if __cplusplus < 201100L +#if __cplusplus < 201400L boost::bind(in_cb, _1, sub_info) #else [sub_info](auto& msg){ in_cb(msg, sub_info); }