From b3768dad78a341f9c9617dfe74e3302f76b5687f Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 14 Apr 2020 08:21:02 -0700 Subject: [PATCH] updates since changes to message_info in rclcpp Signed-off-by: William Woodall --- include/ros1_bridge/factory.hpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/include/ros1_bridge/factory.hpp b/include/ros1_bridge/factory.hpp index d58a38f9..e41b207d 100755 --- a/include/ros1_bridge/factory.hpp +++ b/include/ros1_bridge/factory.hpp @@ -117,7 +117,7 @@ class Factory : public FactoryInterface rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr) { std::function< - void(const typename ROS2_T::SharedPtr msg, const rmw_message_info_t & msg_info)> callback; + void(const typename ROS2_T::SharedPtr msg, const rclcpp::MessageInfo & msg_info)> callback; callback = std::bind( &Factory::ros2_callback, std::placeholders::_1, std::placeholders::_2, ros1_pub, ros1_type_name_, ros2_type_name_, node->get_logger(), ros2_pub); @@ -190,7 +190,7 @@ class Factory : public FactoryInterface static void ros2_callback( typename ROS2_T::SharedPtr ros2_msg, - const rmw_message_info_t & msg_info, + const rclcpp::MessageInfo & msg_info, ros::Publisher ros1_pub, const std::string & ros1_type_name, const std::string & ros2_type_name, @@ -199,7 +199,10 @@ class Factory : public FactoryInterface { if (ros2_pub) { bool result = false; - auto ret = rmw_compare_gids_equal(&msg_info.publisher_gid, &ros2_pub->get_gid(), &result); + auto ret = rmw_compare_gids_equal( + &msg_info.get_rmw_message_info().publisher_gid, + &ros2_pub->get_gid(), + &result); if (ret == RMW_RET_OK) { if (result) { // message GID equals to bridge's ROS2 publisher GID return; // do not publish messages from bridge itself