diff --git a/.github/workflows/config.yml b/.github/workflows/config.yml index 782b7943b..d42f9826f 100644 --- a/.github/workflows/config.yml +++ b/.github/workflows/config.yml @@ -20,7 +20,7 @@ jobs: ROS_PARALLEL_TEST_JOBS: "-j8" # latest catkin_virtualenv with pip==21.0.1 is incompatible with python 2.x # https://github.com/jsk-ros-pkg/jsk_3rdparty/pull/237 - BEFORE_SCRIPT : "sudo pip install virtualenv==15.1.0" + BEFORE_SCRIPT : "sudo pip install virtualenv==15.1.0 setuptools==44.1.1" - ROS_DISTRO: kinetic CONTAINER: ubuntu:16.04 ROS_PARALLEL_TEST_JOBS: "-j8" @@ -84,3 +84,77 @@ jobs: TEST_PKGS : ${{ matrix.TEST_PKGS }} BEFORE_SCRIPT : ${{ matrix.BEFORE_SCRIPT }} EXTRA_DEB : ${{ matrix.EXTRA_DEB }} + + + ubuntu: + runs-on: ubuntu-latest + + strategy: + fail-fast: false + matrix: + include: + - DISTRO: ubuntu:22.04 + + container: ${{ matrix.DISTRO }} + + steps: + - name: Chcekout Source + uses: actions/checkout@v3.0.2 + + - name: Install Buildtools + run: | + set -x + echo 'debconf debconf/frontend select Noninteractive' | debconf-set-selections + apt update -q + apt install -y -q -qq catkin git curl build-essential libboost-all-dev python3-pip python3-venv python3-rosdep2 + apt install -y -q -qq ros-desktop-dev rosbash + apt install -y -q -qq libself-test-dev libpcl-ros-dev + apt install -y -q -qq ros-core-dev ros-robot-dev + pip install vcstool + rosdep update + + - name: Setup rosinstall_generator + run: | + set -x + # install rosinstall_geneartor with --depend-type buildtool build, see https://github.com/ros-infrastructure/rosinstall_generator/pull/81 + git clone https://github.com/k-okada/rosinstall_generator -b add_depend_type + cd rosinstall_generator + python3 ./setup.py install + + - name: Setup Dependencies Workspace + run: | + set -x + # install dependencies + mkdir -p ~/ws_depend/src + cd ~/ws_depend/src + ROS_PACKAGE_PATH=/usr/share rosinstall_generator --rosdistro noetic --from-path $GITHUB_WORKSPACE --deps --exclude RPP --depend-type buildtool build | tee repos + vcs import --shallow < repos + # override to use latest development for 22.04 + rosinstall_generator laser_filters laser_assembler map_server --rosdistro noetic --upstream-development | vcs import --force + rosinstall_generator catkin_virtualenv --rosdistro noetic | vcs import --force + rm -fr jsk_common + curl -s -L -O https://patch-diff.githubusercontent.com/raw/locusrobotics/catkin_virtualenv/pull/89.diff + patch -p1 < 89.diff + rosdep install -qq -r -y --from-path . --ignore-src || echo "OK" + cd .. + catkin_make_isolated --cmake-args -DCATKIN_ENABLE_TESTING=OFF + + - name: Setup Workspace + run: | + set -x + # hack! + apt install -y -q -qq python-is-python3 + sed -i s/noetic/Debian/ $GITHUB_WORKSPACE/jsk_rosbag_tools/CMakeLists.txt + # setup workspace + mkdir -p ~/ws_current/src + cd ~/ws_current/src + ln -sf $GITHUB_WORKSPACE . + rosdep install -qq -r -y --from-path . --ignore-src || echo "OK" + + - name: Compile Packages + run: | + set -x + cd ~/ws_current/ + source ~/ws_depend/devel_isolated/setup.bash + catkin_make_isolated --cmake-args -DCATKIN_ENABLE_TESTING=OFF + shell: bash diff --git a/jsk_network_tools/setup.py b/jsk_network_tools/setup.py index 7ffd6d804..844bbc07c 100755 --- a/jsk_network_tools/setup.py +++ b/jsk_network_tools/setup.py @@ -1,6 +1,6 @@ ## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD -from distutils.core import setup +from setuptools import setup from catkin_pkg.python_setup import generate_distutils_setup # fetch values from package.xml diff --git a/jsk_ros_patch/image_view2/CMakeLists.txt b/jsk_ros_patch/image_view2/CMakeLists.txt index c9509c3c9..447840333 100644 --- a/jsk_ros_patch/image_view2/CMakeLists.txt +++ b/jsk_ros_patch/image_view2/CMakeLists.txt @@ -11,12 +11,6 @@ if (CMAKE_VERSION VERSION_LESS 3.4) endif(CCACHE_FOUND) endif() -if(NOT $ENV{ROS_DISTRO} STRLESS noetic) - add_compile_options(-std=c++14) -elseif(NOT $ENV{ROS_DISTRO} STRLESS kinetic) - add_compile_options(-std=c++11) -endif() - find_package(catkin REQUIRED COMPONENTS roscpp dynamic_reconfigure cv_bridge std_msgs sensor_msgs geometry_msgs image_transport tf image_geometry message_filters message_generation std_srvs pcl_ros) generate_dynamic_reconfigure_options( diff --git a/jsk_ros_patch/image_view2/image_view2.cpp b/jsk_ros_patch/image_view2/image_view2.cpp index 754672116..f50b74f82 100644 --- a/jsk_ros_patch/image_view2/image_view2.cpp +++ b/jsk_ros_patch/image_view2/image_view2.cpp @@ -116,7 +116,11 @@ namespace image_view2{ srv_ = boost::make_shared >(local_nh); dynamic_reconfigure::Server::CallbackType f = +#if __cplusplus < 201100L boost::bind(&ImageView2::config_callback, this, _1, _2); +#else + [this](auto& config, auto level){ config_callback(config, level); }; +#endif srv_->setCallback(f); } diff --git a/jsk_ros_patch/image_view2/points_rectangle_extractor.cpp b/jsk_ros_patch/image_view2/points_rectangle_extractor.cpp index 89d4f13cc..7eac64e96 100644 --- a/jsk_ros_patch/image_view2/points_rectangle_extractor.cpp +++ b/jsk_ros_patch/image_view2/points_rectangle_extractor.cpp @@ -13,6 +13,27 @@ #include #include +#if BOOST_VERSION < 106000 // since 1.60.0, boost uses placeholders namesapce for _1,_2... +#ifndef BOOST_PLAEHOLDERS +#define BOOST_PLAEHOLDERS +namespace boost +{ + namespace placeholders + { + extern boost::arg<1> _1; + extern boost::arg<2> _2; + extern boost::arg<3> _3; + extern boost::arg<4> _4; + extern boost::arg<5> _5; + extern boost::arg<6> _6; + extern boost::arg<7> _7; + extern boost::arg<8> _8; + extern boost::arg<9> _9; + } // namespace placeholders +} // namespace boost +#endif // BOOST_PLAEHOLDERS +#endif // BOOST_VERSION < 106000 + class PointsRectExtractor { typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, @@ -43,11 +64,11 @@ class PointsRectExtractor sync_a_polygon_ = boost::make_shared < message_filters::Synchronizer< PolygonApproxSyncPolicy > > (queue_size); sync_a_polygon_->connectInput (points_sub_, rect_sub_); - sync_a_polygon_->registerCallback (boost::bind (&PointsRectExtractor::callback_polygon, this, _1, _2)); + sync_a_polygon_->registerCallback (boost::bind (&PointsRectExtractor::callback_polygon, this, boost::placeholders::_1, boost::placeholders::_2)); sync_a_point_ = boost::make_shared < message_filters::Synchronizer< PointApproxSyncPolicy > > (queue_size); sync_a_point_->connectInput (points_sub_, point_sub_); - sync_a_point_->registerCallback (boost::bind (&PointsRectExtractor::callback_point, this, _1, _2)); + sync_a_point_->registerCallback (boost::bind (&PointsRectExtractor::callback_point, this, boost::placeholders::_1, boost::placeholders::_2)); pub_ = pnode_.advertise< sensor_msgs::PointCloud2 > ("output", 1); } diff --git a/jsk_tilt_laser/src/spin_laser_snapshotter.cpp b/jsk_tilt_laser/src/spin_laser_snapshotter.cpp index d92bdb2c3..e60164717 100644 --- a/jsk_tilt_laser/src/spin_laser_snapshotter.cpp +++ b/jsk_tilt_laser/src/spin_laser_snapshotter.cpp @@ -103,8 +103,12 @@ class SpinLaserSnapshotter private_ns_.param("spindle_frame", spindle_frame_, std::string("multisense/spindle")); private_ns_.param("motor_frame", motor_frame_, std::string("multisense/motor")); timer_ = private_ns_.createTimer( - ros::Duration(1.0 / rate_), boost::bind( - &SpinLaserSnapshotter::timerCallback, this, _1)); + ros::Duration(1.0 / rate_), +#if __cplusplus < 201100L + boost::bind(&SpinLaserSnapshotter::timerCallback, this, _1)); +#else + [this](auto& event){ timerCallback(event); }); +#endif } } diff --git a/jsk_topic_tools/CMakeLists.txt b/jsk_topic_tools/CMakeLists.txt index 4699dea1f..7d4895d06 100644 --- a/jsk_topic_tools/CMakeLists.txt +++ b/jsk_topic_tools/CMakeLists.txt @@ -2,8 +2,6 @@ cmake_minimum_required(VERSION 2.8.3) project(jsk_topic_tools) -add_compile_options(-std=c++11) - # Use ccache if installed to make it fast to generate object files if (CMAKE_VERSION VERSION_LESS 3.4) find_program(CCACHE_FOUND ccache) 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 0657d29d6..075ac3897 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 @@ -86,7 +86,7 @@ namespace jsk_topic_tools virtual void onInitPostProcess(); /** @brief - * callback function which is called when new subscriber come + * callback function which is called when new subscriber connects or disconnects */ virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub); @@ -192,9 +192,17 @@ namespace jsk_topic_tools { boost::mutex::scoped_lock lock(connection_mutex_); ros::SubscriberStatusCallback connect_cb +#if __cplusplus < 201100L = boost::bind(&ConnectionBasedNodelet::connectionCallback, this, _1); +#else + = [this](auto& pub){ connectionCallback(pub); }; +#endif ros::SubscriberStatusCallback disconnect_cb +#if __cplusplus < 201100L = boost::bind(&ConnectionBasedNodelet::connectionCallback, this, _1); +#else + = [this](auto& pub){ connectionCallback(pub); }; +#endif ros::Publisher ret = nh.advertise(topic, queue_size, connect_cb, disconnect_cb, @@ -254,11 +262,19 @@ namespace jsk_topic_tools { boost::mutex::scoped_lock lock(connection_mutex_); image_transport::SubscriberStatusCallback connect_cb +#if __cplusplus < 201100L = boost::bind(&ConnectionBasedNodelet::imageConnectionCallback, this, _1); +#else + = [this](auto& pub){ imageConnectionCallback(pub); }; +#endif image_transport::SubscriberStatusCallback disconnect_cb +#if __cplusplus < 201100L = boost::bind(&ConnectionBasedNodelet::imageConnectionCallback, this, _1); +#else + = [this](auto& pub){ imageConnectionCallback(pub); }; +#endif image_transport::Publisher pub = image_transport::ImageTransport(nh).advertise( topic, 1, connect_cb, @@ -318,17 +334,33 @@ namespace jsk_topic_tools { boost::mutex::scoped_lock lock(connection_mutex_); image_transport::SubscriberStatusCallback connect_cb +#if __cplusplus < 201100L = boost::bind(&ConnectionBasedNodelet::cameraConnectionCallback, this, _1); +#else + = [this](auto& pub){ cameraConnectionCallback(pub); }; +#endif image_transport::SubscriberStatusCallback disconnect_cb +#if __cplusplus < 201100L = boost::bind(&ConnectionBasedNodelet::cameraConnectionCallback, this, _1); +#else + = [this](auto& pub){ cameraConnectionCallback(pub); }; +#endif ros::SubscriberStatusCallback info_connect_cb +#if __cplusplus < 201100L = boost::bind(&ConnectionBasedNodelet::cameraInfoConnectionCallback, this, _1); +#else + = [this](auto& pub){ cameraInfoConnectionCallback(pub); }; +#endif ros::SubscriberStatusCallback info_disconnect_cb +#if __cplusplus < 201100L = boost::bind(&ConnectionBasedNodelet::cameraInfoConnectionCallback, this, _1); +#else + = [this](auto& pub){ cameraInfoConnectionCallback(pub); }; +#endif image_transport::CameraPublisher pub = image_transport::ImageTransport(nh).advertiseCamera( topic, 1, diff --git a/jsk_topic_tools/include/jsk_topic_tools/constant_rate_throttle_nodelet.h b/jsk_topic_tools/include/jsk_topic_tools/constant_rate_throttle_nodelet.h index d1ab8e775..4da299844 100644 --- a/jsk_topic_tools/include/jsk_topic_tools/constant_rate_throttle_nodelet.h +++ b/jsk_topic_tools/include/jsk_topic_tools/constant_rate_throttle_nodelet.h @@ -7,7 +7,6 @@ #include #include #include -#include namespace jsk_topic_tools { diff --git a/jsk_topic_tools/src/block_nodelet.cpp b/jsk_topic_tools/src/block_nodelet.cpp index cf5534c39..1f9e2a60b 100644 --- a/jsk_topic_tools/src/block_nodelet.cpp +++ b/jsk_topic_tools/src/block_nodelet.cpp @@ -31,7 +31,7 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include "jsk_topic_tools/block_nodelet.h" #include diff --git a/jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp b/jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp index b0de6e9d1..f43a4ac54 100644 --- a/jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp +++ b/jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp @@ -11,7 +11,12 @@ namespace jsk_topic_tools msg_cached_ = boost::shared_ptr(new topic_tools::ShapeShifter()); srv_ = boost::make_shared >(pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind(&ConstantRateThrottle::configCallback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f +#if __cplusplus < 201100L + = boost::bind(&ConstantRateThrottle::configCallback, this, _1, _2); +#else + = [this](auto& config, auto level) {configCallback(config, level); }; +#endif srv_->setCallback(f); sub_.reset(new ros::Subscriber( @@ -62,7 +67,12 @@ namespace jsk_topic_tools boost::mutex::scoped_lock lock(mutex_); if (!advertised_) { sub_->shutdown(); - ros::SubscriberStatusCallback connect_cb = boost::bind(&ConstantRateThrottle::connectionCallback, this, _1); + ros::SubscriberStatusCallback connect_cb +#if __cplusplus < 201100L + = boost::bind(&ConstantRateThrottle::connectionCallback, this, _1); +#else + = [this](auto& pub){ connectionCallback(pub); }; +#endif ros::AdvertiseOptions opts("output", 1, msg->getMD5Sum(), msg->getDataType(), diff --git a/jsk_topic_tools/src/deprecated_relay_nodelet.cpp b/jsk_topic_tools/src/deprecated_relay_nodelet.cpp index ff66e106a..adfda15f2 100644 --- a/jsk_topic_tools/src/deprecated_relay_nodelet.cpp +++ b/jsk_topic_tools/src/deprecated_relay_nodelet.cpp @@ -33,7 +33,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include "jsk_topic_tools/deprecated_relay.h" #include "jsk_topic_tools/log_utils.h" namespace jsk_topic_tools diff --git a/jsk_topic_tools/src/diagnostic_nodelet.cpp b/jsk_topic_tools/src/diagnostic_nodelet.cpp index 14e5bd0ca..365968ec0 100644 --- a/jsk_topic_tools/src/diagnostic_nodelet.cpp +++ b/jsk_topic_tools/src/diagnostic_nodelet.cpp @@ -56,10 +56,15 @@ namespace jsk_topic_tools diagnostic_updater_->setHardwareID(getName()); diagnostic_updater_->add( getName(), +#if __cplusplus < 201100L boost::bind( &DiagnosticNodelet::updateDiagnostic, this, - _1)); + _1) +#else + [this](auto& stat){ updateDiagnostic(stat); } +#endif + ); bool use_warn; nh_->param("/diagnostic_nodelet/use_warn", use_warn, false); diff --git a/jsk_topic_tools/src/hz_measure_nodelet.cpp b/jsk_topic_tools/src/hz_measure_nodelet.cpp index 2a378ce6d..f859fe9b9 100644 --- a/jsk_topic_tools/src/hz_measure_nodelet.cpp +++ b/jsk_topic_tools/src/hz_measure_nodelet.cpp @@ -34,7 +34,7 @@ #include #include -#include +#include #include "jsk_topic_tools/hz_measure_nodelet.h" #include "std_msgs/Float32.h" @@ -78,9 +78,13 @@ namespace jsk_topic_tools diagnostic_updater_.reset(new TimeredDiagnosticUpdater(pnh_, ros::Duration(1.0))); diagnostic_updater_->setHardwareID(getName()); +#if __cplusplus < 201100L diagnostic_updater_->add(getName(), boost::bind(&HzMeasure::updateDiagnostic, this, _1)); +#else + diagnostic_updater_->add(getName(), [this](auto& stat){ updateDiagnostic(stat); }); +#endif diagnostic_updater_->start(); hz_pub_ = pnh_.advertise("output", 1); diff --git a/jsk_topic_tools/src/lightweight_throttle_nodelet.cpp b/jsk_topic_tools/src/lightweight_throttle_nodelet.cpp index 1caf36c97..dd59d9551 100644 --- a/jsk_topic_tools/src/lightweight_throttle_nodelet.cpp +++ b/jsk_topic_tools/src/lightweight_throttle_nodelet.cpp @@ -45,7 +45,11 @@ namespace jsk_topic_tools srv_ = boost::make_shared >(pnh_); dynamic_reconfigure::Server::CallbackType f = +#if __cplusplus < 201100L boost::bind(&LightweightThrottle::configCallback, this, _1, _2); +#else + [this](auto& config, auto level){ configCallback(config, level); }; +#endif srv_->setCallback(f); // Subscribe input topic at first in order to decide @@ -95,7 +99,11 @@ namespace jsk_topic_tools // This section should be called once sub_->shutdown(); // Shutdown before advertising topic ros::SubscriberStatusCallback connect_cb +#if __cplusplus < 201100L = boost::bind(&LightweightThrottle::connectionCallback, this, _1); +#else + = [this](auto& pub){ connectionCallback(pub); }; +#endif ros::AdvertiseOptions opts("output", 1, msg->getMD5Sum(), msg->getDataType(), @@ -120,6 +128,6 @@ namespace jsk_topic_tools } } -#include +#include typedef jsk_topic_tools::LightweightThrottle LightweightThrottle; PLUGINLIB_EXPORT_CLASS(LightweightThrottle, nodelet::Nodelet) diff --git a/jsk_topic_tools/src/mux_nodelet.cpp b/jsk_topic_tools/src/mux_nodelet.cpp index 3d2575c9a..fe27fcff2 100644 --- a/jsk_topic_tools/src/mux_nodelet.cpp +++ b/jsk_topic_tools/src/mux_nodelet.cpp @@ -31,7 +31,7 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include "jsk_topic_tools/mux_nodelet.h" #include #include "jsk_topic_tools/rosparam_utils.h" @@ -194,7 +194,11 @@ namespace jsk_topic_tools { if (!advertised_) { // first time ros::SubscriberStatusCallback connect_cb +#if __cplusplus < 201100L = boost::bind(&MUX::connectCb, this, _1); +#else + = [this](auto& pub){ connectCb(pub); }; +#endif ros::AdvertiseOptions opts("output", 1, msg->getMD5Sum(), msg->getDataType(), diff --git a/jsk_topic_tools/src/passthrough_nodelet.cpp b/jsk_topic_tools/src/passthrough_nodelet.cpp index ad7a4276f..0c8b5adee 100644 --- a/jsk_topic_tools/src/passthrough_nodelet.cpp +++ b/jsk_topic_tools/src/passthrough_nodelet.cpp @@ -31,7 +31,7 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include "jsk_topic_tools/passthrough_nodelet.h" namespace jsk_topic_tools diff --git a/jsk_topic_tools/src/relay_nodelet.cpp b/jsk_topic_tools/src/relay_nodelet.cpp index 4ff3fb8f7..d26bd254a 100644 --- a/jsk_topic_tools/src/relay_nodelet.cpp +++ b/jsk_topic_tools/src/relay_nodelet.cpp @@ -31,7 +31,7 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#include +#include #include "jsk_topic_tools/relay_nodelet.h" namespace jsk_topic_tools @@ -50,8 +50,12 @@ namespace jsk_topic_tools diagnostic_updater_->setHardwareID(getName()); diagnostic_updater_->add( getName() + "::Relay", +#if __cplusplus < 201100L boost::bind( &Relay::updateDiagnostic, this, _1)); +#else + [this](auto& stat){ updateDiagnostic(stat); }); +#endif double vital_rate; pnh_.param("vital_rate", vital_rate, 1.0); vital_checker_.reset( diff --git a/jsk_topic_tools/src/snapshot_nodelet.cpp b/jsk_topic_tools/src/snapshot_nodelet.cpp index 84770b786..e5ac57308 100644 --- a/jsk_topic_tools/src/snapshot_nodelet.cpp +++ b/jsk_topic_tools/src/snapshot_nodelet.cpp @@ -101,5 +101,5 @@ namespace jsk_topic_tools } -#include +#include PLUGINLIB_EXPORT_CLASS (jsk_topic_tools::Snapshot, nodelet::Nodelet); diff --git a/jsk_topic_tools/src/stealth_relay_nodelet.cpp b/jsk_topic_tools/src/stealth_relay_nodelet.cpp index 4a01d0915..7b309839e 100644 --- a/jsk_topic_tools/src/stealth_relay_nodelet.cpp +++ b/jsk_topic_tools/src/stealth_relay_nodelet.cpp @@ -69,7 +69,11 @@ namespace jsk_topic_tools srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = +#if __cplusplus < 201100L boost::bind(&StealthRelay::configCallback, this, _1, _2); +#else + [this](auto& config, auto level){ configCallback(config, level); }; +#endif srv_->setCallback(f); /* To advertise output topic as the same type of input topic, @@ -197,6 +201,6 @@ namespace jsk_topic_tools } } -#include +#include typedef jsk_topic_tools::StealthRelay StealthRelay; PLUGINLIB_EXPORT_CLASS(StealthRelay, nodelet::Nodelet) diff --git a/jsk_topic_tools/src/string_relay_nodelet.cpp b/jsk_topic_tools/src/string_relay_nodelet.cpp index 1cf270797..fc3ac622d 100644 --- a/jsk_topic_tools/src/string_relay_nodelet.cpp +++ b/jsk_topic_tools/src/string_relay_nodelet.cpp @@ -60,6 +60,6 @@ namespace jsk_topic_tools } } -#include +#include typedef jsk_topic_tools::StringRelay StringRelay; PLUGINLIB_EXPORT_CLASS(StringRelay, nodelet::Nodelet) diff --git a/jsk_topic_tools/src/synchronized_throttle_nodelet.cpp b/jsk_topic_tools/src/synchronized_throttle_nodelet.cpp index c58f93c54..995a6db6b 100644 --- a/jsk_topic_tools/src/synchronized_throttle_nodelet.cpp +++ b/jsk_topic_tools/src/synchronized_throttle_nodelet.cpp @@ -39,6 +39,27 @@ #include +#if BOOST_VERSION < 106000 // since 1.60.0, boost uses placeholders namesapce for _1,_2... +#ifndef BOOST_PLAEHOLDERS +#define BOOST_PLAEHOLDERS +namespace boost +{ + namespace placeholders + { + extern boost::arg<1> _1; + extern boost::arg<2> _2; + extern boost::arg<3> _3; + extern boost::arg<4> _4; + extern boost::arg<5> _5; + extern boost::arg<6> _6; + extern boost::arg<7> _7; + extern boost::arg<8> _8; + extern boost::arg<9> _9; + } // namespace placeholders +} // namespace boost +#endif // BOOST_PLAEHOLDERS +#endif // BOOST_VERSION < 106000 + namespace jsk_topic_tools { @@ -66,7 +87,11 @@ void SynchronizedThrottle::onInit() srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = +#if __cplusplus < 201100L boost::bind(&SynchronizedThrottle::configCallback, this, _1, _2); +#else + [this](auto& config, auto level){ configCallback(config, level); }; +#endif srv_->setCallback(f); // message_filter supports 2~8 input topics @@ -89,7 +114,12 @@ void SynchronizedThrottle::onInit() { check_sub_[i] = pnh_->subscribe( input_topics_[i], 1, - boost::bind(&SynchronizedThrottle::checkCallback, this, _1, i)); +#if __cplusplus < 201100L + boost::bind(&SynchronizedThrottle::checkCallback, this, _1, i) +#else + [this,i](auto& msg){ checkCallback(msg, i); } +#endif + ); sub_[i].reset(new message_filters::Subscriber()); } @@ -178,7 +208,12 @@ void SynchronizedThrottle::subscribe() if (n_topics < MAX_SYNC_NUM) { sub_[0]->registerCallback( - boost::bind(&SynchronizedThrottle::fillNullMessage, this, _1)); +#if __cplusplus < 201100L + boost::bind(&SynchronizedThrottle::fillNullMessage, this, _1) +#else + [this](auto& msg){ fillNullMessage(msg); } +#endif + ); } if (approximate_sync_) @@ -220,8 +255,16 @@ void SynchronizedThrottle::subscribe() return; } async_->registerCallback( - boost::bind(&SynchronizedThrottle::inputCallback, this, - _1, _2, _3, _4, _5, _6, _7, _8)); + boost::bind(&SynchronizedThrottle::inputCallback, this, + boost::placeholders::_1, + boost::placeholders::_2, + boost::placeholders::_3, + boost::placeholders::_4, + boost::placeholders::_5, + boost::placeholders::_6, + boost::placeholders::_7, + boost::placeholders::_8)); + } else { sync_ = boost::make_shared >(queue_size_); @@ -260,8 +303,15 @@ void SynchronizedThrottle::subscribe() return; } sync_->registerCallback( - boost::bind(&SynchronizedThrottle::inputCallback, this, - _1, _2, _3, _4, _5, _6, _7, _8)); + boost::bind(&SynchronizedThrottle::inputCallback, this, + boost::placeholders::_1, + boost::placeholders::_2, + boost::placeholders::_3, + boost::placeholders::_4, + boost::placeholders::_5, + boost::placeholders::_6, + boost::placeholders::_7, + boost::placeholders::_8)); } } @@ -427,6 +477,6 @@ void SynchronizedThrottle::inputCallback( } // jsk_topic_tools -#include +#include typedef jsk_topic_tools::SynchronizedThrottle SynchronizedThrottle; PLUGINLIB_EXPORT_CLASS(SynchronizedThrottle, nodelet::Nodelet) diff --git a/jsk_topic_tools/src/tests/test_log_utils_nodelet.cpp b/jsk_topic_tools/src/tests/test_log_utils_nodelet.cpp index d789cb392..62a1bd909 100644 --- a/jsk_topic_tools/src/tests/test_log_utils_nodelet.cpp +++ b/jsk_topic_tools/src/tests/test_log_utils_nodelet.cpp @@ -45,5 +45,5 @@ class LogUtils : public nodelet::Nodelet } // namespace jsk_topic_tools -#include +#include PLUGINLIB_EXPORT_CLASS(jsk_topic_tools::test::LogUtils, nodelet::Nodelet) diff --git a/jsk_topic_tools/src/timered_diagnostic_updater.cpp b/jsk_topic_tools/src/timered_diagnostic_updater.cpp index 93c07f9e7..c3b384e9d 100644 --- a/jsk_topic_tools/src/timered_diagnostic_updater.cpp +++ b/jsk_topic_tools/src/timered_diagnostic_updater.cpp @@ -43,10 +43,13 @@ namespace jsk_topic_tools diagnostic_updater_(new diagnostic_updater::Updater) { timer_ = nh.createTimer( - timer_duration, boost::bind( - &TimeredDiagnosticUpdater::timerCallback, - this, - _1)); + timer_duration, +#if __cplusplus < 201100L + boost::bind(&TimeredDiagnosticUpdater::timerCallback,this,_1) +#else + [this](auto& event){ timerCallback(event); } +#endif + ); timer_.stop(); } diff --git a/jsk_topic_tools/src/topic_buffer_client.cpp b/jsk_topic_tools/src/topic_buffer_client.cpp index f4aaafacf..5ab8db2d3 100644 --- a/jsk_topic_tools/src/topic_buffer_client.cpp +++ b/jsk_topic_tools/src/topic_buffer_client.cpp @@ -200,8 +200,13 @@ int main(int argc, char **argv) pub_info->advertised = false; 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, boost::bind(in_cb, _1, pub_info))); - + pub_info->sub = new ros::Subscriber(n.subscribe(pub_info->topic_name+string("_update"), 10, +#if __cplusplus < 201100L + boost::bind(in_cb, _1, pub_info) +#else + [pub_info](auto& msg){ in_cb(msg, pub_info); } +#endif + )); g_pubs.push_back(pub_info); } diff --git a/jsk_topic_tools/src/topic_buffer_server.cpp b/jsk_topic_tools/src/topic_buffer_server.cpp index 4358e4ab2..b79b0f2a5 100644 --- a/jsk_topic_tools/src/topic_buffer_server.cpp +++ b/jsk_topic_tools/src/topic_buffer_server.cpp @@ -219,8 +219,13 @@ int main(int argc, char **argv) sub_info->advertised = false; 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, boost::bind(in_cb, _1, sub_info))); - + sub_info->sub = new ros::Subscriber(n.subscribe(sub_info->topic_name, 10, +#if __cplusplus < 201100L + boost::bind(in_cb, _1, sub_info) +#else + [sub_info](auto& msg){ in_cb(msg, sub_info); } +#endif + )); // waiting for all topics are publisherd while (sub_info->sub->getNumPublishers() == 0 ) { ros::Duration(1.0).sleep(); diff --git a/jsk_topic_tools/src/vital_checker_nodelet.cpp b/jsk_topic_tools/src/vital_checker_nodelet.cpp index d39a0c7cd..395a31e6b 100644 --- a/jsk_topic_tools/src/vital_checker_nodelet.cpp +++ b/jsk_topic_tools/src/vital_checker_nodelet.cpp @@ -86,6 +86,6 @@ namespace jsk_topic_tools } } -#include +#include typedef jsk_topic_tools::VitalCheckerNodelet VitalCheckerNodelet; PLUGINLIB_EXPORT_CLASS(VitalCheckerNodelet, nodelet::Nodelet)