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

use hardcoded QoS (keep all, transient local) for /tf_static topic in dynamic_bridge #282

Merged
merged 7 commits into from Aug 19, 2020
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
23 changes: 23 additions & 0 deletions include/ros1_bridge/bridge.hpp
Expand Up @@ -83,6 +83,17 @@ create_bridge_from_1_to_2(
const std::string & ros2_topic_name,
size_t publisher_queue_size);

Bridge1to2Handles
create_bridge_from_1_to_2(
ros::NodeHandle ros1_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t subscriber_queue_size,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
const rclcpp::QoS & publisher_qos);

Bridge2to1Handles
create_bridge_from_2_to_1(
rclcpp::Node::SharedPtr ros2_node,
Expand All @@ -95,6 +106,18 @@ create_bridge_from_2_to_1(
size_t publisher_queue_size,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr);

Bridge2to1Handles
create_bridge_from_2_to_1(
rclcpp::Node::SharedPtr ros2_node,
ros::NodeHandle ros1_node,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
const rclcpp::QoS & subscriber_qos,
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t publisher_queue_size,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr);

BridgeHandles
create_bidirectional_bridge(
ros::NodeHandle ros1_node,
Expand Down
33 changes: 27 additions & 6 deletions include/ros1_bridge/factory.hpp
Expand Up @@ -70,6 +70,15 @@ class Factory : public FactoryInterface
{
auto qos = rclcpp::QoS(rclcpp::KeepAll());
qos.get_rmw_qos_profile() = qos_profile;
return create_ros2_publisher(node, topic_name, qos);
}

rclcpp::PublisherBase::SharedPtr
create_ros2_publisher(
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
const rclcpp::QoS & qos)
{
return node->create_publisher<ROS2_T>(topic_name, qos);
}

Expand Down Expand Up @@ -103,9 +112,9 @@ class Factory : public FactoryInterface
ros::Publisher ros1_pub,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr)
{
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_sensor_data;
custom_qos_profile.depth = queue_size;
return create_ros2_subscriber(node, topic_name, custom_qos_profile, ros1_pub, ros2_pub);
auto qos = rclcpp::SensorDataQoS();
qos.keep_last(queue_size);
dirk-thomas marked this conversation as resolved.
Show resolved Hide resolved
return create_ros2_subscriber(node, topic_name, qos, ros1_pub, ros2_pub);
}

rclcpp::SubscriptionBase::SharedPtr
Expand All @@ -115,18 +124,30 @@ class Factory : public FactoryInterface
const rmw_qos_profile_t & qos,
ros::Publisher ros1_pub,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr)
{
auto rclcpp_qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos));
rclcpp_qos.get_rmw_qos_profile() = qos;
return create_ros2_subscriber(
node, topic_name, rclcpp_qos, ros1_pub, ros2_pub);
}

rclcpp::SubscriptionBase::SharedPtr
create_ros2_subscriber(
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
const rclcpp::QoS & qos,
ros::Publisher ros1_pub,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr)
{
std::function<
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);
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, options);
topic_name, qos, callback, options);
}

void convert_1_to_2(const void * ros1_msg, void * ros2_msg) override
Expand Down
16 changes: 16 additions & 0 deletions include/ros1_bridge/factory_interface.hpp
Expand Up @@ -67,6 +67,13 @@ class FactoryInterface
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile) = 0;

virtual
rclcpp::PublisherBase::SharedPtr
create_ros2_publisher(
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
const rclcpp::QoS & qos) = 0;

virtual
ros::Subscriber
create_ros1_subscriber(
Expand Down Expand Up @@ -94,6 +101,15 @@ class FactoryInterface
ros::Publisher ros1_pub,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr) = 0;

virtual
rclcpp::SubscriptionBase::SharedPtr
create_ros2_subscriber(
rclcpp::Node::SharedPtr node,
const std::string & topic_name,
const rclcpp::QoS & qos,
ros::Publisher ros1_pub,
rclcpp::PublisherBase::SharedPtr ros2_pub = nullptr) = 0;

virtual
void
convert_1_to_2(const void * ros1_msg, void * ros2_msg) = 0;
Expand Down
52 changes: 50 additions & 2 deletions src/bridge.cpp
Expand Up @@ -30,10 +30,32 @@ create_bridge_from_1_to_2(
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
size_t publisher_queue_size)
{
return create_bridge_from_1_to_2(
ros1_node,
ros2_node,
ros1_type_name,
ros1_topic_name,
subscriber_queue_size,
ros2_type_name,
ros2_topic_name,
rclcpp::QoS(rclcpp::KeepLast(publisher_queue_size)));
}

Bridge1to2Handles
create_bridge_from_1_to_2(
ros::NodeHandle ros1_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t subscriber_queue_size,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
const rclcpp::QoS & publisher_qos)
{
auto factory = get_factory(ros1_type_name, ros2_type_name);
auto ros2_pub = factory->create_ros2_publisher(
ros2_node, ros2_topic_name, publisher_queue_size);
ros2_node, ros2_topic_name, publisher_qos);

auto ros1_sub = factory->create_ros1_subscriber(
ros1_node, ros1_topic_name, subscriber_queue_size, ros2_pub, ros2_node->get_logger());
Expand All @@ -55,13 +77,39 @@ create_bridge_from_2_to_1(
const std::string & ros1_topic_name,
size_t publisher_queue_size,
rclcpp::PublisherBase::SharedPtr ros2_pub)
{
auto subscriber_qos = rclcpp::SensorDataQoS();
subscriber_qos.keep_last(subscriber_queue_size);
return create_bridge_from_2_to_1(
ros2_node,
ros1_node,
ros2_type_name,
ros2_topic_name,
subscriber_qos,
ros1_type_name,
ros1_topic_name,
publisher_queue_size,
ros2_pub);
}

Bridge2to1Handles
create_bridge_from_2_to_1(
rclcpp::Node::SharedPtr ros2_node,
ros::NodeHandle ros1_node,
const std::string & ros2_type_name,
const std::string & ros2_topic_name,
const rclcpp::QoS & subscriber_qos,
const std::string & ros1_type_name,
const std::string & ros1_topic_name,
size_t publisher_queue_size,
rclcpp::PublisherBase::SharedPtr ros2_pub)
{
auto factory = get_factory(ros1_type_name, ros2_type_name);
auto ros1_pub = factory->create_ros1_publisher(
ros1_node, ros1_topic_name, publisher_queue_size);

auto ros2_sub = factory->create_ros2_subscriber(
ros2_node, ros2_topic_name, subscriber_queue_size, ros1_pub, ros2_pub);
ros2_node, ros2_topic_name, subscriber_qos, ros1_pub, ros2_pub);

Bridge2to1Handles handles;
handles.ros2_subscriber = ros2_sub;
Expand Down
7 changes: 6 additions & 1 deletion src/dynamic_bridge.cpp
Expand Up @@ -183,11 +183,16 @@ void update_bridge(
bridge.ros1_type_name = ros1_type_name;
bridge.ros2_type_name = ros2_type_name;

auto ros2_publisher_qos = rclcpp::QoS(rclcpp::KeepLast(10));
if (topic_name == "/tf_static") {
ros2_publisher_qos.keep_all();
ros2_publisher_qos.transient_local();
}
try {
bridge.bridge_handles = ros1_bridge::create_bridge_from_1_to_2(
ros1_node, ros2_node,
bridge.ros1_type_name, topic_name, 10,
bridge.ros2_type_name, topic_name, 10);
bridge.ros2_type_name, topic_name, ros2_publisher_qos);
} catch (std::runtime_error & e) {
fprintf(
stderr,
Expand Down