Skip to content

Commit

Permalink
updates since changes to message_info in rclcpp (#253)
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood authored Apr 14, 2020
1 parent 0c7c175 commit 373453f
Showing 1 changed file with 6 additions and 3 deletions.
9 changes: 6 additions & 3 deletions include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ROS1_T, ROS2_T>::ros2_callback, std::placeholders::_1, std::placeholders::_2,
ros1_pub, ros1_type_name_, ros2_type_name_, node->get_logger(), ros2_pub);
Expand Down Expand Up @@ -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,
Expand All @@ -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
Expand Down

0 comments on commit 373453f

Please sign in to comment.