Skip to content

Commit

Permalink
Merge pull request #1773 from k-okada/ros_o
Browse files Browse the repository at this point in the history
add test to compile on 22.04, see #1770
  • Loading branch information
k-okada authored Dec 15, 2022
2 parents 7697952 + 4dd2c68 commit dbefb4c
Show file tree
Hide file tree
Showing 27 changed files with 274 additions and 46 deletions.
76 changes: 75 additions & 1 deletion .github/workflows/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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/[email protected]

- 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
2 changes: 1 addition & 1 deletion jsk_network_tools/setup.py
Original file line number Diff line number Diff line change
@@ -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
Expand Down
6 changes: 0 additions & 6 deletions jsk_ros_patch/image_view2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
4 changes: 4 additions & 0 deletions jsk_ros_patch/image_view2/image_view2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,11 @@ namespace image_view2{

srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(local_nh);
dynamic_reconfigure::Server<Config>::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);
}

Expand Down
25 changes: 23 additions & 2 deletions jsk_ros_patch/image_view2/points_rectangle_extractor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,27 @@
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PolygonStamped.h>

#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,
Expand Down Expand Up @@ -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);
}
Expand Down
8 changes: 6 additions & 2 deletions jsk_tilt_laser/src/spin_laser_snapshotter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
}

Expand Down
2 changes: 0 additions & 2 deletions jsk_topic_tools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down Expand Up @@ -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<T>(topic, queue_size,
connect_cb,
disconnect_cb,
Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
#include <dynamic_reconfigure/server.h>
#include <jsk_topic_tools/ConstantRateThrottleConfig.h>
#include <topic_tools/shape_shifter.h>
#include <mutex>

namespace jsk_topic_tools
{
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/block_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include "jsk_topic_tools/block_nodelet.h"

#include <ros/advertise_options.h>
Expand Down
14 changes: 12 additions & 2 deletions jsk_topic_tools/src/constant_rate_throttle_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,12 @@ namespace jsk_topic_tools
msg_cached_ = boost::shared_ptr<topic_tools::ShapeShifter>(new topic_tools::ShapeShifter());

srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f = boost::bind(&ConstantRateThrottle::configCallback, this, _1, _2);
dynamic_reconfigure::Server<Config>::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(
Expand Down Expand Up @@ -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(),
Expand Down
2 changes: 1 addition & 1 deletion jsk_topic_tools/src/deprecated_relay_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include "jsk_topic_tools/deprecated_relay.h"
#include "jsk_topic_tools/log_utils.h"
namespace jsk_topic_tools
Expand Down
7 changes: 6 additions & 1 deletion jsk_topic_tools/src/diagnostic_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
6 changes: 5 additions & 1 deletion jsk_topic_tools/src/hz_measure_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

#include <limits>
#include <boost/format.hpp>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include "jsk_topic_tools/hz_measure_nodelet.h"

#include "std_msgs/Float32.h"
Expand Down Expand Up @@ -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<std_msgs::Float32>("output", 1);
Expand Down
10 changes: 9 additions & 1 deletion jsk_topic_tools/src/lightweight_throttle_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,11 @@ namespace jsk_topic_tools

srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(pnh_);
dynamic_reconfigure::Server<Config>::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
Expand Down Expand Up @@ -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(),
Expand All @@ -120,6 +128,6 @@ namespace jsk_topic_tools
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
typedef jsk_topic_tools::LightweightThrottle LightweightThrottle;
PLUGINLIB_EXPORT_CLASS(LightweightThrottle, nodelet::Nodelet)
Loading

0 comments on commit dbefb4c

Please sign in to comment.