diff --git a/.github/workflows/ros2-ci.yml b/.github/workflows/ros2-ci.yml index ced53c2..d8e43a5 100644 --- a/.github/workflows/ros2-ci.yml +++ b/.github/workflows/ros2-ci.yml @@ -11,7 +11,7 @@ jobs: matrix: include: - docker-image: "ubuntu:22.04" - ros-distro: "rolling" + ros-distro: "humble" container: image: ${{ matrix.docker-image }} steps: diff --git a/point_cloud_transport/include/point_cloud_transport/simple_publisher_plugin.hpp b/point_cloud_transport/include/point_cloud_transport/simple_publisher_plugin.hpp index ae9562d..2e4ba8e 100644 --- a/point_cloud_transport/include/point_cloud_transport/simple_publisher_plugin.hpp +++ b/point_cloud_transport/include/point_cloud_transport/simple_publisher_plugin.hpp @@ -114,7 +114,7 @@ class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin } void setParamCallback( - rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType + rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType param_change_callback) { if (simple_impl_) { diff --git a/point_cloud_transport/include/point_cloud_transport/simple_subscriber_plugin.hpp b/point_cloud_transport/include/point_cloud_transport/simple_subscriber_plugin.hpp index 792565d..7df6015 100644 --- a/point_cloud_transport/include/point_cloud_transport/simple_subscriber_plugin.hpp +++ b/point_cloud_transport/include/point_cloud_transport/simple_subscriber_plugin.hpp @@ -98,7 +98,7 @@ class SimpleSubscriberPlugin : public SubscriberPlugin } void setParamCallback( - rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType + rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType param_change_callback) { if (impl_) {