Skip to content

Commit

Permalink
fix build by passing options (#192)
Browse files Browse the repository at this point in the history
Signed-off-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>
  • Loading branch information
dirk-thomas authored May 9, 2019
1 parent 9184ce8 commit 3bc78e8
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 2 deletions.
4 changes: 3 additions & 1 deletion include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,8 +123,10 @@ class Factory : public FactoryInterface
ros1_pub, ros1_type_name_, ros2_type_name_, node->get_logger(), ros2_pub);
auto rclcpp_qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos));
rclcpp_qos.get_rmw_qos_profile() = qos;
rclcpp::SubscriptionOptions options;
options.ignore_local_publications = true;
return node->create_subscription<ROS2_T>(
topic_name, rclcpp_qos, callback, nullptr, true);
topic_name, rclcpp_qos, callback, options);
}

void convert_1_to_2(const void * ros1_msg, void * ros2_msg) override
Expand Down
4 changes: 3 additions & 1 deletion src/simple_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,10 @@ int main(int argc, char * argv[])
"chatter", 10, ros1ChatterCallback);

// ROS 2 subscriber
rclcpp::SubscriptionOptions options;
options.ignore_local_publications = true;
auto ros2_sub = ros2_node->create_subscription<std_msgs::msg::String>(
"chatter", rclcpp::SensorDataQoS(), ros2ChatterCallback, nullptr, true);
"chatter", rclcpp::SensorDataQoS(), ros2ChatterCallback, options);

// ROS 1 asynchronous spinner
ros::AsyncSpinner async_spinner(1);
Expand Down

0 comments on commit 3bc78e8

Please sign in to comment.