Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Updated deprecated message filter headers #1012

Merged
merged 8 commits into from
Jul 22, 2024
Merged
Show file tree
Hide file tree
Changes from 7 commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 34 additions & 1 deletion .github/workflows/basic-build-ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ jobs:
image: osrf/ros2:testing
steps:
- name: Checkout repo
uses: actions/checkout@v2
uses: actions/checkout@v4
- name: Create Workspace
run: |
mkdir src_tmp
Expand All @@ -35,3 +35,36 @@ jobs:
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
colcon test; \
colcon test-result --verbose'
build-rolling-testing:
runs-on: ubuntu-latest
strategy:
fail-fast: false
container:
image: osrf/ros2:testing
steps:
- name: Checkout repo
uses: actions/checkout@v4
- name: Create Workspace
run: |
mkdir src_tmp
mv `find -maxdepth 1 -not -name . -not -name src_tmp` src_tmp/
mv src_tmp/ src/
- name: Install Prerequisites
run: |
apt update -qq
apt install -qq -y lsb-release wget curl gnupg2 git
curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-testing-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-testing-archive-keyring.gpg] http://packages.ros.org/ros2-testing/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | tee /etc/apt/sources.list.d/ros2.list > /dev/null
apt-get update && apt-get upgrade -q -y
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
apt-get update && apt-get upgrade -y && rosdep update; \
rosdep install --from-paths src --ignore-src -y'
- name: Build Workspace
run: |
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
colcon build'
- name: Run Tests
run: |
bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \
colcon test; \
colcon test-result --verbose'
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@

#include "depth_image_proc/visibility.h"
#include "image_geometry/pinhole_camera_model.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/synchronizer.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "message_filters/synchronizer.hpp"

#include <image_transport/subscriber_filter.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,9 @@
#include <vector>

#include "depth_image_proc/visibility.h"
#include "message_filters/subscriber.h"
#include "message_filters/synchronizer.h"
#include "message_filters/sync_policies/exact_time.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/synchronizer.hpp"
#include "message_filters/sync_policies/exact_time.hpp"

#include <image_transport/subscriber_filter.hpp>
#include <opencv2/core/mat.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@

#include "depth_image_proc/visibility.h"
#include "image_geometry/pinhole_camera_model.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/synchronizer.h"
#include "message_filters/sync_policies/exact_time.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/synchronizer.hpp"
#include "message_filters/sync_policies/exact_time.hpp"
#include "message_filters/sync_policies/approximate_time.hpp"

#include <image_transport/image_transport.hpp>
#include <image_transport/subscriber_filter.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,10 +40,10 @@

#include "depth_image_proc/visibility.h"
#include "image_geometry/pinhole_camera_model.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/synchronizer.h"
#include "message_filters/sync_policies/exact_time.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/synchronizer.hpp"
#include "message_filters/sync_policies/exact_time.hpp"
#include "message_filters/sync_policies/approximate_time.hpp"

#include <opencv2/core/mat.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down
4 changes: 2 additions & 2 deletions depth_image_proc/src/disparity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#include <string>

#include "depth_image_proc/visibility.h"
#include "message_filters/subscriber.h"
#include "message_filters/time_synchronizer.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/time_synchronizer.hpp"

#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.hpp>
Expand Down
6 changes: 3 additions & 3 deletions depth_image_proc/src/register.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@
#include "Eigen/Geometry"
#include "depth_image_proc/visibility.h"
#include "image_geometry/pinhole_camera_model.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/synchronizer.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/synchronizer.hpp"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"

Expand Down
6 changes: 3 additions & 3 deletions image_view/include/image_view/stereo_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,9 +53,9 @@
#include <mutex>
#include <string>

#include "message_filters/subscriber.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/sync_policies/exact_time.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "message_filters/sync_policies/exact_time.hpp"

#include <opencv2/highgui/highgui.hpp>

Expand Down
8 changes: 4 additions & 4 deletions image_view/src/stereo_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,10 @@
#include <string>

#include "cv_bridge/cv_bridge.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/sync_policies/exact_time.h"
#include "message_filters/synchronizer.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "message_filters/sync_policies/exact_time.hpp"
#include "message_filters/synchronizer.hpp"

#include "image_view/stereo_view_node.hpp"

Expand Down
10 changes: 5 additions & 5 deletions stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,11 @@

#include "cv_bridge/cv_bridge.hpp"
#include "image_geometry/stereo_camera_model.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/synchronizer.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/sync_policies/approximate_epsilon_time.h"
#include "message_filters/sync_policies/exact_time.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/synchronizer.hpp"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "message_filters/sync_policies/approximate_epsilon_time.hpp"
#include "message_filters/sync_policies/exact_time.hpp"

#include <stereo_image_proc/stereo_processor.hpp>

Expand Down
10 changes: 5 additions & 5 deletions stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,11 +35,11 @@
#include <string>

#include "image_geometry/stereo_camera_model.hpp"
#include "message_filters/subscriber.h"
#include "message_filters/synchronizer.h"
#include "message_filters/sync_policies/approximate_time.h"
#include "message_filters/sync_policies/approximate_epsilon_time.h"
#include "message_filters/sync_policies/exact_time.h"
#include "message_filters/subscriber.hpp"
#include "message_filters/synchronizer.hpp"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "message_filters/sync_policies/approximate_epsilon_time.hpp"
#include "message_filters/sync_policies/exact_time.hpp"
#include "rcutils/logging_macros.h"

#include <image_transport/camera_common.hpp>
Expand Down
Loading