Skip to content

Commit

Permalink
auto lambda for c++14
Browse files Browse the repository at this point in the history
  • Loading branch information
iory committed Mar 21, 2023
1 parent 720b6a9 commit ee0cb1f
Show file tree
Hide file tree
Showing 12 changed files with 23 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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); };
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace jsk_topic_tools

srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f
#if __cplusplus < 201100L
#if __cplusplus < 201400L
= boost::bind(&ConstantRateThrottle::configCallback, this, _1, _2);
#else
= [this](auto& config, auto level) {configCallback(config, level); };
Expand Down Expand Up @@ -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); };
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/diagnostic_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/hz_measure_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down
4 changes: 2 additions & 2 deletions jsk_topic_tools/src/lightweight_throttle_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace jsk_topic_tools

srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f =
#if __cplusplus < 201100L
#if __cplusplus < 201400L
boost::bind(&LightweightThrottle::configCallback, this, _1, _2);
#else
[this](auto& config, auto level){ configCallback(config, level); };
Expand Down Expand Up @@ -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); };
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/mux_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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); };
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/relay_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/stealth_relay_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ namespace jsk_topic_tools

srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f =
#if __cplusplus < 201100L
#if __cplusplus < 201400L
boost::bind(&StealthRelay::configCallback, this, _1, _2);
#else
[this](auto& config, auto level){ configCallback(config, level); };
Expand Down
6 changes: 3 additions & 3 deletions jsk_topic_tools/src/synchronized_throttle_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ void SynchronizedThrottle::onInit()

srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f =
#if __cplusplus < 201100L
#if __cplusplus < 201400L
boost::bind(&SynchronizedThrottle::configCallback, this, _1, _2);
#else
[this](auto& config, auto level){ configCallback(config, level); };
Expand All @@ -114,7 +114,7 @@ void SynchronizedThrottle::onInit()
{
check_sub_[i] = pnh_->subscribe<topic_tools::ShapeShifterStamped>(
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); }
Expand Down Expand Up @@ -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); }
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/timered_diagnostic_updater.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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); }
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/topic_buffer_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ShapeShifter>(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); }
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/topic_buffer_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ShapeShifter>(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); }
Expand Down

0 comments on commit ee0cb1f

Please sign in to comment.